diff --git a/Gazebo_Distributed/.gitignore b/Gazebo_Distributed/.gitignore new file mode 100644 index 0000000..1899660 --- /dev/null +++ b/Gazebo_Distributed/.gitignore @@ -0,0 +1,2 @@ +build +.vscode \ No newline at end of file diff --git a/Gazebo_Distributed/gazebo/CMakeLists.txt b/Gazebo_Distributed/gazebo/CMakeLists.txt index 8066c5c..79899e9 100644 --- a/Gazebo_Distributed/gazebo/CMakeLists.txt +++ b/Gazebo_Distributed/gazebo/CMakeLists.txt @@ -131,5 +131,6 @@ set(headers gazebo.hh Master.hh Server.hh + countTime.hh ) gz_install_includes("" ${headers}) diff --git a/Gazebo_Distributed/gazebo/countTime.hh b/Gazebo_Distributed/gazebo/countTime.hh new file mode 100644 index 0000000..e304234 --- /dev/null +++ b/Gazebo_Distributed/gazebo/countTime.hh @@ -0,0 +1,13 @@ +#ifndef _COUNT_TIME_HH_ +#define _COUNT_TIME_HH_ + +#ifndef _WIN32 //Added by zenglei@2018-12-04 + #include +#endif + +#ifndef USE_COUNT_TIME + #define USE_COUNT_TIME +#endif + + +#endif diff --git a/Gazebo_Distributed/gazebo/physics/CMakeLists.txt b/Gazebo_Distributed/gazebo/physics/CMakeLists.txt index 7c1c667..e44a4a8 100644 --- a/Gazebo_Distributed/gazebo/physics/CMakeLists.txt +++ b/Gazebo_Distributed/gazebo/physics/CMakeLists.txt @@ -85,6 +85,8 @@ set (sources ${sources} World.cc WorldState.cc TcpCommunication.cc #zhangshuai 2019.03.19 + Distribution.cc #zhangshuai 2019.03.28 + GazeboID.cc #zhangshuai 2019.03.28 ) set (headers @@ -139,6 +141,8 @@ set (headers World.hh WorldState.hh TcpCommunication.hh #zhangshuai 2019.03.19 + Distribution.hh #zhangshuai 2019.03.28 + GazeboID.hh #zhangshuai 2019.03.28 ) set (physics_headers "" CACHE INTERNAL "physics headers" FORCE) diff --git a/Gazebo_Distributed/gazebo/physics/Distribution.cc b/Gazebo_Distributed/gazebo/physics/Distribution.cc new file mode 100644 index 0000000..981a4be --- /dev/null +++ b/Gazebo_Distributed/gazebo/physics/Distribution.cc @@ -0,0 +1,125 @@ +/* + * Copyright (C) 2019 AIRC 01 + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distribution under the License is distribution on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +/* Desc: Base class for distribution simualtion + * Author: Zhang Shuai + * Date: 28 March 2019 + */ + +#ifdef _WIN32 +// Ensure that Winsock2.h is included before Windows.h, which can get +// pulled in by anybody (e.g., Boost). +#include +#endif + +// #include +// #include +// #include + +#include +#include +// #include +// #include + +// #include "gazebo/util/OpenAL.hh" +// #include "gazebo/common/KeyFrame.hh" +// #include "gazebo/common/Animation.hh" +// #include "gazebo/common/Plugin.hh" +// #include "gazebo/common/Events.hh" +// #include "gazebo/common/Exception.hh" +// #include "gazebo/common/Console.hh" +// #include "gazebo/common/CommonTypes.hh" + +// #include "gazebo/physics/Gripper.hh" +// #include "gazebo/physics/Joint.hh" +// #include "gazebo/physics/JointController.hh" +// #include "gazebo/physics/Link.hh" +// #include "gazebo/physics/World.hh" +// #include "gazebo/physics/PhysicsEngine.hh" +// #include "gazebo/physics/Model.hh" +// #include "gazebo/physics/Contact.hh" + +// #include "gazebo/transport/Node.hh" + +#include "gazebo/physics/Distribution.hh" + +using namespace gazebo; +using namespace physics; + +////////////////////////////////////////////////// +Distribution::Distribution() +{ +} + +////////////////////////////////////////////////// +Distribution::~Distribution() +{ + this->Fini(); +} + +////////////////////////////////////////////////// +void Distribution::Load(sdf::ElementPtr _sdf) +{ + + if (_sdf) + this->sdf = _sdf; + + if (this->sdf->HasElement("gazebo_id")) + { + sdf::ElementPtr gazeboIdElem = this->sdf->GetElement("gazebo_id"); + while (gazeboIdElem) + { + GazeboIDPtr GazeboID(new physics::GazeboID()); + GazeboID->Load(gazeboIdElem); + this->gazeboIDs.push_back(GazeboID); + gazeboIdElem = gazeboIdElem->GetNextElement("gazebo_id"); + } + } +} + +////////////////////////////////////////////////// +unsigned int Distribution::GetGazeboID(unsigned int _i) +{ + return gazeboIDs[_i]->GetGazeboID(); +} + +////////////////////////////////////////////////// +GazeboIDPtr Distribution::GetGazeboIDPtr(unsigned int _gazeboID) +{ + GazeboIDPtr result; + for (unsigned int i = 0; i < this->GetGazeboCount(); i++) + { + if (this->GetGazeboID(i) == _gazeboID) + { + result = gazeboIDs[i]; + break; + } + } + return result; +} + +////////////////////////////////////////////////// +unsigned int Distribution::GetGazeboCount() +{ + return gazeboIDs.size(); +} + +////////////////////////////////////////////////// +void Distribution::Fini() +{ + this->gazeboIDs.clear(); + this->sdf.reset(); +} \ No newline at end of file diff --git a/Gazebo_Distributed/gazebo/physics/Distribution.hh b/Gazebo_Distributed/gazebo/physics/Distribution.hh new file mode 100644 index 0000000..ae56a6b --- /dev/null +++ b/Gazebo_Distributed/gazebo/physics/Distribution.hh @@ -0,0 +1,99 @@ +/* + * Copyright (C) 2019 AIRC 01 + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distribution under the License is distribution on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +/* Desc: Base class for distribution simualtion + * Author: Zhang Shuai + * Date: 28 March 2019 + */ + +#ifndef _DISTRIBUTION_HH_ +#define _DISTRIBUTION_HH_ + +#include +// #include +#include +#include +// #include + +#include + +// #include "gazebo/common/CommonTypes.hh" +#include "gazebo/physics/PhysicsTypes.hh" +// #include "gazebo/physics/ModelState.hh" +// #include "gazebo/physics/Entity.hh" +#include "gazebo/util/system.hh" + +#include "gazebo/physics/GazeboID.hh" + +namespace gazebo +{ +namespace physics +{ +/// \class Distribution Distribution.hh physics/physics.hh +/// \brief Distribution is used to store information about the distribution simulation. +class GZ_PHYSICS_VISIBLE Distribution +{ + /// \brief Constructor. + /// \param[in] _parent Parent object. +public: + explicit Distribution(); + + /// \brief Destructor. +public: + virtual ~Distribution(); + + /// \brief Load the Distribution. + /// \param[in] _sdf SDF parameters to load from. +public: + void Load(sdf::ElementPtr _sdf); + + /// \brief Get the gazebo ID of the specified gazebo. + /// \param[in] _i Number of the gazebo ID to get. + /// \return the gazebo ID of the specified gazebo. +public: + unsigned int GetGazeboID(unsigned int _i); + + /// \brief Get the gazebo ID pointer of the specified gazebo. + /// \param[in] _i Number of the gazebo ID to get. + /// \return the gazebo ID pointer of the specified gazebo. +public: + GazeboIDPtr GetGazeboIDPtr(unsigned int _gazeboID); + + /// \brief Get the number of Gazebos this Distribution has. + /// \return Number of Gazebos associated with this Distribution. +public: + unsigned int GetGazeboCount(); + + /// \brief Finialize the Distribution +public: + void Fini(); + + /// \brief The Distribution's current SDF description. +private: + sdf::ElementPtr sdf; + + // /// \brief Gazebos' ID in this distribution gazebo. + // private: + // std::vector gazeboIDs; + + /// \brief Gazebos' ID in this distribution gazebo. +private: + GazeboID_V gazeboIDs; +}; + +} // namespace physics +} // namespace gazebo +#endif diff --git a/Gazebo_Distributed/gazebo/physics/GazeboID.cc b/Gazebo_Distributed/gazebo/physics/GazeboID.cc new file mode 100644 index 0000000..98d94bc --- /dev/null +++ b/Gazebo_Distributed/gazebo/physics/GazeboID.cc @@ -0,0 +1,137 @@ +/* + * Copyright (C) 2019 AIRC 01 + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +/* Desc: Base class for distributed gazebo + * Author: Zhang Shuai + * Date: 28 March 2019 + */ + +#ifdef _WIN32 +// Ensure that Winsock2.h is included before Windows.h, which can get +// pulled in by anybody (e.g., Boost). +#include +#endif + +// #include +// #include +// #include + +// #include +// #include +// #include +// #include + +// #include "gazebo/util/OpenAL.hh" +// #include "gazebo/common/KeyFrame.hh" +// #include "gazebo/common/Animation.hh" +// #include "gazebo/common/Plugin.hh" +// #include "gazebo/common/Events.hh" +// #include "gazebo/common/Exception.hh" +// #include "gazebo/common/Console.hh" +// #include "gazebo/common/CommonTypes.hh" + +// #include "gazebo/physics/Gripper.hh" +// #include "gazebo/physics/Joint.hh" +// #include "gazebo/physics/JointController.hh" +// #include "gazebo/physics/Link.hh" +// #include "gazebo/physics/World.hh" +// #include "gazebo/physics/PhysicsEngine.hh" +// #include "gazebo/physics/Model.hh" +// #include "gazebo/physics/Contact.hh" + +// #include "gazebo/transport/Node.hh" + +#include "gazebo/physics/GazeboID.hh" + +using namespace gazebo; +using namespace physics; + +////////////////////////////////////////////////// +GazeboID::GazeboID() +{ +} + +////////////////////////////////////////////////// +GazeboID::~GazeboID() +{ + this->Fini(); +} + +////////////////////////////////////////////////// +void GazeboID::Load(sdf::ElementPtr _sdf) +{ + if (_sdf) + this->sdf = _sdf; + + if (this->sdf->HasAttribute("num")) + this->gazeboID = this->sdf->Get("num"); + + if (this->sdf->HasAttribute("ip")) + this->ip = this->sdf->Get("ip"); + + // if (this->sdf->HasElement("ip")) + // { + // sdf::ElementPtr gazeboIdElem = this->sdf->GetElement("ip"); + // ip = gazeboIdElem->Get(); + // } + + // if (this->sdf->HasElement("port")) + // { + // sdf::ElementPtr gazeboPortElem = this->sdf->GetElement("port"); + // port = gazeboPortElem->Get(); + // } + + if (this->sdf->HasElement("model_name")) + { + sdf::ElementPtr modelNameElem = this->sdf->GetElement("model_name"); + while (modelNameElem) + { + modelNames.push_back(modelNameElem->Get()); + modelNameElem = modelNameElem->GetNextElement("model_name"); + } + } +} + +////////////////////////////////////////////////// +unsigned int GazeboID::GetGazeboID() +{ + return gazeboID; +} + +////////////////////////////////////////////////// +std::string GazeboID::GetGazeboIp() +{ + return ip; +} + +////////////////////////////////////////////////// +unsigned int GazeboID::GetModelCount() +{ + return modelNames.size(); +} + +////////////////////////////////////////////////// +std::string GazeboID::GetModelName(unsigned int _i) +{ + return modelNames[_i]; +} + +////////////////////////////////////////////////// +void GazeboID::Fini() +{ + this->modelNames.clear(); + this->sdf.reset(); +} \ No newline at end of file diff --git a/Gazebo_Distributed/gazebo/physics/GazeboID.hh b/Gazebo_Distributed/gazebo/physics/GazeboID.hh new file mode 100644 index 0000000..411bd28 --- /dev/null +++ b/Gazebo_Distributed/gazebo/physics/GazeboID.hh @@ -0,0 +1,109 @@ +/* + * Copyright (C) 2019 AIRC 01 + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +/* Desc: Base class for distributed gazebo + * Author: Zhang Shuai + * Date: 28 March 2019 + */ + +#ifndef _GAZEBOID_HH_ +#define _GAZEBOID_HH_ + +#include +// #include +#include +#include +// #include + +#include + +// #include "gazebo/common/CommonTypes.hh" +#include "gazebo/physics/PhysicsTypes.hh" +// #include "gazebo/physics/ModelState.hh" +// #include "gazebo/physics/Entity.hh" +#include "gazebo/util/system.hh" + +namespace gazebo +{ +namespace physics +{ +/// \class Distribution Distribution.hh physics/physics.hh +/// \brief Distribution is used to store information about the distributed simulation. +class GZ_PHYSICS_VISIBLE GazeboID +{ + /// \brief Constructor. + /// \param[in] _parent Parent object. +public: + explicit GazeboID(); + + /// \brief Destructor. +public: + virtual ~GazeboID(); + + /// \brief Load the Distribution. + /// \param[in] _sdf SDF parameters to load from. +public: + void Load(sdf::ElementPtr _sdf); + + /// \brief Get the gazebo ID of this Distribution. + /// \return the gazebo ID of this Distribution. +public: + unsigned int GetGazeboID(); + + /// \brief Get the gazebo ip of this Distribution. + /// \return the gazebo ip of this Distribution. +public: + std::string GetGazeboIp(); + + /// \brief Get the number of models this Distribution has. + /// \return Number of models associated with this Distribution. +public: + unsigned int GetModelCount(); + + /// \brief Get the name of the specified model. + /// \param[in] _i Number of the model name to get. + /// \return the name of the specified model. +public: + std::string GetModelName(unsigned int _i); + + /// \brief Finialize the gazeboID +public: + void Fini(); + + /// \brief The Distribution's current SDF description. +private: + sdf::ElementPtr sdf; + + /// \brief idex of distributed gazebo. +private: + unsigned int gazeboID; + + /// \brief ip of distributed gazebo. +private: + std::string ip; + + /// \brief port of distributed gazebo. +private: + int port; + + /// \brief Models name in this gazebo +private: + std::vector modelNames; +}; + +} // namespace physics +} // namespace gazebo +#endif diff --git a/Gazebo_Distributed/gazebo/physics/Link.cc b/Gazebo_Distributed/gazebo/physics/Link.cc index b68ffe3..7724fb5 100644 --- a/Gazebo_Distributed/gazebo/physics/Link.cc +++ b/Gazebo_Distributed/gazebo/physics/Link.cc @@ -16,9 +16,9 @@ */ #ifdef _WIN32 - // Ensure that Winsock2.h is included before Windows.h, which can get - // pulled in by anybody (e.g., Boost). - #include +// Ensure that Winsock2.h is included before Windows.h, which can get +// pulled in by anybody (e.g., Boost). +#include #endif #include @@ -85,8 +85,7 @@ void Link::Load(sdf::ElementPtr _sdf) { this->SetSelfCollide(this->GetModel()->GetSelfCollide()); } - this->sdf->GetElement("self_collide")->GetValue()->SetUpdateFunc( - std::bind(&Link::GetSelfCollide, this)); + this->sdf->GetElement("self_collide")->GetValue()->SetUpdateFunc(std::bind(&Link::GetSelfCollide, this)); // Parse visuals from SDF this->ParseVisuals(); @@ -103,45 +102,43 @@ void Link::Load(sdf::ElementPtr _sdf) } } - //zhangshuai - std::string bebop_0 = "bebop_0"; - std::cout << "bebop_0:" << bebop_0 << std::endl; //zhangshuai - std::cout << "model_name:" << this->GetModel()->GetName() << std::endl; //zhangshuai - - // if (std::strcmp(this->GetModel()->GetName(), bebop_0) == 0) - if (this->GetModel()->GetName() == bebop_0) + // Modified by zhangshuai 2019.04.02 ----Begin + // Judge if the model to load is simulated in this gazebo + for (unsigned int i = 0; i < this->GetWorld()->GetDistribution()->GetGazeboIDPtr(this->GetWorld()->GetGazeboLocalID())->GetModelCount(); i++) { - //zhangshuai - if (this->sdf->HasElement("sensor")) - { - sdf::ElementPtr sensorElem = this->sdf->GetElement("sensor"); - while (sensorElem) + if (this->GetModel()->GetName() == this->GetWorld()->GetDistribution()->GetGazeboIDPtr(this->GetWorld()->GetGazeboLocalID())->GetModelName(i)) { - /// \todo This if statement is a hack to prevent Links from creating - /// a force torque sensor. We should make this more generic. - if (sensorElem->Get("type") == "force_torque") + // Original part + if (this->sdf->HasElement("sensor")) { - gzerr << "A link cannot load a [" << - sensorElem->Get("type") << "] sensor.\n"; - } - else if (sensorElem->Get("type") != "__default__") - { - // This must match the implementation in Sensors::GetScopedName - std::string sensorName = this->GetScopedName(true) + "::" + - sensorElem->Get("name"); + sdf::ElementPtr sensorElem = this->sdf->GetElement("sensor"); + while (sensorElem) + { + /// \todo This if statement is a hack to prevent Links from creating + /// a force torque sensor. We should make this more generic. + if (sensorElem->Get("type") == "force_torque") + { + gzerr << "A link cannot load a [" << sensorElem->Get("type") << "] sensor.\n"; + } + else if (sensorElem->Get("type") != "__default__") + { + // This must match the implementation in Sensors::GetScopedName + std::string sensorName = this->GetScopedName(true) + "::" + + sensorElem->Get("name"); - // Tell the sensor library to create a sensor. - event::Events::createSensor(sensorElem, - this->GetWorld()->GetName(), this->GetScopedName(), this->GetId()); + // Tell the sensor library to create a sensor. + event::Events::createSensor(sensorElem, + this->GetWorld()->GetName(), this->GetScopedName(), this->GetId()); - this->sensors.push_back(sensorName); + this->sensors.push_back(sensorName); + } + sensorElem = sensorElem->GetNextElement("sensor"); + } } - sensorElem = sensorElem->GetNextElement("sensor"); + // Original part } } - //zhangshuai - } - //zhangshuai + // Modified by zhangshuai 2019.04.02 ----End // Load the lights if (this->sdf->HasElement("light")) @@ -187,16 +184,16 @@ void Link::Load(sdf::ElementPtr _sdf) if (!collisionNames.empty()) { for (std::vector::iterator iter = collisionNames.begin(); - iter != collisionNames.end(); ++iter) + iter != collisionNames.end(); ++iter) { (*iter) = this->GetScopedName() + "::" + (*iter); } std::string topic = - this->world->GetPhysicsEngine()->GetContactManager()->CreateFilter( - this->GetScopedName() + "/audio_collision", collisionNames); + this->world->GetPhysicsEngine()->GetContactManager()->CreateFilter( + this->GetScopedName() + "/audio_collision", collisionNames); this->audioContactsSub = this->node->Subscribe(topic, - &Link::OnCollision, this); + &Link::OnCollision, this); } } @@ -249,7 +246,7 @@ void Link::Init() } if ((*iter)->HasType(Base::LIGHT)) { - LightPtr light= boost::static_pointer_cast(*iter); + LightPtr light = boost::static_pointer_cast(*iter); // TODO add to lights var? // this->lights.push_back(light); light->Init(); @@ -290,7 +287,7 @@ void Link::Fini() for (auto iter : this->visuals) { auto deleteMsg = msgs::CreateRequest("entity_delete", - std::to_string(iter.second.id())); + std::to_string(iter.second.id())); this->requestPub->Publish(*deleteMsg, true); msgs::Visual msg; @@ -373,8 +370,7 @@ void Link::UpdateParameters(sdf::ElementPtr _sdf) this->sdf->GetElement("gravity")->GetValue()->SetUpdateFunc( boost::bind(&Link::GetGravityMode, this)); - this->sdf->GetElement("kinematic")->GetValue()->SetUpdateFunc( - boost::bind(&Link::GetKinematic, this)); + this->sdf->GetElement("kinematic")->GetValue()->SetUpdateFunc(boost::bind(&Link::GetKinematic, this)); if (this->sdf->Get("gravity") != this->GetGravityMode()) this->SetGravityMode(this->sdf->Get("gravity")); @@ -442,13 +438,13 @@ void Link::SetCollideMode(const std::string &_mode) if (_mode == "all") { - categoryBits = GZ_ALL_COLLIDE; - collideBits = GZ_ALL_COLLIDE; + categoryBits = GZ_ALL_COLLIDE; + collideBits = GZ_ALL_COLLIDE; } else if (_mode == "none") { - categoryBits = GZ_NONE_COLLIDE; - collideBits = GZ_NONE_COLLIDE; + categoryBits = GZ_NONE_COLLIDE; + collideBits = GZ_NONE_COLLIDE; } else if (_mode == "sensors") { @@ -514,7 +510,8 @@ void Link::Update(const common::UpdateInfo & /*_info*/) // Update all the audio sources for (std::vector::iterator iter = - this->audioSources.begin(); iter != this->audioSources.end(); ++iter) + this->audioSources.begin(); + iter != this->audioSources.end(); ++iter) { (*iter)->SetPose(this->GetWorldPose().Ign()); (*iter)->SetVelocity(this->GetWorldLinearVel().Ign()); @@ -522,7 +519,7 @@ void Link::Update(const common::UpdateInfo & /*_info*/) #endif // FIXME: race condition on factory-based model loading!!!!! - /*if (this->GetEnabled() != this->enabled) + /*if (this->GetEnabled() != this->enabled) { this->enabled = this->GetEnabled(); this->enabledSignal(this->enabled); @@ -567,8 +564,8 @@ Link_V Link::GetChildJointsLinks() const { Link_V links; for (std::vector::const_iterator iter = this->childJoints.begin(); - iter != this->childJoints.end(); - ++iter) + iter != this->childJoints.end(); + ++iter) { if ((*iter)->GetChild()) links.push_back((*iter)->GetChild()); @@ -581,8 +578,8 @@ Link_V Link::GetParentJointsLinks() const { Link_V links; for (std::vector::const_iterator iter = this->parentJoints.begin(); - iter != this->parentJoints.end(); - ++iter) + iter != this->parentJoints.end(); + ++iter) { if ((*iter)->GetParent()) links.push_back((*iter)->GetParent()); @@ -595,13 +592,13 @@ void Link::LoadCollision(sdf::ElementPtr _sdf) { CollisionPtr collision; std::string geomType = - _sdf->GetElement("geometry")->GetFirstElement()->GetName(); + _sdf->GetElement("geometry")->GetFirstElement()->GetName(); if (geomType == "heightmap" || geomType == "map") this->SetStatic(true); collision = this->GetWorld()->GetPhysicsEngine()->CreateCollision(geomType, - boost::static_pointer_cast(shared_from_this())); + boost::static_pointer_cast(shared_from_this())); if (!collision) gzthrow("Unknown Collisionetry Type[" + geomType + "]"); @@ -683,7 +680,7 @@ math::Vector3 Link::GetRelativeLinearVel() const math::Vector3 Link::GetRelativeAngularVel() const { return this->GetWorldPose().rot.RotateVectorReverse( - this->GetWorldAngularVel()); + this->GetWorldAngularVel()); } ////////////////////////////////////////////////// @@ -702,7 +699,7 @@ math::Vector3 Link::GetWorldLinearAccel() const math::Vector3 Link::GetRelativeAngularAccel() const { return this->GetWorldPose().rot.RotateVectorReverse( - this->GetWorldAngularAccel()); + this->GetWorldAngularAccel()); } ////////////////////////////////////////////////// @@ -713,8 +710,7 @@ math::Vector3 Link::GetWorldAngularAccel() const // L: angular momentum of CoG in world frame // w: angular velocity in world frame // return I^-1 * (T - w x L) - return this->GetWorldInertiaMatrix().Inverse() * (this->GetWorldTorque() - - this->GetWorldAngularVel().Cross(this->GetWorldAngularMomentum())); + return this->GetWorldInertiaMatrix().Inverse() * (this->GetWorldTorque() - this->GetWorldAngularVel().Cross(this->GetWorldAngularMomentum())); } ////////////////////////////////////////////////// @@ -770,7 +766,7 @@ bool Link::SetSelected(bool _s) } ////////////////////////////////////////////////// -void Link::SetInertial(const InertialPtr &/*_inertial*/) +void Link::SetInertial(const InertialPtr & /*_inertial*/) { gzwarn << "Link::SetMass is empty\n"; } @@ -813,8 +809,8 @@ void Link::AddChildJoint(JointPtr _joint) void Link::RemoveParentJoint(const std::string &_jointName) { for (std::vector::iterator iter = this->parentJoints.begin(); - iter != this->parentJoints.end(); - ++iter) + iter != this->parentJoints.end(); + ++iter) { /// @todo: can we assume there are no repeats? if ((*iter)->GetName() == _jointName) @@ -829,8 +825,8 @@ void Link::RemoveParentJoint(const std::string &_jointName) void Link::RemoveChildJoint(const std::string &_jointName) { for (std::vector::iterator iter = this->childJoints.begin(); - iter != this->childJoints.end(); - ++iter) + iter != this->childJoints.end(); + ++iter) { /// @todo: can we assume there are no repeats? if ((*iter)->GetName() == _jointName) @@ -870,7 +866,7 @@ void Link::FillMsg(msgs::Link &_msg) _msg.mutable_inertial()->set_iyz(this->inertial->GetIYZ()); _msg.mutable_inertial()->set_izz(this->inertial->GetIZZ()); msgs::Set(_msg.mutable_inertial()->mutable_pose(), - this->inertial->GetPose().Ign()); + this->inertial->GetPose().Ign()); for (auto &child : this->children) { @@ -901,7 +897,7 @@ void Link::FillMsg(msgs::Link &_msg) this->UpdateVisualMsg(); for (Visuals_M::iterator iter = this->visuals.begin(); - iter != this->visuals.end(); ++iter) + iter != this->visuals.end(); ++iter) { msgs::Visual *vis = _msg.add_visual(); vis->CopyFrom(iter->second); @@ -976,7 +972,7 @@ void Link::ProcessMsg(const msgs::Link &_msg) if (coll) coll->ProcessMsg(_msg.collision(i)); } - if (_msg.collision_size()>0) + if (_msg.collision_size() > 0) this->UpdateSurface(); } @@ -1015,8 +1011,8 @@ void Link::DetachStaticModel(const std::string &_modelName) { if (this->attachedModels[i]->GetName() == _modelName) { - this->attachedModels.erase(this->attachedModels.begin()+i); - this->attachedModelsOffset.erase(this->attachedModelsOffset.begin()+i); + this->attachedModels.erase(this->attachedModels.begin() + i); + this->attachedModelsOffset.erase(this->attachedModelsOffset.begin() + i); break; } } @@ -1085,7 +1081,7 @@ double Link::GetAngularDamping() const } ///////////////////////////////////////////////// -void Link::SetKinematic(const bool &/*_kinematic*/) +void Link::SetKinematic(const bool & /*_kinematic*/) { } @@ -1109,8 +1105,8 @@ void Link::SetPublishData(bool _enable) std::string topic = "~/" + this->GetScopedName(); this->dataPub = this->node->Advertise(topic); this->connections.push_back( - event::Events::ConnectWorldUpdateEnd( - boost::bind(&Link::PublishData, this))); + event::Events::ConnectWorldUpdateEnd( + boost::bind(&Link::PublishData, this))); } else { @@ -1128,9 +1124,9 @@ void Link::PublishData() msgs::Set(this->linkDataMsg.mutable_time(), this->world->GetSimTime()); linkDataMsg.set_name(this->GetScopedName()); msgs::Set(this->linkDataMsg.mutable_linear_velocity(), - this->GetWorldLinearVel().Ign()); + this->GetWorldLinearVel().Ign()); msgs::Set(this->linkDataMsg.mutable_angular_velocity(), - this->GetWorldAngularVel().Ign()); + this->GetWorldAngularVel().Ign()); this->dataPub->Publish(this->linkDataMsg); } } @@ -1227,7 +1223,7 @@ bool Link::SetVisualPose(const uint32_t _id, while (visualElem) { std::string visName = linkName + "::" + - visualElem->Get("name"); + visualElem->Get("name"); // update visual msg if it exists if (msg.name() == visName) @@ -1266,12 +1262,13 @@ void Link::OnCollision(ConstContactsPtr &_msg) GZ_ASSERT(pos1 != std::string::npos, "Invalid collision name"); GZ_ASSERT(pos2 != std::string::npos, "Invalid collision name"); - collisionName1 = collisionName1.substr(pos1+2); - collisionName2 = collisionName2.substr(pos2+2); + collisionName1 = collisionName1.substr(pos1 + 2); + collisionName2 = collisionName2.substr(pos2 + 2); #ifdef HAVE_OPENAL for (std::vector::iterator iter = - this->audioSources.begin(); iter != this->audioSources.end(); ++iter) + this->audioSources.begin(); + iter != this->audioSources.end(); ++iter) { if ((*iter)->HasCollisionName(collisionName1) || (*iter)->HasCollisionName(collisionName2)) @@ -1351,7 +1348,7 @@ void Link::UpdateVisualGeomSDF(const math::Vector3 &_scale) math::Vector3 size = geomElem->GetElement("box")->Get("size"); geomElem->GetElement("box")->GetElement("size")->Set( - _scale/this->scale*size); + _scale / this->scale * size); } else if (geomElem->HasElement("sphere")) { @@ -1359,9 +1356,9 @@ void Link::UpdateVisualGeomSDF(const math::Vector3 &_scale) double radius = geomElem->GetElement("sphere")->Get("radius"); double newRadius = std::max(_scale.z, std::max(_scale.x, _scale.y)); double oldRadius = std::max(this->scale.Z(), - std::max(this->scale.X(), this->scale.Y())); + std::max(this->scale.X(), this->scale.Y())); geomElem->GetElement("sphere")->GetElement("radius")->Set( - newRadius/oldRadius*radius); + newRadius / oldRadius * radius); } else if (geomElem->HasElement("cylinder")) { @@ -1371,10 +1368,8 @@ void Link::UpdateVisualGeomSDF(const math::Vector3 &_scale) double oldRadius = std::max(this->scale.X(), this->scale.Y()); double length = geomElem->GetElement("cylinder")->Get("length"); - geomElem->GetElement("cylinder")->GetElement("radius")->Set( - newRadius/oldRadius*radius); - geomElem->GetElement("cylinder")->GetElement("length")->Set( - _scale.z/this->scale.Z()*length); + geomElem->GetElement("cylinder")->GetElement("radius")->Set(newRadius / oldRadius * radius); + geomElem->GetElement("cylinder")->GetElement("length")->Set(_scale.z / this->scale.Z() * length); } else if (geomElem->HasElement("mesh")) geomElem->GetElement("mesh")->GetElement("scale")->Set(_scale); @@ -1402,7 +1397,7 @@ void Link::UpdateVisualMsg() for (auto &iter : this->visuals) { std::string visName = linkName + "::" + - visualElem->Get("name"); + visualElem->Get("name"); if (iter.second.name() == visName) { iter.second.mutable_geometry()->CopyFrom(msg.geometry()); @@ -1424,7 +1419,7 @@ void Link::UpdateVisualMsg() auto iter = this->visuals.find(msg.id()); if (iter != this->visuals.end()) - gzthrow(std::string("Duplicate visual name[")+msg.name()+"]\n"); + gzthrow(std::string("Duplicate visual name[") + msg.name() + "]\n"); this->visuals[msg.id()] = msg; } @@ -1479,15 +1474,14 @@ double Link::GetWorldEnergy() const void Link::MoveFrame(const math::Pose &_worldReferenceFrameSrc, const math::Pose &_worldReferenceFrameDst) { - math::Pose targetWorldPose = (this->GetWorldPose() - _worldReferenceFrameSrc) - + _worldReferenceFrameDst; + math::Pose targetWorldPose = (this->GetWorldPose() - _worldReferenceFrameSrc) + _worldReferenceFrameDst; this->SetWorldPose(targetWorldPose); this->SetWorldTwist(math::Vector3(0, 0, 0), math::Vector3(0, 0, 0)); } ///////////////////////////////////////////////// bool Link::FindAllConnectedLinksHelper(const LinkPtr &_originalParentLink, - Link_V &_connectedLinks, bool _fistLink) + Link_V &_connectedLinks, bool _fistLink) { // debug // std::string pn; @@ -1507,7 +1501,7 @@ bool Link::FindAllConnectedLinksHelper(const LinkPtr &_originalParentLink, // loop through all joints where this link is a parent link of the joint for (Link_V::iterator li = childLinks.begin(); - li != childLinks.end(); ++li) + li != childLinks.end(); ++li) { // gzerr << "debug: checking " << (*li)->GetName() << "\n"; @@ -1536,7 +1530,7 @@ bool Link::FindAllConnectedLinksHelper(const LinkPtr &_originalParentLink, // if it returns false, it looped back to parent, mark flag and break // from current for-loop. if (!(*li)->FindAllConnectedLinksHelper(_originalParentLink, - _connectedLinks)) + _connectedLinks)) { // one of the recursed link is the parent link return false; @@ -1553,7 +1547,7 @@ bool Link::FindAllConnectedLinksHelper(const LinkPtr &_originalParentLink, // loop through all joints where this link is a parent link of the joint for (Link_V::iterator li = parentLinks.begin(); - li != parentLinks.end(); ++li) + li != parentLinks.end(); ++li) { // check child link of each child joint recursively if ((*li).get() == _originalParentLink.get()) @@ -1586,7 +1580,7 @@ bool Link::FindAllConnectedLinksHelper(const LinkPtr &_originalParentLink, // if it returns false, it looped back to parent, mark flag and break // from current for-loop. if (!(*li)->FindAllConnectedLinksHelper(_originalParentLink, - _connectedLinks)) + _connectedLinks)) { // one of the recursed link is the parent link return false; diff --git a/Gazebo_Distributed/gazebo/physics/PhysicsTypes.hh b/Gazebo_Distributed/gazebo/physics/PhysicsTypes.hh index fa6c215..df7b0fc 100644 --- a/Gazebo_Distributed/gazebo/physics/PhysicsTypes.hh +++ b/Gazebo_Distributed/gazebo/physics/PhysicsTypes.hh @@ -66,6 +66,10 @@ namespace gazebo class LightState; class LinkState; class JointState; + // Added by zhangshuai 2019.03.28 ----Begin + class GazeboID; + class Distribution; + // Added by zhangshuai 2019.03.28 ----End /// \def BasePtr /// \brief Boost shared pointer to a Base object @@ -235,6 +239,24 @@ namespace gazebo /// \brief Map of joint state typedef std::map JointState_M; + // Added by zhangshuai 2019.03.28 ----Begin + /// \def GazeboIDPtr + /// \brief Boost shared pointer to a GazeboID object + typedef boost::shared_ptr GazeboIDPtr; + + /// \def DistributionPtr + /// \brief Boost shared pointer to a Distribution object + typedef boost::shared_ptr DistributionPtr; + + /// \def GazeboID_V + /// \brief Vector of GazeboIDPtr + typedef std::vector GazeboID_V; + + /// \def Distribution_V + /// \brief Vector of DistributionPtr + typedef std::vector Distribution_V; + // Added by zhangshuai 2019.03.28 ----End + #ifndef GZ_COLLIDE_BITS /// \def GZ_ALL_COLLIDE diff --git a/Gazebo_Distributed/gazebo/physics/World.cc b/Gazebo_Distributed/gazebo/physics/World.cc index 7c1b5af..537c144 100644 --- a/Gazebo_Distributed/gazebo/physics/World.cc +++ b/Gazebo_Distributed/gazebo/physics/World.cc @@ -84,6 +84,10 @@ #include "gazebo/physics/ContactManager.hh" #include "gazebo/physics/Population.hh" +// Added by zhangshuai 2019.04.03 for count time ----Begin +#include "gazebo/countTime.hh" +// Added by zhangshuai 2019.04.03 for count time ----End + using namespace gazebo; using namespace physics; @@ -91,6 +95,22 @@ using namespace physics; /// This will be replaced with a class member variable in Gazebo 3.0 bool g_clearModels; +// Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME +double before_worldUpdateBeginTime = 0; +double worldUpdateBeginTime = 0; +double modelUpdateFuncTime = 0; +double updateCollisionTime = 0; +double loggingTime = 0; +double before_updatePhysicsTime = 0; +double updatePhysicsTime = 0; +double before_tcpTime = 0; +double tcpTime = 0; +double after_tcpTime = 0; +double wholeUpdataTime = 0; +#endif +// Added by zhangshuai 2019.04.03 for count time ----End + class ModelUpdate_TBB { public: @@ -253,15 +273,30 @@ void World::Load(sdf::ElementPtr _sdf) "~/factory/light"); // Added by zhangshuai based on zenglei 2019.03.19 ----Begin - if (this->dataPtr->sdf->HasElement("distributed")) + if (this->dataPtr->sdf->HasElement("distribution")) { - sdf::ElementPtr eventElem = this->dataPtr->sdf->GetElement("distributed"); - type_ = eventElem->Get("type"); - ip = eventElem->Get("ip"); - port = eventElem->Get("port"); - flag = eventElem->Get("flag"); - simula_entity_num = eventElem->Get("simula_entity_num"); - shadow_entity_num = eventElem->Get("shadow_entity_num"); + sdf::ElementPtr distributionElem = this->dataPtr->sdf->GetElement("distribution"); + + gazeboLocalID = distributionElem->Get("gazebo_local_ID"); + port = distributionElem->Get("port"); + flag = distributionElem->Get("flag"); + + std::cout << "================= gazebo_local_ID: " << gazeboLocalID << "\t Port: " << port << "\t Flag: " << flag << " =================" << std::endl; + + DistributionPtr distribution_tmp(new physics::Distribution()); + + this->distribution = distribution_tmp; + this->distribution->Load(distributionElem); + + std::cout << "================= gazebo_counts: " << this->distribution->GetGazeboCount() << " =================" << std::endl; + std::cout << "================= gazebo_ID: " << this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetGazeboID() << " =================" << std::endl; + std::cout << "================= gazebo_ip: " << this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetGazeboIp() << " =================" << std::endl; + std::cout << "================= model_counts: " << this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelCount() << " =================" << std::endl; + // std::cout << "================= the second model name: " << this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelName(1) << " =================" << std::endl; + + // ip = eventElem->Get("ip"); + // simula_entity_num = eventElem->Get("simula_entity_num"); + // shadow_entity_num = eventElem->Get("shadow_entity_num"); } //Added by zhangshuai based on zenglei 2019.03.19 ----End @@ -419,18 +454,16 @@ void World::Run(unsigned int _iterations) this->dataPtr->stopIterations = _iterations; // Added by zhangshuai based on zenglei 2019.03.19 ----Begin - std::cout << "Server IP: " << ip << "\t Server Port: " << port << "\t Flag: " << flag << std::endl; - std::cout << "simula_entity_num: " << simula_entity_num << "\t shadow_entity_num: " << shadow_entity_num << std::endl; if (1 == flag) { - if (0 == type_) + if (0 == this->gazeboLocalID) { gazeboZero.SetPort(port); gazeboZero.StartServer(); } - else if (1 == type_) + else if (1 == this->gazeboLocalID) { - gazeboOne.SetIp(ip); + gazeboOne.SetIp(this->distribution->GetGazeboIDPtr(0)->GetGazeboIp()); gazeboOne.SetPort(port); gazeboOne.ConnectServer(); } @@ -519,11 +552,11 @@ void World::RunLoop() // Added by zhangshuai based on zenglei 2019.03.19 ----Begin if (1 == flag) { - if (0 == type_) + if (0 == this->gazeboLocalID) { gazeboZero.Close(); } - else if (1 == type_) + else if (1 == this->gazeboLocalID) { gazeboOne.Close(); } @@ -720,6 +753,18 @@ void World::Step(unsigned int _steps) ////////////////////////////////////////////////// void World::Update() { + +// Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + struct timeval tv; + double cur_time; + double start_time; + gettimeofday(&tv, NULL); + cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; + start_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + DIAG_TIMER_START("World::Update"); if (this->dataPtr->needsReset) @@ -737,20 +782,77 @@ void World::Update() this->dataPtr->updateInfo.simTime = this->GetSimTime(); this->dataPtr->updateInfo.realTime = this->GetRealTime(); + +// Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + before_worldUpdateBeginTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + event::Events::worldUpdateBegin(this->dataPtr->updateInfo); +// Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + worldUpdateBeginTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + DIAG_TIMER_LAP("World::Update", "Events::worldUpdateBegin"); + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + // Update all the models (*this.*dataPtr->modelUpdateFunc)(); + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + modelUpdateFuncTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + DIAG_TIMER_LAP("World::Update", "Model::Update"); + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + // This must be called before PhysicsEngine::UpdatePhysics. this->dataPtr->physicsEngine->UpdateCollision(); + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + updateCollisionTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + DIAG_TIMER_LAP("World::Update", "PhysicsEngine::UpdateCollision"); + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + // Wait for logging to finish, if it's running. if (util::LogRecord::Instance()->Running()) { @@ -766,13 +868,41 @@ void World::Update() } } + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + loggingTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + // Give clients a possibility to react to collisions before the physics // gets updated. this->dataPtr->updateInfo.realTime = this->GetRealTime(); event::Events::beforePhysicsUpdate(this->dataPtr->updateInfo); + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + before_updatePhysicsTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + DIAG_TIMER_LAP("World::Update", "Events::beforePhysicsUpdate"); + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + // Update the physics engine if (this->dataPtr->enablePhysicsEngine && this->dataPtr->physicsEngine) { @@ -800,102 +930,133 @@ void World::Update() DIAG_TIMER_LAP("World::Update", "SetWorldPose(dirtyPoses)"); } + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + updatePhysicsTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + // Added by zhangshuai based on zenglei 2019.03.19 ----Begin if (1 == flag) { // if (this->dataPtr->iterations % 10 == 0) + // Modified by zhangshuai 2019.04.02 ----Begin { - unsigned int i = 0; - for (unsigned int k = 0; k < simula_entity_num; k++) + + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + + for (unsigned int i = 0; i < this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelCount(); i++) { - std::stringstream ss; - ss << k; - std::string ks = ss.str(); - std::string tmp_model_name = "bebop_" + ks; - // std::cout << "model_name:" << tmp_model_name << std::endl; - for (i = 0; i < this->GetModel(tmp_model_name)->GetLink("base_link")->GetName().length(); i++) - infor[k].link_name[i] = this->GetModel(tmp_model_name)->GetLink("base_link")->GetName()[i]; - infor[k].link_name[i] = '\0'; - infor[k].ID = this->GetModel(tmp_model_name)->GetLink("base_link")->GetId(); - infor[k].link_pose = this->GetModel(tmp_model_name)->GetLink("base_link")->GetWorldPose(); - - // std::cout << "link_name:" << this->GetModel("bebop_0")->GetLink("base_link")->GetName() << std::endl; - // std::cout << "ID:" << this->GetModel("bebop_0")->GetLink("base_link")->GetId() << std::endl; - // std::cout << "link_pos_x:" << this->GetModel("bebop_0")->GetLink("base_link")->GetWorldPose().pos.x << std::endl; - // std::cout << "link_pos_y:" << this->GetModel("bebop_0")->GetLink("base_link")->GetWorldPose().pos.y << std::endl; - // std::cout << "link_pos_z:" << this->GetModel("bebop_0")->GetLink("base_link")->GetWorldPose().pos.z << std::endl; - // std::cout << "link_rot_x:" << this->GetModel("bebop_0")->GetLink("base_link")->GetWorldPose().rot.GetAsEuler().x << std::endl; - // std::cout << "link_rot_y:" << this->GetModel("bebop_0")->GetLink("base_link")->GetWorldPose().rot.GetAsEuler().y << std::endl; - // std::cout << "link_rot_z:" << this->GetModel("bebop_0")->GetLink("base_link")->GetWorldPose().rot.GetAsEuler().z << std::endl; - - // std::cout << "link_name(infor):" << infor[k].link_name << std::endl; - // std::cout << "ID(infor):" << infor[k].ID << std::endl; - // std::cout << "link_pos_x(infor):" << infor[k].link_pose.pos.x << std::endl; - // std::cout << "link_pos_y(infor):" << infor[k].link_pose.pos.y << std::endl; - // std::cout << "link_pos_z(infor):" << infor[k].link_pose.pos.z << std::endl; - // std::cout << "link_rot_x(infor):" << infor[k].link_pose.rot.GetAsEuler().x << std::endl; - // std::cout << "link_rot_y(infor):" << infor[k].link_pose.rot.GetAsEuler().y << std::endl; - // std::cout << "link_rot_z(infor):" << infor[k].link_pose.rot.GetAsEuler().z << std::endl; + std::string tmp_model_name = this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelName(i); + unsigned int j = 0; + for (j = 0; j < this->GetModel(tmp_model_name)->GetLink("base_link")->GetName().length(); j++) + infor[i].link_name[j] = this->GetModel(tmp_model_name)->GetLink("base_link")->GetName()[j]; + infor[i].link_name[j] = '\0'; + infor[i].ID = this->GetModel(tmp_model_name)->GetLink("base_link")->GetId(); + infor[i].link_pose = this->GetModel(tmp_model_name)->GetLink("base_link")->GetWorldPose(); } CommunicationData temp[50]; - if (0 == type_) + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + before_tcpTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + + if (0 == this->gazeboLocalID) { - if (!gazeboZero.sendInfor(infor, simula_entity_num)) + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + + if (!gazeboZero.sendInfor(infor, this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelCount())) std::cout << "Send Infor fail!" << std::endl; - if (!gazeboZero.recvInfor(temp, shadow_entity_num)) + if (!gazeboZero.recvInfor(temp, this->distribution->GetGazeboIDPtr(1)->GetModelCount())) std::cout << "Rcceive Infor fail!" << std::endl; + + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + tcpTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + + for (unsigned int i = 0; i < this->distribution->GetGazeboIDPtr(1)->GetModelCount(); i++) + { + std::string tmp_model_name = this->distribution->GetGazeboIDPtr(1)->GetModelName(i); + this->GetModel(tmp_model_name)->GetLink("base_link")->SetWorldPose(temp[i].link_pose); + } + + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + after_tcpTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End } - else if (1 == type_) + else if (1 == this->gazeboLocalID) { - if (!gazeboOne.recvInfor(temp, shadow_entity_num)) + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + + if (!gazeboOne.recvInfor(temp, this->distribution->GetGazeboIDPtr(0)->GetModelCount())) std::cout << "Rcceive Infor fail!" << std::endl; - if (!gazeboOne.sendInfor(infor, simula_entity_num)) + if (!gazeboOne.sendInfor(infor, this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelCount())) std::cout << "Send Infor fail!" << std::endl; + + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + tcpTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + cur_time = (double)tv.tv_sec + (double)tv.tv_usec / 1.e6; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End + + for (unsigned int i = 0; i < this->distribution->GetGazeboIDPtr(0)->GetModelCount(); i++) + { + std::string tmp_model_name = this->distribution->GetGazeboIDPtr(0)->GetModelName(i); + this->GetModel(tmp_model_name)->GetLink("base_link")->SetWorldPose(temp[i].link_pose); + } + + // Added by zhangshuai 2019.04.03 for count time ----Begin +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + after_tcpTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - cur_time; +#endif + // Added by zhangshuai 2019.04.03 for count time ----End } - - for (unsigned int k = 0; k < shadow_entity_num; k++) - { - std::stringstream ss; - ss << (k + shadow_entity_num); - std::string ks = ss.str(); - std::string tmp_model_name = "bebop_" + ks; - - // std::cout << "model_name:" << tmp_model_name << std::endl; - // std::cout << "link_name(infor):" << temp[k].link_name << std::endl; - // std::cout << "ID(infor):" << temp[k].ID << std::endl; - // std::cout << "link_pos_x(infor):" << temp[k].link_pose.pos.x << std::endl; - // std::cout << "link_pos_y(infor):" << temp[k].link_pose.pos.y << std::endl; - // std::cout << "link_pos_z(infor):" << temp[k].link_pose.pos.z << std::endl; - // std::cout << "link_rot_x(infor):" << temp[k].link_pose.rot.GetAsEuler().x << std::endl; - // std::cout << "link_rot_y(infor):" << temp[k].link_pose.rot.GetAsEuler().y << std::endl; - // std::cout << "link_rot_z(infor):" << temp[k].link_pose.rot.GetAsEuler().z << std::endl; - - this->GetModel(tmp_model_name)->GetLink("base_link")->SetWorldPose(temp[k].link_pose); - } - - // std::cout << "link_name(infor):" << infor[0].link_name << std::endl; - // std::cout << "ID(infor):" << infor[0].ID << std::endl; - // std::cout << "link_pos_x(infor):" << temp[0].link_pose.pos.x << std::endl; - // std::cout << "link_pos_y(infor):" << temp[0].link_pose.pos.y << std::endl; - // std::cout << "link_pos_z(infor):" << temp[0].link_pose.pos.z << std::endl; - // std::cout << "link_rot_x(infor):" << temp[0].link_pose.rot.GetAsEuler().x << std::endl; - // std::cout << "link_rot_y(infor):" << temp[0].link_pose.rot.GetAsEuler().y << std::endl; - // std::cout << "link_rot_z(infor):" << temp[0].link_pose.rot.GetAsEuler().z << std::endl; - - // std::cout << "link_name:" << this->GetModel("bebop_0")->GetLink("base_link")->GetName() << std::endl; - // std::cout << "ID:" << this->GetModel("bebop_0")->GetLink("base_link")->GetId() << std::endl; - // std::cout << "link_pos_x:" << this->GetModel("bebop_1")->GetLink("base_link")->GetWorldPose().pos.x << std::endl; - // std::cout << "link_pos_y:" << this->GetModel("bebop_1")->GetLink("base_link")->GetWorldPose().pos.y << std::endl; - // std::cout << "link_pos_z:" << this->GetModel("bebop_1")->GetLink("base_link")->GetWorldPose().pos.z << std::endl; - // std::cout << "link_rot_x:" << this->GetModel("bebop_1")->GetLink("base_link")->GetWorldPose().rot.GetAsEuler().x << std::endl; - // std::cout << "link_rot_y:" << this->GetModel("bebop_1")->GetLink("base_link")->GetWorldPose().rot.GetAsEuler().y << std::endl; - // std::cout << "link_rot_z:" << this->GetModel("bebop_1")->GetLink("base_link")->GetWorldPose().rot.GetAsEuler().z << std::endl; } + // Modified by zhangshuai 2019.04.02 ----End } - - //Added by zhangshuai based on zenglei 2019.03.19 ----End + // Added by zhangshuai based on zenglei 2019.03.19 ----End // Only update state information if logging data. if (util::LogRecord::Instance()->Running()) @@ -910,6 +1071,28 @@ void World::Update() event::Events::worldUpdateEnd(); DIAG_TIMER_STOP("World::Update"); + +#ifdef USE_COUNT_TIME + gettimeofday(&tv, NULL); + wholeUpdataTime += (double)tv.tv_sec + (double)tv.tv_usec / 1.e6 - start_time; +#endif + + if (this->dataPtr->iterations == 100000) + { + std::cout << "===== average before_worldUpdateBeginTime:\t" << before_worldUpdateBeginTime / 100.0 << "\tms =====" << std::endl; + std::cout << "===== average worldUpdateBeginTime:\t" << worldUpdateBeginTime / 100.0 << "\tms =====" << std::endl; + std::cout << "===== average modelUpdateFuncTime:\t" << modelUpdateFuncTime / 100.0 << "\tms =====" << std::endl; + std::cout << "===== average updateCollisionTime:\t" << updateCollisionTime / 100.0 << "\tms =====" << std::endl; + std::cout << "===== average loggingTime:\t" << loggingTime / 100.0 << "\tms =====" << std::endl; + std::cout << "===== average before_updatePhysicsTime:\t" << before_updatePhysicsTime / 100.0 << "\tms =====" << std::endl; + std::cout << "===== average updatePhysicsTime:\t" << updatePhysicsTime / 100.0 << "\tms =====" << std::endl; + std::cout << "===== average before_tcpTime:\t" << before_tcpTime / 100.0 << "\tms =====" << std::endl; + std::cout << "===== average tcpTime:\t" << tcpTime / 100.0 << "\tms =====" << std::endl; + std::cout << "===== average after_tcpTime:\t" << after_tcpTime / 100.0 << "\tms =====" << std::endl; + double wholeAddTime = before_worldUpdateBeginTime + worldUpdateBeginTime + modelUpdateFuncTime + updateCollisionTime + loggingTime + before_updatePhysicsTime + updatePhysicsTime + before_tcpTime + tcpTime + after_tcpTime; + std::cout << "===== average wholeAddTime:\t" << wholeAddTime / 100.0 << "\tms =====" << std::endl; + std::cout << "===== average wholeUpdateTime:\t" << wholeUpdataTime / 100.0 << "\tms =====" << std::endl; + } } ////////////////////////////////////////////////// @@ -2189,7 +2372,18 @@ void World::ProcessFactoryMsgs() if (model != nullptr) { model->Init(); - // model->LoadPlugins(); + // Modified by zhangshuai 2019.04.02 ----Begin + // Judge if the model to load is simulated in this gazebo + for (unsigned int i = 0; i < this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelCount(); i++) + { + if (model->GetName() == this->distribution->GetGazeboIDPtr(gazeboLocalID)->GetModelName(i)) + { + // Original part + model->LoadPlugins(); + // Original part + } + } + // Modified by zhangshuai 2019.04.02 ----End } } catch (...) @@ -3095,11 +3289,18 @@ std::string World::UniqueModelName(const std::string &_name) return result; } +// Added by zhangshuai 2019.04.02 ----Begin ////////////////////////////////////////////////// -// Added by zhangshuai based on zenglei 2019.03.19 ----Begin - /// add for Tcp communication -// unsigned int World::GetLengthOfCommunicationData() -// { -// return sizeof(infor); -// } -// Added by zhangshuai based on zenglei 2019.03.19 ----End \ No newline at end of file +/// add for read the element of "distribution" +DistributionPtr World::GetDistribution() +{ + return this->distribution; +} + +////////////////////////////////////////////////// +/// add for read the element of "gazeboLocalID" +unsigned int World::GetGazeboLocalID() +{ + return this->gazeboLocalID; +} +// Added by zhangshuai 2019.04.02 ----End \ No newline at end of file diff --git a/Gazebo_Distributed/gazebo/physics/World.hh b/Gazebo_Distributed/gazebo/physics/World.hh index c029b7b..cf4a6f7 100644 --- a/Gazebo_Distributed/gazebo/physics/World.hh +++ b/Gazebo_Distributed/gazebo/physics/World.hh @@ -52,6 +52,10 @@ #include "gazebo/physics/TcpCommunication.hh" // Added by zhangshuai based on zenglei 2019.03.19 ----End +// Added by zhangshuai 2019.04.01 ----Begin +#include "gazebo/physics/Distribution.hh" +// Added by zhangshuai 2019.04.01 ----End + namespace gazebo { namespace physics @@ -716,11 +720,11 @@ private: private: TcpServer gazeboZero; -private: - std::string ip; + // private: + // std::string ip; -private: - int type_; //0:server:gazeboZero; 1:client:gazeboOne; + // private: + // int type_; //0:server:gazeboZero; 1:client:gazeboOne; private: int port; @@ -728,18 +732,32 @@ private: private: int flag; -private: - unsigned int simula_entity_num; + // private: + // unsigned int simula_entity_num; -private: - unsigned int shadow_entity_num; + // private: + // unsigned int shadow_entity_num; private: CommunicationData infor[50]; - -// public: -// unsigned int GetLengthOfCommunicationData(); // Added by zhangshuai based on zenglei 2019.03.19 ----End + + // Added by zhangshuai 2019.04.01 ----Begin + /// \brief the . +private: + unsigned int gazeboLocalID; + + /// \brief the . +private: + // Distribution_V distributions; + DistributionPtr distribution; + +public: + DistributionPtr GetDistribution(); + +public: + unsigned int GetGazeboLocalID(); + // Added by zhangshuai 2019.04.01 ----End }; /// \} } // namespace physics diff --git a/Gazebo_Hector_Test/.catkin_workspace b/Gazebo_Hector_Test/.catkin_workspace new file mode 100644 index 0000000..52fd97e --- /dev/null +++ b/Gazebo_Hector_Test/.catkin_workspace @@ -0,0 +1 @@ +# This file currently only serves to mark the location of a catkin workspace for tool integration diff --git a/Gazebo_Hector_Test/.gitignore b/Gazebo_Hector_Test/.gitignore new file mode 100644 index 0000000..76daf9b --- /dev/null +++ b/Gazebo_Hector_Test/.gitignore @@ -0,0 +1,2 @@ +build +devel diff --git a/Gazebo_Hector_Test/Distributed_Gazebo b/Gazebo_Hector_Test/Distributed_Gazebo new file mode 100755 index 0000000..590afa4 --- /dev/null +++ b/Gazebo_Hector_Test/Distributed_Gazebo @@ -0,0 +1,361 @@ +#!/bin/bash +######################################################################### +# Author: zhangshuai # +# Date: 2019.03.21 # +# Description: Automated generation of launch and world # +# Usage: ./Distributed_Gazebo configuration_file # +######################################################################### + +configuration_file=$1 + +world="WORLD:" +node="GAZEBO_NODE:" +ip="GAZEBO_IP:" +port="SOCKET_PORT:" +hector="HECTOR_NAME:" + +world_name=0 +idex=(0 0) +id0=0 +id1=1 +node_0_hector_count=0 +node_1_hector_count=0 +gazebo_idex_count=0 +# gazebo_count +# gazebo_id +# local_hector_ +gazebo_param_0=(0 0) +gazebo_param_1=(0 0) +hector_node_0=(0) +hector_node_1=(0) + +echo "begin" + +while read line +do + if [[ $line =~ $world ]] + then + temp=${line#*\"} + temp=${temp%\"*} + world_name=$temp + echo ${temp} + fi + + if [[ $line =~ $node ]] + then + temp=${line#*\"} + temp=${temp%\"*} + idex[gazebo_idex_count]=$temp + + + echo ${temp} + + echo ${idex[gazebo_idex_count]} + echo "gazebo_idex_count:$gazebo_idex_count" + + let gazebo_idex_count++ + fi + + if [[ $line =~ $ip ]] + then + temp=${line#*\"} + temp=${temp%\"*} + + if [ "${idex[gazebo_idex_count-1]}" == "$id0" ] + then + gazebo_param_0[0]=$temp + # echo "gazebo_param_0[0]:${gazebo_param_0[0]}" + fi + if [ "${idex[gazebo_idex_count-1]}" == "$id1" ] + then + gazebo_param_1[0]=$temp + # echo "gazebo_param_1[0]:${gazebo_param_1[0]}" + fi + + echo ${temp} + fi + + if [[ $line =~ $port ]] + then + temp=${line#*\"} + temp=${temp%\"*} + + if [ "${idex[gazebo_idex_count-1]}" == "$id0" ] + then + gazebo_param_0[1]=$temp + fi + if [ "${idex[gazebo_idex_count-1]}" == "$id1" ] + then + gazebo_param_1[1]=$temp + fi + + echo ${temp} + fi + + if [[ $line =~ $hector ]] + then + temp=${line#*\"} + temp=${temp%\"*} + + if [ "${idex[gazebo_idex_count-1]}" == "$id0" ] + then + hector_node_0[node_0_hector_count]=$temp + let node_0_hector_count++ + fi + if [ "${idex[gazebo_idex_count-1]}" == "$id1" ] + then + hector_node_1[node_1_hector_count]=$temp + let node_1_hector_count++ + fi + + echo ${temp} + fi + +done < $configuration_file + + +echo "end" +# echo ${gazebo_param_0[0]} +# echo ${gazebo_param_0[1]} +# echo ${gazebo_param_1[0]} +# echo ${gazebo_param_1[1]} +# echo ${hector_node_0[0]} +# echo ${hector_node_0[1]} +# echo ${hector_node_1[0]} +# echo ${hector_node_1[1]} +echo "node0:${node_0_hector_count}" +echo "node1:${node_1_hector_count}" + +file="var/log/messages" +echo "${file#*/}" +echo "${file##*/}" + + +# 开始写文件 +launch_file=(0 0) +world_file=(0 0) +# node_0çš„launch文件 +launch_file[0]="src/hector_quadrotor/hector_quadrotor_gazebo/launch/hector_node_0_${node_0_hector_count}_${node_1_hector_count}.launch" +if [ -f ${launch_file[0]} ] +then + `rm -rf ${launch_file[0]}` +fi +`touch ${launch_file[0]}` + +# node_1çš„launch文件 +launch_file[1]="src/hector_quadrotor/hector_quadrotor_gazebo/launch/hector_node_1_${node_0_hector_count}_${node_1_hector_count}.launch" +if [ -f ${launch_file[1]} ] +then + `rm -rf ${launch_file[1]}` +fi +`touch ${launch_file[1]}` + +# node_0çš„world文件 +world_file[0]="src/hector_quadrotor/hector_quadrotor_gazebo/worlds/${world_name}_node_0.world" +if [ -f ${world_file[0]} ] +then + `rm -rf ${world_file[0]}` +fi +`touch ${world_file[0]}` + +# node_1çš„world文件 +world_file[1]="src/hector_quadrotor/hector_quadrotor_gazebo/worlds/${world_name}_node_1.world" +if [ -f ${world_file[1]} ] +then + `rm -rf ${world_file[1]}` +fi +`touch ${world_file[1]}` + +# 写world文件 +for((i=0;i<$gazebo_idex_count;i++)) +do + echo "" >> ${world_file[i]} + echo "" >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo "" >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo " model://sun" >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo "" >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo " model://${world_name}" >> ${world_file[i]} + echo " 0 0 0 0 0 0" >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo "" >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo " 0.68 0.68 0.68 1.0" >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo " 0" >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo "" >> ${world_file[i]} + + tmp_int=$i + if [ "$tmp_int" == "$id0" ] + then + echo " " >> ${world_file[i]} + fi + if [ "$tmp_int" == "$id1" ] + then + echo " " >> ${world_file[i]} + fi + + echo "" >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo " 0" >> ${world_file[i]} + echo " 0.001" >> ${world_file[i]} + echo " 0" >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo "" >> ${world_file[i]} + echo " " >> ${world_file[i]} + echo "" >> ${world_file[i]} +done + +# 写launch文件 +for((i=0;i<$gazebo_idex_count;i++)) +do + + echo "" >> ${launch_file[i]} + echo "" >> ${launch_file[i]} + echo "" >> ${launch_file[i]} + echo "" >> ${launch_file[i]} + echo "" >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo "" >> ${launch_file[i]} + + x=0 + y=0 + t_x=0 + t_y=0 + # tmp0=$node_0_hector_count+$node_1_hector_count + # tmp1=$node_1_hector_count + + tmp_int=$i + + if [ "$tmp_int" == "$id0" ] + then + while [ $x -lt $(($node_0_hector_count + $node_1_hector_count)) ] + do + + for((j=0;j<$node_0_hector_count;j++)) + do + if [ $y -eq 10 ] + then + let t_y=0 + let t_x=t_x+5 + fi + + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo "" >> ${launch_file[i]} + + let t_y=t_y+5 + let y++; + let x++; + done + + for((j=0;j<$node_1_hector_count;j++)) + do + if [ $y -eq 10 ] + then + let t_y=0 + let t_x=t_x+5 + fi + + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo "" >> ${launch_file[i]} + + let t_y=t_y+5 + let y++; + let x++; + done + done + fi + if [ "$tmp_int" == "$id1" ] + then + while [ $x -lt 4 ] + do + + for((j=0;j<$node_0_hector_count;j++)) + do + if [ $y -eq 10 ] + then + let t_y=0 + let t_x=t_x+5 + fi + + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo "" >> ${launch_file[i]} + + let t_y=t_y+5 + let y++; + let x++; + done + + for((j=0;j<$node_1_hector_count;j++)) + do + if [ $y -eq 10 ] + then + let t_y=0 + let t_x=t_x+5 + fi + + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo " " >> ${launch_file[i]} + echo "" >> ${launch_file[i]} + + let t_y=t_y+5 + let y++; + let x++; + done + done + fi + + echo " " >> ${launch_file[i]} + echo "" >> ${launch_file[i]} + echo "" >> ${launch_file[i]} +done diff --git a/Gazebo_Hector_Test/configuration_file b/Gazebo_Hector_Test/configuration_file new file mode 100644 index 0000000..40f946c --- /dev/null +++ b/Gazebo_Hector_Test/configuration_file @@ -0,0 +1,42 @@ +WORLD:"kunming_airport" + +GAZEBO_NODE:"0" +GAZEBO_IP:"192.168.1.7" +SOCKET_PORT:"8888" +HECTOR_NAME:"bebop_0" +HECTOR_NAME:"bebop_1" +HECTOR_NAME:"bebop_2" +HECTOR_NAME:"bebop_3" +HECTOR_NAME:"bebop_4" +HECTOR_NAME:"bebop_5" +HECTOR_NAME:"bebop_6" +HECTOR_NAME:"bebop_7" +HECTOR_NAME:"bebop_8" +HECTOR_NAME:"bebop_9" +HECTOR_NAME:"bebop_10" +HECTOR_NAME:"bebop_11" +HECTOR_NAME:"bebop_12" +HECTOR_NAME:"bebop_13" +HECTOR_NAME:"bebop_14" + +GAZEBO_NODE:"1" +GAZEBO_IP:"192.168.1.231" +SOCKET_PORT:"8888" +HECTOR_NAME:"bebop_15" +HECTOR_NAME:"bebop_16" +HECTOR_NAME:"bebop_17" +HECTOR_NAME:"bebop_18" +HECTOR_NAME:"bebop_19" +HECTOR_NAME:"bebop_20" +HECTOR_NAME:"bebop_21" +HECTOR_NAME:"bebop_22" +HECTOR_NAME:"bebop_23" +HECTOR_NAME:"bebop_24" +HECTOR_NAME:"bebop_25" +HECTOR_NAME:"bebop_26" +HECTOR_NAME:"bebop_27" +HECTOR_NAME:"bebop_28" +HECTOR_NAME:"bebop_29" + + + diff --git a/Gazebo_Hector_Test/src/CMakeLists.txt b/Gazebo_Hector_Test/src/CMakeLists.txt new file mode 120000 index 0000000..581e61d --- /dev/null +++ b/Gazebo_Hector_Test/src/CMakeLists.txt @@ -0,0 +1 @@ +/opt/ros/kinetic/share/catkin/cmake/toplevel.cmake \ No newline at end of file diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/README.md b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/README.md new file mode 100644 index 0000000..8c4b15a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/README.md @@ -0,0 +1,23 @@ +# ROSplane + +This is intended to eventually be a fully-featured fixed-wing autopilot for ROS using ROSflight as the hardware I/O or fcu_sim as the simulator. It is built according to the method published in [Small Unmanned Aircraft: Theory and Practice](http://uavbook.byu.edu/doku.php) by Beard and McLain, so as to allow anyone to easily understand, modify and use the code. This framework is inherently modular and extensively documented so as to aid the user in understanding and extending for personal use. + +The package is intended to be used with fcu\_io or fcu\_sim, for hardware with a naze32 or spracingf3 (or derivatives) or simulation, respectively. + +It is a single ROS package, with several nodes. + +# - Estimator + +The estimator is a standard ekf, as defined mostly in the way in the reference above. It has a attitude filter and a possition filter for gps smoothing. We are probably going to release a full state filter at some point. We are estimating position, velocity, and attitude. The state is then published in the rosplane_msgs/msg/State.msg. + +# - Controller + +Implements a nested PID controller according to the revefereance above. Requires State and Controller_Commands messages to be published. Altitude is controlled in a longitudinal state machine including take-off, climb, desend, and hold zones. Controller can be tuned using rqt_reconfigure. Again a full state controller is in the works and will probably be on a seperate branch. + +# - Path Follower + +Gets the aircraft onto a Current_Path using vector fields. K_path and K_orbit gains can also be tuned using rqt_reconfigure. + +# - Path Manager + +Receives Waypoint messages and creates a path (straight line, fillet, or Dubins) to acheive all the waypoints. diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/CMakeLists.txt new file mode 100644 index 0000000..888ce22 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/CMakeLists.txt @@ -0,0 +1,165 @@ +cmake_minimum_required(VERSION 2.8.3) +project(hector) + +set(CMAKE_CXX_STANDARD 11) +if (NOT CMAKE_BUILD_TYPE) + # Options: Debug, Release, MinSizeRel, RelWithDebInfo + message(STATUS "No build type selected, default to Release") + set(CMAKE_BUILD_TYPE "Release") +endif() + +set(CMAKE_CXX_FLAGS "-fopenmp") + +find_package(catkin REQUIRED COMPONENTS + roscpp + rospy + rosflight_msgs + hector_msgs + dynamic_reconfigure + sensor_msgs + tf +) +find_package(Eigen3 REQUIRED) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a run_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +# Generate dynamic reconfigure parameters in the 'cfg' folder +generate_dynamic_reconfigure_options( + cfg/Follower.cfg + cfg/Controller.cfg +) + +catkin_package( + INCLUDE_DIRS include +# LIBRARIES + CATKIN_DEPENDS roscpp rospy rosflight_msgs hector_msgs +# DEPENDS system_lib +) + +include_directories(include ${catkin_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIRS}) + +## Declare a C++ executable +#add_executable(hector_controller +# src/controller_base.cpp +# src/controller_example.cpp) +#add_dependencies(hector_controller ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_gencfg) +#target_link_libraries(hector_controller ${catkin_LIBRARIES}) + +#add_executable(hector_controller99 +# src/controller_base99.cpp +# src/controller_example99.cpp) +#add_dependencies(hector_controller99 ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_gencfg) +#target_link_libraries(hector_controller99 ${catkin_LIBRARIES}) + +add_executable(hector_pseudo_controller + # src/controller_base.cpp + # src/controller_example.cpp) + src/pseudo_controller_base.cpp + src/pseudo_controller_example.cpp) +add_dependencies(hector_pseudo_controller ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_gencfg) +target_link_libraries(hector_pseudo_controller ${catkin_LIBRARIES}) + +## Declare a C++ executable +#add_executable(hector_estimator +# src/estimator_base.cpp +# src/estimator_example.cpp) +#add_dependencies(hector_estimator ${catkin_EXPORTED_TARGETS}) +#target_link_libraries(hector_estimator ${catkin_LIBRARIES}) + +## Declare a C++ executable +add_executable(hector_estimator_statesub + src/estimator_base_statesub.cpp + ) +add_dependencies(hector_estimator_statesub ${catkin_EXPORTED_TARGETS}) +target_link_libraries(hector_estimator_statesub ${catkin_LIBRARIES}) + +## Declare a C++ executable +#add_executable(hector_estimator_updata_statesub +# src/estimator_base_updata_statesub.cpp +# ) +#add_dependencies(hector_estimator_updata_statesub ${catkin_EXPORTED_TARGETS}) +#target_link_libraries(hector_estimator_updata_statesub ${catkin_LIBRARIES}) + +## Declare a C++ executable +add_executable(hector_estimator_99pub + src/estimator_base_99pub.cpp + ) +add_dependencies(hector_estimator_99pub ${catkin_EXPORTED_TARGETS}) +target_link_libraries(hector_estimator_99pub ${catkin_LIBRARIES}) + +## Declare a C++ executable +add_executable(hector_path_follower + src/path_follower_example.cpp + src/path_follower_base.cpp) +add_dependencies(hector_path_follower ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_gencfg) +target_link_libraries(hector_path_follower ${catkin_LIBRARIES}) + + +## Declare a C++ executable +add_executable(hector_path_manager + src/path_manager_base.cpp + src/path_manager_example.cpp) +add_dependencies(hector_path_manager ${catkin_EXPORTED_TARGETS}) +target_link_libraries(hector_path_manager ${catkin_LIBRARIES}) + + +## Declare a C++ executable +add_executable(hector_path_planner + src/path_planner.cpp) +add_dependencies(hector_path_planner ${catkin_EXPORTED_TARGETS}) +target_link_libraries(hector_path_planner ${catkin_LIBRARIES}) + +## Declare a C++ executable +add_executable(hector_path_point_transfer + src/path_point_transfer.cpp) +add_dependencies(hector_path_point_transfer ${catkin_EXPORTED_TARGETS}) +target_link_libraries(hector_path_point_transfer ${catkin_LIBRARIES}) + +## Declare a C++ executable +add_executable(hector_simple_takeoff + src/simple_takeoff.cpp) +add_dependencies(hector_simple_takeoff ${catkin_EXPORTED_TARGETS}) +target_link_libraries(hector_simple_takeoff ${catkin_LIBRARIES}) + +# ## Declare a C++ executable +# add_executable(udp_send_image +# src/udp_send_image.cpp +# ) +# add_dependencies(udp_send_image +# ${catkin_EXPORTED_TARGETS} +# ) +# target_link_libraries(udp_send_image +# ${catkin_LIBRARIES} +# ${OpenCV_LIBRARIES} +# ) + +# ## Declare a C++ executable +# add_executable(udp_recv_image +# src/udp_recv_image.cpp +# ) +# add_dependencies(udp_recv_image +# ${catkin_EXPORTED_TARGETS} +# ) +# target_link_libraries(udp_recv_image +# ${catkin_LIBRARIES} +# ${OpenCV_LIBRARIES} +# ) + +# ## Declare a C++ executable +# add_executable(udp_send_state +# src/udp_send_state.cpp) +# add_dependencies(udp_send_state ${catkin_EXPORTED_TARGETS}) +# target_link_libraries(udp_send_state ${catkin_LIBRARIES}) + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/cfg/Controller.cfg b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/cfg/Controller.cfg new file mode 100755 index 0000000..0a6124e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/cfg/Controller.cfg @@ -0,0 +1,58 @@ +#!/usr/bin/env python +PACKAGE = "hector" + +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() + +# trim +trim = gen.add_group("Trim") +trim.add("TRIM_E", double_t, 0, "Elevator trim", 0, -1, 1) +trim.add("TRIM_A", double_t, 0, "Aileron trim", 0, -1, 1) +trim.add("TRIM_R", double_t, 0, "Rudder trim", 0, -1, 1) +trim.add("TRIM_T", double_t, 0, "Throttle trim", 0.6, 0, 1) + +# course hold +course = gen.add_group("Course") +course.add("COURSE_KP", double_t, 0, "Course proportional gain", 0.7329, 0, 2) +course.add("COURSE_KD", double_t, 0, "Course derivative gain", 0, -1, 0) +course.add("COURSE_KI", double_t, 0, "Course integral gain", 0.0, 0, 0.2) + +# roll hold +roll = gen.add_group("Roll") +roll.add("ROLL_KP", double_t, 0, "Roll proportional gain", 1.17, 0, 3) +roll.add("ROLL_KD", double_t, 0, "Roll derivative gain", -0.13, -1, 0) +roll.add("ROLL_KI", double_t, 0, "Roll integral gain", 0, 0, 0.2) + +# pitch hold +pitch = gen.add_group("Pitch") +pitch.add("PITCH_KP", double_t, 0, "Pitch proportional gain", 1.0, 0, 3) +pitch.add("PITCH_KD", double_t, 0, "Pitch derivative gain", -0.17, -0.4, 0) +pitch.add("PITCH_KI", double_t, 0, "Pitch integral gain", 0, 0, 0.2) +pitch.add("PITCH_FF", double_t, 0, "Pitch feed forward value", 0, -1, 1) + +# airspeed with pitch hold +as_pitch = gen.add_group("Airspeed with Pitch") +as_pitch.add("AS_PITCH_KP", double_t, 0, "Airspeed with pitch proportional gain", -0.0713, 0, 0.2) +as_pitch.add("AS_PITCH_KD", double_t, 0, "Airspeed with pitch derivative gain", -0.0635, -0.2, 0) +as_pitch.add("AS_PITCH_KI", double_t, 0, "Airspeed with pitch integral gain", 0, 0, 0.2) + +# airspeed with throttle hold +as_thr = gen.add_group("Airspeed with Throttle") +as_thr.add("AS_THR_KP", double_t, 0, "Airspeed with throttle proportional gain", 3.2, 0, 10) +as_thr.add("AS_THR_KD", double_t, 0, "Airspeed with throttle derivative gain", 0, -5, 0) +as_thr.add("AS_THR_KI", double_t, 0, "Airspeed with throttle integral gain", 1.0, 0, 10) + +# altitude hold +alt = gen.add_group("Altitude") +alt.add("ALT_KP", double_t, 0, "Altitude proportional gain", 0.045, 0, 0.1) +alt.add("ALT_KD", double_t, 0, "Altitude derivative gain", 0, -0.05, 0) +alt.add("ALT_KI", double_t, 0, "Altitude integral gain", 0.01, 0, 0.05) + +# side-slip hold +sideslip = gen.add_group("Side Slip") +sideslip.add("BETA_KP", double_t, 0, "Side slip proportional gain", -0.1164, 0, 0.3) +sideslip.add("BETA_KD", double_t, 0, "Side slip derivative gain", 0, -0.15, 0) +sideslip.add("BETA_KI", double_t, 0, "Side slip integral gain", -0.0037111, 0, 0.05) + +exit(gen.generate(PACKAGE, "rosplane", "Controller")) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/cfg/Follower.cfg b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/cfg/Follower.cfg new file mode 100755 index 0000000..56f21be --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/cfg/Follower.cfg @@ -0,0 +1,17 @@ +#!/usr/bin/env python +PACKAGE = "hector" + +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() + +# Chi Infinity +gen.add("CHI_INFTY", double_t, 0, "Chi Infinity", 1.0472, 0 , 1.5708) + +# K Path +gen.add("K_PATH", double_t, 0, "K Path", 0.025, 0, 1) + +# K Orbit +gen.add("K_ORBIT", double_t, 0, "K Orbit", 4.0, 0, 15) + +exit(gen.generate(PACKAGE, "rosplane", "Follower")) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/controller_base.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/controller_base.h new file mode 100644 index 0000000..69c890a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/controller_base.h @@ -0,0 +1,145 @@ +/** + * @file controller_base.h + * + * Base class definition for autopilot controller in chapter 6 of UAVbook, see http://uavbook.byu.edu/doku.php + * + * @author Gary Ellingson + */ + +#ifndef CONTROLLER_BASE_H +#define CONTROLLER_BASE_H + +#include +#include +#include +#include +#include + +#include +#include + +namespace hector +{ + +enum class alt_zones +{ + TAKE_OFF, + CLIMB, + DESCEND, + ALTITUDE_HOLD +}; + +class controller_base +{ +public: + controller_base(); + float spin(); + +protected: + + struct input_s + { + float Ts; /** time step */ + float h; /** altitude */ + float va; /** airspeed */ + float phi; /** roll angle */ + float psi; // + float theta; /** pitch angle */ + float chi; /** course angle */ + float p; /** body frame roll rate */ + float q; /** body frame pitch rate */ + float r; /** body frame yaw rate */ + float Va_c; /** commanded airspeed (m/s) */ + float h_c; /** commanded altitude (m) */ + float chi_c; /** commanded course (rad) */ + float phi_ff; /** feed forward term for orbits (rad) */ + }; + + struct output_s + { + float theta_c; //俯仰角--å³å¹³è¡ŒäºŽæœºèº«è½´çº¿å¹¶æŒ‡å‘飞行器å‰æ–¹çš„å‘é‡ä¸Žåœ°é¢çš„夹角 + float phi_c; //滚转角--机体å标系OZb轴与通过机体OXbè½´çš„é“…åž‚é¢é—´çš„夹角,机体å‘å³æ»šä¸ºæ­£ï¼Œå之为负 + float delta_a; //副翼å移é‡-转弯用-副翼跳å˜é€ æˆæ²¹é—¨å’Œå‡é™èˆµæ•°å€¼çš„波动 + float delta_e; //å‡é™èˆµå移é‡-拉高é™ä½Ž + float delta_r; //æ–¹å‘舵å移é‡-ä¿æŒç¨³å®šï¼Œæ¶ˆé™¤æµ‹æ»‘ + float delta_t; //油门åç§»é‡ + alt_zones current_zone; + }; + + struct params_s + { + double alt_hz; /**< altitude hold zone */ + double alt_toz; /**< altitude takeoff zone */ + double tau; + double c_kp; + double c_kd; + double c_ki; + double r_kp; + double r_kd; + double r_ki; + double p_kp; + double p_kd; + double p_ki; + double p_ff; + double a_p_kp; + double a_p_kd; + double a_p_ki; + double a_t_kp; + double a_t_kd; + double a_t_ki; + double a_kp; + double a_kd; + double a_ki; + double b_kp; + double b_kd; + double b_ki; + double trim_e; + double trim_a; + double trim_r; + double trim_t; + double max_e; + double max_a; + double max_r; + double max_t; + double pwm_rad_e; + double pwm_rad_a; + double pwm_rad_r; + }; + + virtual void control(const struct params_s ¶ms, const struct input_s &input, struct output_s &output) = 0; + +private: + ros::NodeHandle nh_; + ros::NodeHandle nh_private_; + ros::Subscriber vehicle_state_sub_; + ros::Subscriber controller_commands_sub_; + ros::Publisher actuators_pub_; + ros::Publisher internals_pub_; + ros::Timer act_pub_timer_; + + struct params_s params_; /**< params */ + hector_msgs::Controller_Commands controller_commands_; + hector_msgs::State vehicle_state_; + + void vehicle_state_callback(const hector_msgs::StateConstPtr &msg); + void controller_commands_callback(const hector_msgs::Controller_CommandsConstPtr &msg); + bool command_recieved_; + + dynamic_reconfigure::Server server_; + dynamic_reconfigure::Server::CallbackType func_; + + void reconfigure_callback(hector::ControllerConfig &config, uint32_t level); + + /** + * Convert from deflection angle to pwm + */ + void convert_to_pwm(struct output_s &output); + + /** + * Publish the outputs + */ + void actuator_controls_publish(const ros::TimerEvent &); +}; +} //end namespace + +#endif // CONTROLLER_BASE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/controller_base99.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/controller_base99.h new file mode 100644 index 0000000..bf9c01e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/controller_base99.h @@ -0,0 +1,145 @@ +/** + * @file controller_base99.h + * + * Base class definition for autopilot controller in chapter 6 of UAVbook, see http://uavbook.byu.edu/doku.php + * + * @author Gary Ellingson + */ + +#ifndef CONTROLLER_BASE99_H +#define CONTROLLER_BASE99_H + +#include +#include +#include +#include +#include + +#include +#include + +namespace hector +{ + +enum class alt_zones +{ + TAKE_OFF, + CLIMB, + DESCEND, + ALTITUDE_HOLD +}; + +class controller_base99 +{ +public: + controller_base99(); + float spin(); + +protected: + + struct input_s + { + float Ts; /** time step */ + float h; /** altitude */ + float va; /** airspeed */ + float phi; /** roll angle */ + float psi; // + float theta; /** pitch angle */ + float chi; /** course angle */ + float p; /** body frame roll rate */ + float q; /** body frame pitch rate */ + float r; /** body frame yaw rate */ + float Va_c; /** commanded airspeed (m/s) */ + float h_c; /** commanded altitude (m) */ + float chi_c; /** commanded course (rad) */ + float phi_ff; /** feed forward term for orbits (rad) */ + }; + + struct output_s + { + float theta_c; //俯仰角--å³å¹³è¡ŒäºŽæœºèº«è½´çº¿å¹¶æŒ‡å‘飞行器å‰æ–¹çš„å‘é‡ä¸Žåœ°é¢çš„夹角 + float phi_c; //滚转角--机体å标系OZb轴与通过机体OXbè½´çš„é“…åž‚é¢é—´çš„夹角,机体å‘å³æ»šä¸ºæ­£ï¼Œå之为负 + float delta_a; //副翼å移é‡-转弯用-副翼跳å˜é€ æˆæ²¹é—¨å’Œå‡é™èˆµæ•°å€¼çš„波动 + float delta_e; //å‡é™èˆµå移é‡-拉高é™ä½Ž + float delta_r; //æ–¹å‘舵å移é‡-ä¿æŒç¨³å®šï¼Œæ¶ˆé™¤æµ‹æ»‘ + float delta_t; //油门åç§»é‡ + alt_zones current_zone; + }; + + struct params_s + { + double alt_hz; /**< altitude hold zone */ + double alt_toz; /**< altitude takeoff zone */ + double tau; + double c_kp; + double c_kd; + double c_ki; + double r_kp; + double r_kd; + double r_ki; + double p_kp; + double p_kd; + double p_ki; + double p_ff; + double a_p_kp; + double a_p_kd; + double a_p_ki; + double a_t_kp; + double a_t_kd; + double a_t_ki; + double a_kp; + double a_kd; + double a_ki; + double b_kp; + double b_kd; + double b_ki; + double trim_e; + double trim_a; + double trim_r; + double trim_t; + double max_e; + double max_a; + double max_r; + double max_t; + double pwm_rad_e; + double pwm_rad_a; + double pwm_rad_r; + }; + + virtual void control(const struct params_s ¶ms, const struct input_s &input, struct output_s &output) = 0; + +private: + ros::NodeHandle nh_; + ros::NodeHandle nh_private_; + ros::Subscriber vehicle_state_sub_; + ros::Subscriber controller_commands_sub_; + ros::Publisher actuators_pub_; + ros::Publisher internals_pub_; + ros::Timer act_pub_timer_; + + struct params_s params_; /**< params */ + hector_msgs::Controller_Commands controller_commands_; + hector_msgs::State vehicle_state_; + + void vehicle_state_callback(const hector_msgs::StateConstPtr &msg); + void controller_commands_callback(const hector_msgs::Controller_CommandsConstPtr &msg); + bool command_recieved_; + + dynamic_reconfigure::Server server_; + dynamic_reconfigure::Server::CallbackType func_; + + void reconfigure_callback(hector::ControllerConfig &config, uint32_t level); + + /** + * Convert from deflection angle to pwm + */ + void convert_to_pwm(struct output_s &output); + + /** + * Publish the outputs + */ + void actuator_controls_publish(const ros::TimerEvent &); +}; +} //end namespace + +#endif // CONTROLLER_BASE99_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/controller_example.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/controller_example.h new file mode 100644 index 0000000..ee91ab4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/controller_example.h @@ -0,0 +1,53 @@ +#ifndef CONTROLLER_EXAMPLE_H +#define CONTROLLER_EXAMPLE_H + +#include "controller_base.h" + +namespace hector +{ + +class controller_example : public controller_base +{ +public: + controller_example(); +private: + virtual void control(const struct params_s ¶ms, const struct input_s &input, struct output_s &output); + alt_zones current_zone; + + float course_hold(float chi_c, float chi, float phi_ff, float r, const struct params_s ¶ms, float Ts); + float c_error_; + float c_integrator_; + + float roll_hold(float phi_c, float phi, float p, const struct params_s ¶ms, float Ts); + float r_error_; + float r_integrator; + + float pitch_hold(float theta_c, float theta, float q, const struct params_s ¶ms, float Ts); + float p_error_; + float p_integrator_; + + float airspeed_with_pitch_hold(float Va_c, float Va, const struct params_s ¶ms, float Ts); + float ap_error_; + float ap_integrator_; + float ap_differentiator_; + + float airspeed_with_throttle_hold(float Va_c, float Va, const struct params_s ¶ms, float Ts); + float at_error_; + float at_integrator_; + float at_differentiator_; + + float altitiude_hold(float h_c, float h, const struct params_s ¶ms, float Ts); + float a_error_; + float a_integrator_; + float a_differentiator_; + +// float cooridinated_turn_hold(float v, const struct params_s ¶ms, float Ts); +// float ct_error_; +// float ct_integrator_; +// float ct_differentiator_; + + float sat(float value, float up_limit, float low_limit); +}; +} //end namespace + +#endif // CONTROLLER_EXAMPLE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/controller_example99.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/controller_example99.h new file mode 100644 index 0000000..e677bc6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/controller_example99.h @@ -0,0 +1,56 @@ +#ifndef CONTROLLER_EXAMPLE99_H +#define CONTROLLER_EXAMPLE99_H + +#include "controller_base99.h" + +namespace hector +{ + +class controller_example99 : public controller_base99 +{ +public: + controller_example99(); +private: + virtual void control(const struct params_s ¶ms, const struct input_s &input, struct output_s &output); + alt_zones current_zone; + + float course_hold(float chi_c, float chi, float phi_ff, float r, const struct params_s ¶ms, float Ts); + float c_error_; + float c_integrator_; + + float roll_hold(float phi_c, float phi, float p, const struct params_s ¶ms, float Ts); + float r_error_; + float r_integrator; + + float pitch_hold(float theta_c, float theta, float q, const struct params_s ¶ms, float Ts); + float p_error_; + float p_integrator_; + + float airspeed_with_pitch_hold(float Va_c, float Va, const struct params_s ¶ms, float Ts); + float ap_error_; + float ap_integrator_; + float ap_differentiator_; + + float decend_airspeed_with_pitch_hold(float h_c, float h, const struct params_s ¶ms, float Ts); + float decend_airspeed_oil(float h_c, float h, const params_s ¶ms, float Ts); + + float airspeed_with_throttle_hold(float Va_c, float Va, const struct params_s ¶ms, float Ts); + float at_error_; + float at_integrator_; + float at_differentiator_; + + float altitiude_hold(float h_c, float h, const struct params_s ¶ms, float Ts); + float a_error_; + float a_integrator_; + float a_differentiator_; + +// float cooridinated_turn_hold(float v, const struct params_s ¶ms, float Ts); +// float ct_error_; +// float ct_integrator_; +// float ct_differentiator_; + + float sat(float value, float up_limit, float low_limit); +}; +} //end namespace + +#endif // CONTROLLER_EXAMPLE99_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/estimator_base.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/estimator_base.h new file mode 100644 index 0000000..4f5e8a8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/estimator_base.h @@ -0,0 +1,131 @@ +/** + * @file estimator_base.h + * + * Base class definition for autopilot estimator in chapter 8 of UAVbook, see http://uavbook.byu.edu/doku.php + * + * @author Gary Ellingson + */ + +#ifndef ESTIMATOR_BASE_H +#define ESTIMATOR_BASE_H + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define EARTH_RADIUS 6378145.0f + +namespace hector +{ + + +class estimator_base +{ +public: + estimator_base(); + +protected: + + struct input_s + { + float gyro_x; + float gyro_y; + float gyro_z; + float accel_x; + float accel_y; + float accel_z; + float static_pres; + float diff_pres; + bool gps_new; + float gps_n; + float gps_e; + float gps_h; + float gps_Vg; + float gps_course; + bool status_armed; + bool armed_init; + }; + + struct output_s + { + float pn; + float pe; + float h; + float Va; + float alpha; + float beta; + float phi; + float theta; + float psi; + float chi; + float p; + float q; + float r; + float Vg; + float wn; + float we; + }; + + struct params_s + { + double gravity; + double rho; + double sigma_accel; + double sigma_n_gps; + double sigma_e_gps; + double sigma_Vg_gps; + double sigma_course_gps; + double Ts; + }; + + virtual void estimate(const struct params_s ¶ms, const struct input_s &input, struct output_s &output) = 0; + +private: + ros::NodeHandle nh_; + ros::NodeHandle nh_private_; + ros::Publisher vehicle_state_pub_; + ros::Subscriber gps_sub_; + ros::Subscriber imu_sub_; + ros::Subscriber baro_sub_; + ros::Subscriber airspeed_sub_; + ros::Subscriber status_sub_; + + void update(const ros::TimerEvent &); + void gpsCallback(const rosflight_msgs::GPS &msg); + void imuCallback(const sensor_msgs::Imu &msg); + void baroAltCallback(const rosflight_msgs::Barometer &msg); + void airspeedCallback(const rosflight_msgs::Airspeed &msg); + void statusCallback(const rosflight_msgs::Status &msg); + + double update_rate_; + ros::Timer update_timer_; + std::string gps_topic_; + std::string imu_topic_; + std::string baro_topic_; + std::string airspeed_topic_; + std::string status_topic_; + + bool gps_new_; + bool gps_init_; + double init_lat_; /**< Initial latitude in degrees */ + double init_lon_; /**< Initial longitude in degrees */ + float init_alt_; /**< Initial altitude in meters above MSL */ + bool armed_first_time_; /**< Arm before starting estimation */ + bool baro_init_; /**< Initial barometric pressure */ + float init_static_; /**< Initial static pressure (mbar) */ + int baro_count_; /**< Used to grab the first set of baro measurements */ + std::vector init_static_vector_; /**< Used to grab the first set of baro measurements */ + + struct params_s params_; + struct input_s input_; +}; + +} //end namespace + +#endif // ESTIMATOR_BASE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/estimator_base_99pub.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/estimator_base_99pub.h new file mode 100644 index 0000000..b1f1d77 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/estimator_base_99pub.h @@ -0,0 +1,45 @@ + +// modified by kobe and zhangshuai + +#ifndef ESTIMATOR_BASE_PUB_H +#define ESTIMATOR_BASE_PUB_H + +#include +#include +#include +#include +#include + +#define EARTH_RADIUS 6378145.0f + +namespace hector +{ +class estimator_base_99pub +{ +public: + estimator_base_99pub(); + +protected: + +private: + ros::NodeHandle nh_; + ros::NodeHandle nh_private_; + ros::Publisher vehicle_state99_pub_; + ros::Subscriber true_state_sub_; + + void update(const ros::TimerEvent &); + void truestateCallback(const hector_msgs::StateConstPtr &msg); + + double update_rate_; + ros::Timer update_timer_; + + std::string truth_topic_; + + bool state_init_; + hector_msgs::State true_state_; + +}; + +} //end namespace + +#endif // diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/estimator_base_statesub.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/estimator_base_statesub.h new file mode 100644 index 0000000..b0ed859 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/estimator_base_statesub.h @@ -0,0 +1,46 @@ +// modified by kobe and zhangshuai + +#ifndef ESTIMATOR_BASE_SUB_H +#define ESTIMATOR_BASE_SUB_H + +#include +#include +#include //采用新的消æ¯å¤´æ–‡ä»¶ + +#include +#include + +#define EARTH_RADIUS 6378145.0f + +namespace hector +{ +class estimator_base_statesub +{ +public: + estimator_base_statesub(); + +protected: + +private: + ros::NodeHandle nh_; + ros::NodeHandle nh_private_; + ros::Publisher vehicle_state_pub_; + ros::Subscriber state29_sub_; + void update(const ros::TimerEvent &); + void state99Callback(const hector_msgs::State29ConstPtr &msg); + + double update_rate_; + ros::Timer update_timer_; + std::string state29_topic_; + + double init_lat_; /**< Initial latitude in degrees */ + double init_lon_; /**< Initial longitude in degrees */ + float init_alt_; /**< Initial altitude in meters above MSL */ + + bool state_init_; + hector_msgs::State29 state29_; +}; + +} //end namespace + +#endif // diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/estimator_base_updata_statesub.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/estimator_base_updata_statesub.h new file mode 100644 index 0000000..9538998 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/estimator_base_updata_statesub.h @@ -0,0 +1,46 @@ +// modified by kobe + +#ifndef ESTIMATOR_BASE_UPDATA_SUB_H +#define ESTIMATOR_BASE_UPDATA_SUB_H + +#include +#include +#include + +#include +#include + +#define EARTH_RADIUS 6378145.0f + +namespace hector +{ +class estimator_base_updata_statesub +{ +public: + estimator_base_updata_statesub(); + +protected: + +private: + ros::NodeHandle nh_; + ros::NodeHandle nh_private_; + ros::Publisher vehicle_state_pub_; + ros::Subscriber state29_sub_; + void update(const ros::TimerEvent &); + void state99Callback(const hector_msgs::Up_Data_NewConstPtr &msg); + + double update_rate_; + ros::Timer update_timer_; + std::string state29_topic_; + + double init_lat_; /**< Initial latitude in degrees */ + double init_lon_; /**< Initial longitude in degrees */ + float init_alt_; /**< Initial altitude in meters above MSL */ + + bool state_init_; + hector_msgs::Up_Data_New state29_; +}; + +} //end namespace + +#endif // diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/estimator_example.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/estimator_example.h new file mode 100644 index 0000000..647b227 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/estimator_example.h @@ -0,0 +1,73 @@ +#ifndef ESTIMATOR_EXAMPLE_H +#define ESTIMATOR_EXAMPLE_H + +#include "estimator_base.h" + +#include +#include + +namespace hector +{ + +class estimator_example : public estimator_base +{ +public: + estimator_example(); + +private: + virtual void estimate(const params_s ¶ms, const input_s &input, output_s &output); + +// float gps_n_old_; +// float gps_e_old_; +// float gps_Vg_old_; +// float gps_course_old_; + + double lpf_a_; + float alpha_; + float alpha1_; + int N_; + + float lpf_gyro_x_; + float lpf_gyro_y_; + float lpf_gyro_z_; + float lpf_static_; + float lpf_diff_; + float lpf_accel_x_; + float lpf_accel_y_; + float lpf_accel_z_; + + float phat_; + float qhat_; + float rhat_; + float Vwhat_; + float phihat_; + float thetahat_; + float psihat_; + Eigen::Vector2f xhat_a_; // 2 + Eigen::Matrix2f P_a_; // 2x2 + + Eigen::VectorXf xhat_p_; // 7 + Eigen::MatrixXf P_p_; // 7x7 + + Eigen::Matrix2f Q_a_; // 2x2 + float R_accel_; + Eigen::Vector2f f_a_; // 2 + Eigen::Matrix2f A_a_; // 2x2 + float h_a_; + Eigen::Vector2f C_a_; // 2 + Eigen::Vector2f L_a_; // 2 + + Eigen::MatrixXf Q_p_; // 7x7 + Eigen::MatrixXf R_p_; // 6x6 + Eigen::VectorXf f_p_; // 7 + Eigen::MatrixXf A_p_; // 7x7 + float h_p_; + Eigen::VectorXf C_p_; // 7 + Eigen::VectorXf L_p_; // 7 + + void check_xhat_a(); + +}; +} //end namespace + +#endif // ESTIMATOR_EXAMPLE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/path_follower_base.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/path_follower_base.h new file mode 100644 index 0000000..0bd3368 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/path_follower_base.h @@ -0,0 +1,103 @@ +//* @author AIRC-DA group,questions contack kobe. + +#ifndef PATH_FOLLOWER_BASE_H +#define PATH_FOLLOWER_BASE_H + +#include +#include +#include +#include +#include +#include +#include +#define EARTH_RADIUS 6378145.0f +namespace hector +{ + +enum class path_type +{ + Orbit, + Line, + Star //add by kobe +}; + +class path_follower_base +{ +public: + path_follower_base(); + float spin(); + +protected: + + struct input_s + { + enum path_type p_type; + float Va_d; + float r_path[3]; + float q_path[3]; + float c_orbit[3]; + float rho_orbit; + int lam_orbit; + float pn; /** position north */ + float pe; /** position east */ + float h; /** altitude */ + float Va; /** airspeed */ + float chi; /** course angle */ + float h_c_path; /** goal attitude */ + float Va_c_path; /** goal attitude */ + bool landing; + bool takeoff; + }; + + struct output_s + { + double Va_c; /** commanded airspeed (m/s) */ + double h_c; /** commanded altitude (m) */ + double chi_c; /** commanded course (rad) */ + double phi_ff; /** feed forward term for orbits (rad) */ + }; + + struct params_s + { + double chi_infty; + double k_path; + double k_orbit; + }; + + virtual void follow(const struct params_s ¶ms, const struct input_s &input, struct output_s &output) = 0; + +private: + ros::NodeHandle nh_; + ros::NodeHandle nh_private_; + ros::Subscriber vehicle_state_sub_; + ros::Subscriber bebop1_state_sub_; + ros::Subscriber current_path_sub_; + + ros::Publisher controller_commands_pub_; + + double update_rate_ = 100.0; + ros::Timer update_timer_; + + hector_msgs::Controller_Commands controller_commands_; + struct params_s params_; /**< params */ + struct input_s input_; + + void vehicle_state_callback(const hector_msgs::StateConstPtr &msg); + bool state_init_; + + void bebop1_state_callback(const nav_msgs::Odometry::ConstPtr &msg); + float Quaternion_to_Euler(float,float,float,float); + + void current_path_callback(const hector_msgs::Current_PathConstPtr &msg); + bool current_path_init_; + + dynamic_reconfigure::Server server_; + dynamic_reconfigure::Server::CallbackType func_; + void reconfigure_callback(hector::FollowerConfig &config, uint32_t level); + + void update(const ros::TimerEvent &); +}; + +} // end namespace + +#endif // PATH_FOLLOWER_BASE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/path_follower_example.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/path_follower_example.h new file mode 100644 index 0000000..830b1d1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/path_follower_example.h @@ -0,0 +1,18 @@ +#ifndef PATH_FOLLOWER_EXAMPLE_H +#define PATH_FOLLOWER_EXAMPLE_H + +#include "path_follower_base.h" + +namespace hector +{ + +class path_follower_example : public path_follower_base +{ +public: + path_follower_example(); +private: + virtual void follow(const struct params_s ¶ms, const struct input_s &input, struct output_s &output); +}; + +} //end namespace +#endif // PATH_FOLLOWER_EXAMPLE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/path_manager_base.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/path_manager_base.h new file mode 100644 index 0000000..e36aaa8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/path_manager_base.h @@ -0,0 +1,122 @@ +//* @author AIRC-DA group,questions contack kobe. + +#ifndef PATH_MANAGER_BASE_H +#define PATH_MANAGER_BASE_H + +#include +#include +#include +#include +#include +// #include +#include +#include +#include +#include +#include +#include +#include +// #include +#include +#define EARTH_RADIUS 6378145.0f +namespace hector +{ +class path_manager_base +{ +public: + path_manager_base(); + +protected: + //modified by kobe + + struct waypoint_s + { + float w[3]; + float lat; + float lon; + float chi_d; + bool chi_valid; + float Va_d; + bool landing; + bool takeoff; + }; + + std::vector waypoints_; + + waypoint_s waypoint_start_; + waypoint_s waypoint_end_; + bool waypoint_received_; + + int num_waypoints_; + int idx_a_; /** index to the waypoint that was most recently achieved */ + + float min_distance_; + double min_distance_titude; + bool show; //add by kobe + bool show2; + struct input_s + { + float pn; /** position north */ + float pe; /** position east */ + float lat; //latitude + float lon; //lontitude + float h; /** altitude */ + float chi; /** course angle */ + float va; //add by kobe + }; + + struct output_s + { + float Va_c; + int flag; /** Inicates strait line or orbital path (1 is line, 0 is orbit, 2 is star) modified by kobe*/ + float Va_d; /** Desired airspeed (m/s) */ + float r[3]; /** Vector to origin of straight line path (m) */ + float q[3]; /** Unit vector, desired direction of travel for line path */ + float c[3]; /** Center of orbital path (m) */ + float gxy[2]; /** x-y-coordinate (m) */ + float gll[2]; /** latitude-longtitude */ + float rho; /** Radius of orbital path (m) */ + float h_c; + bool landing; + bool takeoff; + int8_t lambda; /** Direction of orbital path (cw is 1, ccw is -1) */ +}; + + struct params_s + { + double R_min; + }; + + virtual void manage(const struct params_s ¶ms, const struct input_s &input, struct output_s &output) = 0; + +private: + + ros::NodeHandle nh_; + ros::NodeHandle nh_private_; + ros::Subscriber vehicle_state_sub_; /**< vehicle state subscription */ + ros::Subscriber bebop1_state_sub_; + + ros::Subscriber new_waypoint_sub_; /**< new waypoint subscription */ + ros::Publisher current_path_pub_; /**< controller commands publication */ + ros::Publisher goal_info_pub_; /**< goal info publication */ + ros::Publisher down_data_pub_; + ros::Subscriber waypoint_received_sub_; + struct params_s params_; + + hector_msgs::State vehicle_state_; /**< vehicle state */ + nav_msgs::Odometry bebop1_state_; + + double update_rate_; + ros::Timer update_timer_; + + void vehicle_state_callback(const hector_msgs::StateConstPtr &msg); + void bebop1_state_callback(const nav_msgs::Odometry::ConstPtr &msg); + float Quaternion_to_Euler(float,float,float,float); + + bool state_init_; + void new_waypoint_callback(const hector_msgs::Waypoint &msg); + void current_path_publish(const ros::TimerEvent &); + void waypoint_received_callback(const hector_msgs::Waypoint &msg); +}; +} //end namespace +#endif // PATH_MANAGER_BASE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/path_manager_example.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/path_manager_example.h new file mode 100644 index 0000000..69600eb --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/path_manager_example.h @@ -0,0 +1,78 @@ +#ifndef PATH_MANAGER_EXAMPLE_H +#define PATH_MANAGER_EXAMPLE_H + +#include "path_manager_base.h" +#include +//#include + + +#define M_PI_F 3.14159265358979323846f +#define M_PI_2_F 1.57079632679489661923f +namespace hector +{ +enum class fillet_state +{ + STRAIGHT, + ORBIT +}; + +enum class dubin_state +{ + FIRST, + BEFORE_H1, + BEFORE_H1_WRONG_SIDE, + STRAIGHT, + BEFORE_H3, + BEFORE_H3_WRONG_SIDE +}; + +class path_manager_example : public path_manager_base +{ +public: + path_manager_example(); +private: + virtual void manage(const struct params_s ¶ms, const struct input_s &input, struct output_s &output); + + void manage_line(const struct params_s ¶ms, const struct input_s &input, struct output_s &output); + void manage_star(const struct params_s ¶ms, const struct input_s &input, struct output_s &output);//add by kobe + void manage_fillet(const struct params_s ¶ms, const struct input_s &input, struct output_s &output); + fillet_state fil_state_; + void manage_dubins(const struct params_s ¶ms, const struct input_s &input, struct output_s &output); + dubin_state dub_state_; + double earth_distance(double, double, double, double); + + bool judge_condition1; + bool judge_condition2; + bool judge_condition3; + bool judge_condition4; + bool judge_condition5; + struct dubinspath_s + { + + Eigen::Vector3f ps; /** the start position */ + float chis; /** the start course angle */ + Eigen::Vector3f pe; /** the end position */ + float chie; /** the end course angle */ + float R; /** turn radius */ + float L; /** length of the path */ + Eigen::Vector3f cs; /** center of the start circle */ + int lams; /** direction of the start circle */ + Eigen::Vector3f ce; /** center of the endcircle */ + int lame; /** direction of the end circle */ + Eigen::Vector3f w1; /** vector defining half plane H1 */ + Eigen::Vector3f q1; /** unit vector along striaght line path */ + Eigen::Vector3f w2; /** vector defining half plane H2 */ + Eigen::Vector3f w3; /** vector defining half plane H3 */ + Eigen::Vector3f q3; /** unit vector defining direction of half plane H3 */ + }; + + + + struct dubinspath_s dubinspath_; + void dubinsParameters(const struct waypoint_s start_node, const struct waypoint_s end_node, float R); + + Eigen::Matrix3f rotz(float theta); + float mo(float in); +}; +} //end namespace +#endif // PATH_MANAGER_EXAMPLE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/path_point_transfer.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/path_point_transfer.h new file mode 100644 index 0000000..a3922b2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/path_point_transfer.h @@ -0,0 +1,123 @@ +/** + * @file path_manager_base.h + * + * Base class definition for autopilot path follower in chapter 10 of UAVbook, see http://uavbook.byu.edu/doku.php + * + * @author Gary Ellingson + * adapted by Judd Mehr and Brian Russel for RosPlane software + */ + +#ifndef PATH_POINT_TRANSFER_H +#define PATH_POINT_TRANSFER_H + +#include +#include +#include +#include +// #include +// #include +#include +#include +#include +#include +#include +#include +#include + +namespace hector +{ +class path_point_transfer +{ +public: + path_point_transfer(); + + ~path_point_transfer(); + +protected: + //modified by kobe + + struct waypoint_s + { + float w[3]; + float lat; + float lon; + float chi_d; + bool chi_valid; + float Va_d; + }; + + std::vector waypoints_; + + waypoint_s waypoint_start_; + waypoint_s waypoint_end_; + bool waypoint_received_; + + int num_waypoints_; + int idx_a_; /** index to the waypoint that was most recently achieved */ + + float min_distance_; + double min_distance_titude; + bool show; //add by kobe + // struct input_s + // { + // float pn; /** position north */ + // float pe; /** position east */ + // float lat; //latitude + // float lon; //lontitude + // float h; /** altitude */ + // float chi; /** course angle */ + // float va; //add by kobe + // }; + + // struct output_s + // { + // int flag; /** Inicates strait line or orbital path (1 is line, 0 is orbit, 2 is star) modified by kobe*/ + // float Va_d; /** Desired airspeed (m/s) */ + // float r[3]; /** Vector to origin of straight line path (m) */ + // float q[3]; /** Unit vector, desired direction of travel for line path */ + // float c[3]; /** Center of orbital path (m) */ + // float gxy[2]; /** x-y-coordinate (m) */ + // float gll[2]; /** latitude-longtitude */ + // float rho; /** Radius of orbital path (m) */ + // float h_c; + // int8_t lambda; /** Direction of orbital path (cw is 1, ccw is -1) */ + // }; + + struct params_s + { + double R_min; + }; + + // virtual void manage(const struct params_s ¶ms, const struct input_s &input, struct output_s &output) = 0; + +private: + ros::NodeHandle nh_; + ros::NodeHandle nh_private_; + ros::Subscriber vehicle_state_sub_; /**< vehicle state subscription */ + ros::Subscriber bebop1_state_sub_; + + ros::Subscriber new_waypoint_sub_; /**< new waypoint subscription */ + ros::Publisher current_path_pub_; /**< controller commands publication */ + // ros::Publisher goal_info_pub_; /**< goal info publication */ + // ros::Publisher down_data_pub_; + ros::Subscriber waypoint_received_sub_; + struct params_s params_; + + hector_msgs::State vehicle_state_; /**< vehicle state */ + hector_msgs::Down_Data_New point_state_; + nav_msgs::Odometry bebop1_state_; + + double update_rate_; + ros::Timer update_timer_; + + void vehicle_state_callback(const hector_msgs::StateConstPtr &msg); + void bebop1_state_callback(const nav_msgs::Odometry::ConstPtr &msg); + // float Quaternion_to_Euler(float, float, float, float); + + bool state_init_; + void new_waypoint_callback(const hector_msgs::Down_Data_NewConstPtr &msg); + void current_path_publish(const ros::TimerEvent &); + // void waypoint_received_callback(const hector_msgs::Waypoint &msg); +}; +} // namespace hector +#endif // PATH_MANAGER_BASE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/pseudo_controller_base.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/pseudo_controller_base.h new file mode 100644 index 0000000..f9505bb --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/pseudo_controller_base.h @@ -0,0 +1,137 @@ +/** + * + * Refer autopilot controller in chapter 6 of UAVbook, see http://uavbook.byu.edu/doku.php + *pseudo fix-wing 四旋翼模拟固定翼飞行,订阅当å‰å®žé™…åŠå‘½ä»¤çš„速度ã€é«˜åº¦å’Œè§’度,å‘布å‘å‰ï¼Œå‘上下速度和角度 + * @author AIRC-DA group,questions contack kobe. + */ + +#ifndef PSEUDO_CONTROLLER_BASE_H +#define PSEUDO_CONTROLLER_BASE_H + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +namespace hector +{ + +enum class alt_zones +{ + PREPARE, + TAKE_OFF, + CLIMB, + DESCEND, + ALTITUDE_HOLD, + LANDING +}; + +class pseudo_controller_base +{ +public: + pseudo_controller_base(); + float spin(); + +protected: + + struct input_s + { + float Ts; /** time step */ + float va; /** airspeed */ + float h; /** altitude */ + float chi; /** course angle */ + float Va_c; /** commanded airspeed (m/s) */ + float h_c; /** commanded altitude (m) */ + float chi_c; /** commanded course (north)(-pi to pi,clockwise:-) */ + bool takeoff; + bool landing; + }; + + struct output_s + { + //float theta_c; //俯仰角--å³å¹³è¡ŒäºŽæœºèº«è½´çº¿å¹¶æŒ‡å‘飞行器å‰æ–¹çš„å‘é‡ä¸Žåœ°é¢çš„夹角 + //float phi_c; //滚转角--机体å标系OZb轴与通过机体OXbè½´çš„é“…åž‚é¢é—´çš„夹角,机体å‘å³æ»šä¸ºæ­£ï¼Œå之为负 + //float delta_a; //副翼å移é‡-转弯用-副翼跳å˜é€ æˆæ²¹é—¨å’Œå‡é™èˆµæ•°å€¼çš„波动 + //float delta_e; //å‡é™èˆµå移é‡-拉高é™ä½Ž + //float delta_r; //æ–¹å‘舵å移é‡-ä¿æŒç¨³å®šï¼Œæ¶ˆé™¤æµ‹æ»‘ + //float delta_t; //油门åç§»é‡ + float forward_trans; //å‰è¿›åŠ›åº¦ + float up_down_trans; //å‘上ã€å‘下力度,上正下负 + float left_right_trans; //å‘å·¦å³åŠ›åº¦,左正å³è´Ÿ + float roll_trans; //å·¦å³æ»šè½¬ï¼Œxè½´,逆时针为正,顺时针为负,[-pi/2,pi/2] + float rotate_trans; //z旋转,逆时针为正,顺时针为负,[-pi/2,pi/2] + float rotate_value; + alt_zones current_zone; + }; + + struct params_s + { + double alt_hz; /**< altitude hold zone */ + double alt_toz; /**< altitude takeoff zone */ + double tau; + double c_kp; + //double c_kd; + double c_ki; + + double a_p_kp; + double a_p_kd; + double a_p_ki; + + double a_t_ki; + double a_t_kp; + double a_t_kd; + + double a_kp; + double a_kd; + double a_ki; + + double trim_t; + //double max_a;y + double max_t; + }; + bool reached; + virtual void control(const struct params_s ¶ms, const struct input_s &input, struct output_s &output) = 0; + +private: + ros::NodeHandle nh_; + ros::NodeHandle nh_private_; + ros::Subscriber vehicle_state_sub_; + ros::Subscriber bebop1_state_sub_; + + ros::Subscriber controller_commands_sub_; + ros::Publisher pesudors_pub_;//actuators + ros::Publisher internals_pub_; + ros::Timer act_pub_timer_; + + struct params_s params_; /**< params */ + hector_msgs::Controller_Commands controller_commands_; + hector_msgs::State vehicle_state_; + nav_msgs::Odometry bebop1_state_; + + void vehicle_state_callback(const hector_msgs::StateConstPtr &msg); + void bebop1_state_callback(const nav_msgs::Odometry::ConstPtr &msg); + float Quaternion_to_Euler(float,float,float,float); + + void controller_commands_callback(const hector_msgs::Controller_CommandsConstPtr &msg); + bool command_recieved_; + + dynamic_reconfigure::Server server_; + dynamic_reconfigure::Server::CallbackType func_; + + void reconfigure_callback(hector::ControllerConfig &config, uint32_t level); + + /*Convert from deflection angle to pwm*/ + //void convert_to_pwm(struct output_s &output); + + /* Publish the outputs */ + void actuator_controls_publish(const ros::TimerEvent &); +}; +} //end namespace + +#endif // PSEUDO_CONTROLLER_BASE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/pseudo_controller_example.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/pseudo_controller_example.h new file mode 100644 index 0000000..b804ebb --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/pseudo_controller_example.h @@ -0,0 +1,66 @@ +#ifndef PSEUDO_CONTROLLER_EXAMPLE_H +#define PSEUDO_CONTROLLER_EXAMPLE_H + +#include "pseudo_controller_base.h" + +namespace hector +{ + +class pseudo_controller_example : public pseudo_controller_base +{ +public: + pseudo_controller_example(); +private: + virtual void control(const struct params_s ¶ms, const struct input_s &input, struct output_s &output); + alt_zones current_zone; + + float pseudo_course_hold(float chi,float chi_c, const params_s ¶ms, float Ts); + //float course_hold(float chi_c, float chi, float phi_ff, float r, const struct params_s ¶ms, float Ts); + float c_error_; + float c_integrator_; + + + float r_error_; + float r_integrator_; + + + //float roll_hold(float phi_c, float phi, float p, const struct params_s ¶ms, float Ts); + //float r_error_; + //float r_integrator_; + + //float pitch_hold(float theta_c, float theta, float q, const struct params_s ¶ms, float Ts); + //float p_error_; + //float p_integrator_; + + + float pseudo_course(float chi, float chi_c); + float pseudo_left_right(float chi, float chi_c, float forward_trans); + + //float airspeed_with_pitch_hold(float Va_c, float Va, const struct params_s ¶ms, float Ts); + float pseudo_pitch_hold(float h_c, float h, const struct params_s ¶ms, float Ts); + float ap_error_; + float ap_integrator_; + float ap_differentiator_; + + //float airspeed_with_throttle_hold(float Va_c, float Va, const struct params_s ¶ms, float Ts); + float pseudo_throttle_hold(float Va_c, float Va, const params_s ¶ms, float Ts); + float at_error_; + float at_integrator_; + float at_differentiator_; + + //float altitiude_hold(float h_c, float h, const struct params_s ¶ms, float Ts); + float pseudo_altitiude_hold(float h_c, float h, const params_s ¶ms, float Ts); + float a_error_; + float a_integrator_; + float a_differentiator_; + +// float cooridinated_turn_hold(float v, const struct params_s ¶ms, float Ts); +// float ct_error_; +// float ct_integrator_; +// float ct_differentiator_; + + float sat(float value, float up_limit, float low_limit); +}; +} //end namespace + +#endif // PSEUDO_CONTROLLER_EXAMPLE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/udp_recv_image.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/udp_recv_image.h new file mode 100644 index 0000000..072f7b3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/udp_recv_image.h @@ -0,0 +1,42 @@ +/************************************************************************ + * * + * Author: ake * + * Date: 2018-10-23 * + * Description: recv image of the camera to server with udp * + * * + ************************************************************************/ +#ifndef _UDP_RECV_IMAGE_H_ +#define _UDP_RECV_IMAGE_H_ + +#include "packageHeader.h" + + + +namespace rosplane +{ + +class udp_recv_image +{ +public: + udp_recv_image(); + ~udp_recv_image(); + void recv_image(); + void udp_close(); + +private: + ros::NodeHandle nh_; + image_transport::ImageTransport it; + image_transport::Publisher image_pub; + + struct PackageHeader* packageHead; + + int server_sockfd; + struct sockaddr_in my_addr; + unsigned int sin_size; + struct sockaddr_in remote_addr; + unsigned char frameBuffer[BUF_SIZE]; +}; + +} + +#endif diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/udp_send_image.h b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/udp_send_image.h new file mode 100644 index 0000000..fab6465 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/include/udp_send_image.h @@ -0,0 +1,42 @@ +/************************************************************************ + * * + * Author: ake * + * Date: 2018-10-23 * + * Description: send image of the camera to server with udp * + * * + ************************************************************************/ +#ifndef _UDP_SEND_IMAGE_H_ +#define _UDP_SEND_IMAGE_H_ + +#include "packageHeader.h" + + + +namespace hector +{ + +class udp_send_image +{ +public: + udp_send_image(); + ~udp_send_image(); + void imageCallback(const sensor_msgs::ImageConstPtr& tem_msg); + void udp_close(); + +private: + ros::NodeHandle nh_; + image_transport::ImageTransport it; + image_transport::Subscriber image_sub; + + struct PackageHeader packageHead; + + int client_sockfd; + + bool bConnected; + struct sockaddr_in remote_addr; + unsigned char frameBuffer[BUF_SIZE]; +}; + +} + +#endif diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/package.xml new file mode 100644 index 0000000..1830c4d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/package.xml @@ -0,0 +1,33 @@ + + + hector + 0.0.0 + The hector package + + Gary Ellingson + + Gary Ellingson + + BSD + + catkin + cmake_modules + dynamic_reconfigure + rosflight_msgs + hector_msgs + roscpp + rospy + sensor_msgs + geometry_msgs + dynamic_reconfigure + rosflight_msgs + hector_msgs + roscpp + rospy + sensor_msgs + geometry_msgs + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/param/aerosonde.yaml b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/param/aerosonde.yaml new file mode 100644 index 0000000..7339e54 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/param/aerosonde.yaml @@ -0,0 +1,33 @@ +TRIM_E: 0 +TRIM_A: 0 +TRIM_R: 0 +TRIM_T: 0.6 + +COURSE_KP: 0.7329 +COURSE_KD: 0 +COURSE_KI: 0.07 + +ROLL_KP: 1.17 +ROLL_KD: -0.13 +ROLL_KI: 0 + +PITCH_KP: 0.1 +PITCH_KD: -0.017 +PITCH_KI: 0 +PITCH_FF: 0 + +AS_PITCH_KP: -0.0713 +AS_PITCH_KD: -0.0635 +AS_PITCH_KI: 0 + +AS_THR_KP: 3.2 +AS_THR_KD: 0 +AS_THR_KI: 1.0 + +ALT_KP: 0.045 +ALT_KD: 0 +ALT_KI: 0.01 + +BETA_KP: -0.1164 +BETA_KD: 0 +BETA_KI: -0.0037111 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/param/bixler.yaml b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/param/bixler.yaml new file mode 100644 index 0000000..b1ab278 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/param/bixler.yaml @@ -0,0 +1,41 @@ +TRIM_E: 0 +TRIM_A: 0 +TRIM_R: 0 +TRIM_T: 0.6 + +COURSE_KP: 0.7329 +COURSE_KD: 0 +COURSE_KI: 0.0 + +ROLL_KP: 1.2855 +ROLL_KD: -0.1 +ROLL_KI: 0 + +PITCH_KP: 1.0 +PITCH_KD: -0.17 +PITCH_KI: 0 +PITCH_FF: 0 + +AS_PITCH_KP: -0.0713 +AS_PITCH_KD: -0.0635 +AS_PITCH_KI: 0 + + +AS_THR_KP: 3.2 +AS_THR_KD: 0 +AS_THR_KI: 1.0 + + +ALT_KP: 0.045 +ALT_KD: 0 +ALT_KI: 0.01 + + +BETA_KP: -0.1164 +BETA_KD: 0 +BETA_KI: -0.0037111 + + +CHI_INFTY: 1.0472 +K_PATH: 0.025 +K_ORBIT: 2.00 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/controller_base.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/controller_base.cpp new file mode 100644 index 0000000..7aeb8d3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/controller_base.cpp @@ -0,0 +1,203 @@ +#include "controller_base.h" +#include "controller_example.h" + +namespace hector +{ + +controller_base::controller_base(): + nh_(ros::NodeHandle()), + nh_private_(ros::NodeHandle()) +{ + vehicle_state_sub_ = nh_.subscribe("state", 10, &controller_base::vehicle_state_callback, this); + controller_commands_sub_ = nh_.subscribe("controller_commands", 10, &controller_base::controller_commands_callback, + this); + + memset(&vehicle_state_, 0, sizeof(vehicle_state_)); + memset(&controller_commands_, 0, sizeof(controller_commands_)); + + nh_private_.param("TRIM_E", params_.trim_e, 0.0); + nh_private_.param("TRIM_A", params_.trim_a, 0.0); + nh_private_.param("TRIM_R", params_.trim_r, 0.0); + nh_private_.param("TRIM_T", params_.trim_t, 0.6); + nh_private_.param("PWM_RAD_E", params_.pwm_rad_e, 1.0); + nh_private_.param("PWM_RAD_A", params_.pwm_rad_a, 1.0); + nh_private_.param("PWM_RAD_R", params_.pwm_rad_r, 1.0); + nh_private_.param("ALT_TOZ", params_.alt_toz, 20.0); /**< altitude takeoff zone */ + nh_private_.param("ALT_HZ", params_.alt_hz, 10.0); /**< altitude hold zone */ + nh_private_.param("TAU", params_.tau, 5.0); + nh_private_.param("COURSE_KP", params_.c_kp, 0.7329); + nh_private_.param("COURSE_KD", params_.c_kd, 0.0); + nh_private_.param("COURSE_KI", params_.c_ki, 0.0); + nh_private_.param("ROLL_KP", params_.r_kp, 1.2855); + nh_private_.param("ROLL_KD", params_.r_kd, -0.325); + nh_private_.param("ROLL_KI", params_.r_ki, 0.0);//0.10f); + nh_private_.param("PITCH_KP", params_.p_kp, 1.0); + nh_private_.param("PITCH_KD", params_.p_kd, -0.17); + nh_private_.param("PITCH_KI", params_.p_ki, 0.0); + nh_private_.param("PITCH_FF", params_.p_ff, 0.0); + nh_private_.param("AS_PITCH_KP", params_.a_p_kp, -0.0713); + nh_private_.param("AS_PITCH_KD", params_.a_p_kd, -0.0635); + nh_private_.param("AS_PITCH_KI", params_.a_p_ki, 0.0); + nh_private_.param("AS_THR_KP", params_.a_t_kp, 3.2); + nh_private_.param("AS_THR_KD", params_.a_t_kd, 0.0); + nh_private_.param("AS_THR_KI", params_.a_t_ki, 0.0); + nh_private_.param("ALT_KP", params_.a_kp, 0.045); + nh_private_.param("ALT_KD", params_.a_kd, 0.0); + nh_private_.param("ALT_KI", params_.a_ki, 0.01); + nh_private_.param("BETA_KP", params_.b_kp, -0.1164); + nh_private_.param("BETA_KD", params_.b_kd, 0.0); + nh_private_.param("BETA_KI", params_.b_ki, -0.0037111); + nh_private_.param("MAX_E", params_.max_e, 0.610); + nh_private_.param("MAX_A", params_.max_a, 0.523); + nh_private_.param("MAX_R", params_.max_r, 0.523); + nh_private_.param("MAX_T", params_.max_t, 1.0); + + func_ = boost::bind(&controller_base::reconfigure_callback, this, _1, _2); + server_.setCallback(func_); + + actuators_pub_ = nh_.advertise("command", 10); + internals_pub_ = nh_.advertise("controller_inners", 10); + act_pub_timer_ = nh_.createTimer(ros::Duration(1.0/100.0), &controller_base::actuator_controls_publish, this); + + command_recieved_ = false; +} + +void controller_base::vehicle_state_callback(const hector_msgs::StateConstPtr &msg) +{ + vehicle_state_ = *msg; +} + +void controller_base::controller_commands_callback(const hector_msgs::Controller_CommandsConstPtr &msg) +{ + command_recieved_ = true; + controller_commands_ = *msg; +} + +void controller_base::reconfigure_callback(hector::ControllerConfig &config, uint32_t level) +{ + params_.trim_e = config.TRIM_E; + params_.trim_a = config.TRIM_A; + params_.trim_r = config.TRIM_R; + params_.trim_t = config.TRIM_T; + + params_.c_kp = config.COURSE_KP; + params_.c_kd = config.COURSE_KD; + params_.c_ki = config.COURSE_KI; + + params_.r_kp = config.ROLL_KP; + params_.r_kd = config.ROLL_KD; + params_.r_ki = config.ROLL_KI; + + params_.p_kp = config.PITCH_KP; + params_.p_kd = config.PITCH_KD; + params_.p_ki = config.PITCH_KI; + params_.p_ff = config.PITCH_FF; + + params_.a_p_kp = config.AS_PITCH_KP; + params_.a_p_kd = config.AS_PITCH_KD; + params_.a_p_ki = config.AS_PITCH_KI; + + params_.a_t_kp = config.AS_THR_KP; + params_.a_t_kd = config.AS_THR_KD; + params_.a_t_ki = config.AS_THR_KI; + + params_.a_kp = config.ALT_KP; + params_.a_kd = config.ALT_KD; + params_.a_ki = config.ALT_KI; + + params_.b_kp = config.BETA_KP; + params_.b_kd = config.BETA_KD; + params_.b_ki = config.BETA_KI; +} + +void controller_base::convert_to_pwm(controller_base::output_s &output) +{ + output.delta_e = output.delta_e*params_.pwm_rad_e; + output.delta_a = output.delta_a*params_.pwm_rad_a; + output.delta_r = output.delta_r*params_.pwm_rad_r; +} + +void controller_base::actuator_controls_publish(const ros::TimerEvent &) +{ + struct input_s input; + input.h = -vehicle_state_.position[2]; + input.va = vehicle_state_.Va; + input.phi = vehicle_state_.phi; + input.theta = vehicle_state_.theta; + input.chi = vehicle_state_.chi; + input.psi = vehicle_state_.psi; + input.p = vehicle_state_.p; + input.q = vehicle_state_.q; + input.r = vehicle_state_.r; + input.Va_c = controller_commands_.Va_c; + input.h_c = controller_commands_.h_c; + input.chi_c = controller_commands_.chi_c; + input.phi_ff = controller_commands_.phi_ff; + input.Ts = 0.01f; + + struct output_s output; + //ROS_INFO("%g",input.va); + //std::cout<<"command_recieved_"< 0) + { + hector_msgs::Controller_Internals inners; + inners.phi_c = output.phi_c; + inners.theta_c = output.theta_c; + switch (output.current_zone) + { + case alt_zones::TAKE_OFF: + inners.alt_zone = inners.ZONE_TAKE_OFF; + break; + case alt_zones::CLIMB: + inners.alt_zone = inners.ZONE_CLIMB; + break; + case alt_zones::DESCEND: + inners.alt_zone = inners.ZONE_DESEND; + break; + case alt_zones::ALTITUDE_HOLD: + inners.alt_zone = inners.ZONE_ALTITUDE_HOLD; + break; + default: + break; + } + inners.aux_valid = false; + internals_pub_.publish(inners); + } + } +} + +} //end namespace + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "hector_controller"); + hector::controller_base *cont = new hector::controller_example(); + + ros::spin(); + + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/controller_base99.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/controller_base99.cpp new file mode 100644 index 0000000..4074023 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/controller_base99.cpp @@ -0,0 +1,203 @@ +#include "controller_base99.h" +#include "controller_example99.h" + +namespace hector +{ + +controller_base99::controller_base99(): + nh_(ros::NodeHandle()), + nh_private_(ros::NodeHandle()) +{ + vehicle_state_sub_ = nh_.subscribe("state", 10, &controller_base99::vehicle_state_callback, this); + controller_commands_sub_ = nh_.subscribe("controller_commands", 10, &controller_base99::controller_commands_callback, + this); + + memset(&vehicle_state_, 0, sizeof(vehicle_state_)); + memset(&controller_commands_, 0, sizeof(controller_commands_)); + + nh_private_.param("TRIM_E", params_.trim_e, 0.0); + nh_private_.param("TRIM_A", params_.trim_a, 0.0); + nh_private_.param("TRIM_R", params_.trim_r, 0.0); + nh_private_.param("TRIM_T", params_.trim_t, 0.6); + nh_private_.param("PWM_RAD_E", params_.pwm_rad_e, 1.0); + nh_private_.param("PWM_RAD_A", params_.pwm_rad_a, 1.0); + nh_private_.param("PWM_RAD_R", params_.pwm_rad_r, 1.0); + nh_private_.param("ALT_TOZ", params_.alt_toz, 20.0); /**< altitude takeoff zone */ + nh_private_.param("ALT_HZ", params_.alt_hz, 10.0); /**< altitude hold zone */ + nh_private_.param("TAU", params_.tau, 5.0); + nh_private_.param("COURSE_KP", params_.c_kp, 0.7329); + nh_private_.param("COURSE_KD", params_.c_kd, 0.0); + nh_private_.param("COURSE_KI", params_.c_ki, 0.0); + nh_private_.param("ROLL_KP", params_.r_kp, 1.2855); + nh_private_.param("ROLL_KD", params_.r_kd, -0.325); + nh_private_.param("ROLL_KI", params_.r_ki, 0.0);//0.10f); + nh_private_.param("PITCH_KP", params_.p_kp, 1.0); + nh_private_.param("PITCH_KD", params_.p_kd, -0.17); + nh_private_.param("PITCH_KI", params_.p_ki, 0.0); + nh_private_.param("PITCH_FF", params_.p_ff, 0.0); + nh_private_.param("AS_PITCH_KP", params_.a_p_kp, -0.0713); + nh_private_.param("AS_PITCH_KD", params_.a_p_kd, -0.0635); + nh_private_.param("AS_PITCH_KI", params_.a_p_ki, 0.0); + nh_private_.param("AS_THR_KP", params_.a_t_kp, 3.2); + nh_private_.param("AS_THR_KD", params_.a_t_kd, 0.0); + nh_private_.param("AS_THR_KI", params_.a_t_ki, 0.0); + nh_private_.param("ALT_KP", params_.a_kp, 0.045); + nh_private_.param("ALT_KD", params_.a_kd, 0.0); + nh_private_.param("ALT_KI", params_.a_ki, 0.01); + nh_private_.param("BETA_KP", params_.b_kp, -0.1164); + nh_private_.param("BETA_KD", params_.b_kd, 0.0); + nh_private_.param("BETA_KI", params_.b_ki, -0.0037111); + nh_private_.param("MAX_E", params_.max_e, 0.610); + nh_private_.param("MAX_A", params_.max_a, 0.523); + nh_private_.param("MAX_R", params_.max_r, 0.523); + nh_private_.param("MAX_T", params_.max_t, 1.0); + + func_ = boost::bind(&controller_base99::reconfigure_callback, this, _1, _2); + server_.setCallback(func_); + + actuators_pub_ = nh_.advertise("command", 10); + internals_pub_ = nh_.advertise("controller_inners", 10); + act_pub_timer_ = nh_.createTimer(ros::Duration(1.0/100.0), &controller_base99::actuator_controls_publish, this); + + command_recieved_ = false; +} + +void controller_base99::vehicle_state_callback(const hector_msgs::StateConstPtr &msg) +{ + vehicle_state_ = *msg; +} + +void controller_base99::controller_commands_callback(const hector_msgs::Controller_CommandsConstPtr &msg) +{ + command_recieved_ = true; + controller_commands_ = *msg; +} + +void controller_base99::reconfigure_callback(hector::ControllerConfig &config, uint32_t level) +{ + params_.trim_e = config.TRIM_E; + params_.trim_a = config.TRIM_A; + params_.trim_r = config.TRIM_R; + params_.trim_t = config.TRIM_T; + + params_.c_kp = config.COURSE_KP; + params_.c_kd = config.COURSE_KD; + params_.c_ki = config.COURSE_KI; + + params_.r_kp = config.ROLL_KP; + params_.r_kd = config.ROLL_KD; + params_.r_ki = config.ROLL_KI; + + params_.p_kp = config.PITCH_KP; + params_.p_kd = config.PITCH_KD; + params_.p_ki = config.PITCH_KI; + params_.p_ff = config.PITCH_FF; + + params_.a_p_kp = config.AS_PITCH_KP; + params_.a_p_kd = config.AS_PITCH_KD; + params_.a_p_ki = config.AS_PITCH_KI; + + params_.a_t_kp = config.AS_THR_KP; + params_.a_t_kd = config.AS_THR_KD; + params_.a_t_ki = config.AS_THR_KI; + + params_.a_kp = config.ALT_KP; + params_.a_kd = config.ALT_KD; + params_.a_ki = config.ALT_KI; + + params_.b_kp = config.BETA_KP; + params_.b_kd = config.BETA_KD; + params_.b_ki = config.BETA_KI; +} + +void controller_base99::convert_to_pwm(controller_base99::output_s &output) +{ + output.delta_e = output.delta_e*params_.pwm_rad_e; + output.delta_a = output.delta_a*params_.pwm_rad_a; + output.delta_r = output.delta_r*params_.pwm_rad_r; +} + +void controller_base99::actuator_controls_publish(const ros::TimerEvent &) +{ + struct input_s input; + input.h = -vehicle_state_.position[2];//>0 + input.va = vehicle_state_.Va; + input.phi = vehicle_state_.phi; + input.theta = vehicle_state_.theta; + input.chi = vehicle_state_.chi; + input.psi = vehicle_state_.psi; + input.p = vehicle_state_.p; + input.q = vehicle_state_.q; + input.r = vehicle_state_.r; + input.Va_c = controller_commands_.Va_c; + input.h_c = controller_commands_.h_c; + input.chi_c = controller_commands_.chi_c; + input.phi_ff = controller_commands_.phi_ff; + input.Ts = 0.01f; + + struct output_s output; + //ROS_INFO("%g",input.va); + //std::cout<<"command_recieved_"< 0) + { + hector_msgs::Controller_Internals inners; + inners.phi_c = output.phi_c; + inners.theta_c = output.theta_c; + switch (output.current_zone) + { + case alt_zones::TAKE_OFF: + inners.alt_zone = inners.ZONE_TAKE_OFF; + break; + case alt_zones::CLIMB: + inners.alt_zone = inners.ZONE_CLIMB; + break; + case alt_zones::DESCEND: + inners.alt_zone = inners.ZONE_DESEND; + break; + case alt_zones::ALTITUDE_HOLD: + inners.alt_zone = inners.ZONE_ALTITUDE_HOLD; + break; + default: + break; + } + inners.aux_valid = false; + internals_pub_.publish(inners); + } + } +} + +} //end namespace + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "hector_controller99"); + hector::controller_base99 *cont = new hector::controller_example99(); + + ros::spin(); + + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/controller_example.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/controller_example.cpp new file mode 100644 index 0000000..2b0678f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/controller_example.cpp @@ -0,0 +1,265 @@ +#include "controller_example.h" + +namespace hector +{ + +controller_example::controller_example() : controller_base() +{ + current_zone = alt_zones::TAKE_OFF; + + c_error_ = 0; + c_integrator_ = 0; + r_error_ = 0; + r_integrator = 0; + p_error_ = 0; + p_integrator_ = 0; + +} + +void controller_example::control(const params_s ¶ms, const input_s &input, output_s &output) +{ + output.delta_r = 0; //cooridinated_turn_hold(input.beta, params, input.Ts) + output.phi_c = course_hold(input.chi_c, input.chi, input.phi_ff, input.r, params, input.Ts); + output.delta_a = roll_hold(output.phi_c, input.phi, input.p, params, input.Ts); + switch (current_zone) + { + case alt_zones::TAKE_OFF: + output.phi_c = 0; + output.delta_a = roll_hold(0.0, input.phi, input.p, params, input.Ts); + output.delta_t = params.max_t; + output.theta_c = 15.0*3.14/180.0; + if (input.h >= params.alt_toz) + { + ROS_WARN("climb"); + current_zone = alt_zones::CLIMB; + ap_error_ = 0; + ap_integrator_ = 0; + ap_differentiator_ = 0; + } + break; + case alt_zones::CLIMB: + output.delta_t = params.max_t; + + //modified by kobe + if (input.Va_c < input.va) + { + output.theta_c = airspeed_with_pitch_hold(input.Va_c, input.va, params, input.Ts); + } + else + { + output.theta_c = altitiude_hold(input.h_c, input.h, params, input.Ts); + } + // + + if (input.h >= input.h_c - params.alt_hz) + { + ROS_WARN("hold"); + current_zone = alt_zones::ALTITUDE_HOLD; + at_error_ = 0; + at_integrator_ = 0; + at_differentiator_ = 0; + a_error_ = 0; + a_integrator_ = 0; + a_differentiator_ = 0; + } + else if (input.h <= params.alt_toz) + { + ROS_WARN("takeoff"); + current_zone = alt_zones::TAKE_OFF; + } + break; + case alt_zones::DESCEND: + output.delta_t = 0; + output.theta_c = airspeed_with_pitch_hold(input.Va_c, input.va, params, input.Ts); + if (input.h <= input.h_c + params.alt_hz) + { + ROS_WARN("hold"); + current_zone = alt_zones::ALTITUDE_HOLD; + at_error_ = 0; + at_integrator_ = 0; + at_differentiator_ = 0; + a_error_ = 0; + a_integrator_ = 0; + a_differentiator_ = 0; + } + break; + case alt_zones::ALTITUDE_HOLD: + output.delta_t = airspeed_with_throttle_hold(input.Va_c, input.va, params, input.Ts); + output.theta_c = altitiude_hold(input.h_c, input.h, params, input.Ts); + if (input.h >= input.h_c + params.alt_hz) + { + ROS_WARN("desend"); + current_zone = alt_zones::DESCEND; + ap_error_ = 0; + ap_integrator_ = 0; + ap_differentiator_ = 0; + } + else if (input.h <= input.h_c - params.alt_hz) + { + ROS_WARN("climb"); + current_zone = alt_zones::CLIMB; + ap_error_ = 0; + ap_integrator_ = 0; + ap_differentiator_ = 0; + } + break; + default: + break; + } + + output.current_zone = current_zone; + output.delta_e = pitch_hold(output.theta_c, input.theta, input.q, params, input.Ts); +} + +float controller_example::course_hold(float chi_c, float chi, float phi_ff, float r, const params_s ¶ms, float Ts) +{ + float error = chi_c - chi; + + c_integrator_ = c_integrator_ + (Ts/2.0)*(error + c_error_); + + float up = params.c_kp*error; + float ui = params.c_ki*c_integrator_; + float ud = params.c_kd*r; + + float phi_c = sat(up + ui + ud + phi_ff, 40.0*3.14/180.0, -40.0*3.14/180.0); + if (fabs(params.c_ki) >= 0.00001) + { + float phi_c_unsat = up + ui + ud + phi_ff; + c_integrator_ = c_integrator_ + (Ts/params.c_ki)*(phi_c - phi_c_unsat); + } + + c_error_ = error; + return phi_c; +} + +float controller_example::roll_hold(float phi_c, float phi, float p, const params_s ¶ms, float Ts) +{ + float error = phi_c - phi; + + r_integrator = r_integrator + (Ts/2.0)*(error + r_error_); + + float up = params.r_kp*error; + float ui = params.r_ki*r_integrator; + float ud = params.r_kd*p; + + float delta_a = sat(up + ui + ud, params.max_a, -params.max_a); + if (fabs(params.r_ki) >= 0.00001) + { + float delta_a_unsat = up + ui + ud; + r_integrator = r_integrator + (Ts/params.r_ki)*(delta_a - delta_a_unsat); + } + + r_error_ = error; + return delta_a; +} + +float controller_example::pitch_hold(float theta_c, float theta, float q, const params_s ¶ms, float Ts) +{ + float error = theta_c - theta; + + p_integrator_ = p_integrator_ + (Ts/2.0)*(error + p_error_); + + float up = params.p_kp*error; + float ui = params.p_ki*p_integrator_; + float ud = params.p_kd*q; + + float delta_e = sat(params.trim_e/params.pwm_rad_e + up + ui + ud, params.max_e, -params.max_e); + if (fabs(params.p_ki) >= 0.00001) + { + float delta_e_unsat = params.trim_e/params.pwm_rad_e + up + ui + ud; + p_integrator_ = p_integrator_ + (Ts/params.p_ki)*(delta_e - delta_e_unsat); + } + + p_error_ = error; + return delta_e; +} + +float controller_example::airspeed_with_pitch_hold(float Va_c, float Va, const params_s ¶ms, float Ts) +{ + float error = Va_c - Va; + + ap_integrator_ = ap_integrator_ + (Ts/2.0)*(error + ap_error_); + ap_differentiator_ = (2.0*params.tau - Ts)/(2.0*params.tau + Ts)*ap_differentiator_ + (2.0 / + (2.0*params.tau + Ts))*(error - ap_error_); + + float up = params.a_p_kp*error; + float ui = params.a_p_ki*ap_integrator_; + float ud = params.a_p_kd*ap_differentiator_; + + float theta_c = sat(up + ui + ud, 20.0*3.14/180.0, -25.0*3.14/180.0); + if (fabs(params.a_p_ki) >= 0.00001) + { + float theta_c_unsat = up + ui + ud; + ap_integrator_ = ap_integrator_ + (Ts/params.a_p_ki)*(theta_c - theta_c_unsat); + } + + ap_error_ = error; + return theta_c; +} + +float controller_example::airspeed_with_throttle_hold(float Va_c, float Va, const params_s ¶ms, float Ts) +{ + float error = Va_c - Va; + + at_integrator_ = at_integrator_ + (Ts/2.0)*(error + at_error_); + at_differentiator_ = (2.0*params.tau - Ts)/(2.0*params.tau + Ts)*at_differentiator_ + (2.0 / + (2.0*params.tau + Ts))*(error - at_error_); + + float up = params.a_t_kp*error; + float ui = params.a_t_ki*at_integrator_; + float ud = params.a_t_kd*at_differentiator_; + + float delta_t = sat(params.trim_t + up + ui + ud, params.max_t, 0); + if (fabs(params.a_t_ki) >= 0.00001) + { + float delta_t_unsat = params.trim_t + up + ui + ud; + at_integrator_ = at_integrator_ + (Ts/params.a_t_ki)*(delta_t - delta_t_unsat); + } + + at_error_ = error; + return delta_t; +} + +float controller_example::altitiude_hold(float h_c, float h, const params_s ¶ms, float Ts) +{ + float error = h_c - h; + + a_integrator_ = a_integrator_ + (Ts/2.0)*(error + a_error_); + a_differentiator_ = (2.0*params.tau - Ts)/(2.0*params.tau + Ts)*a_differentiator_ + (2.0 / + (2.0*params.tau + Ts))*(error - a_error_); + + float up = params.a_kp*error; + float ui = params.a_ki*a_integrator_; + float ud = params.a_kd*a_differentiator_; + + float theta_c = sat(up + ui + ud, 35.0*3.14/180.0, -35.0*3.14/180.0); + if (fabs(params.a_ki) >= 0.00001) + { + float theta_c_unsat = up + ui + ud; + a_integrator_ = a_integrator_ + (Ts/params.a_ki)*(theta_c - theta_c_unsat); + } + + at_error_ = error; + return theta_c; +} + +//float controller_example::cooridinated_turn_hold(float v, const params_s ¶ms, float Ts) +//{ +// //todo finish this if you want... +// return 0; +//} + +float controller_example::sat(float value, float up_limit, float low_limit) +{ + float rVal; + if (value > up_limit) + rVal = up_limit; + else if (value < low_limit) + rVal = low_limit; + else + rVal = value; + + return rVal; +} + +} //end namespace diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/controller_example99.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/controller_example99.cpp new file mode 100644 index 0000000..4ffd661 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/controller_example99.cpp @@ -0,0 +1,293 @@ +#include "controller_example99.h" + +namespace hector +{ + +controller_example99::controller_example99() : controller_base99() +{ + current_zone = alt_zones::TAKE_OFF; + + c_error_ = 0; + c_integrator_ = 0; + r_error_ = 0; + r_integrator = 0; + p_error_ = 0; + p_integrator_ = 0; + +} + +void controller_example99::control(const params_s ¶ms, const input_s &input, output_s &output) +{ + output.delta_r = 0; //cooridinated_turn_hold(input.beta, params, input.Ts) + output.phi_c = course_hold(input.chi_c, input.chi, input.phi_ff, input.r, params, input.Ts); + output.delta_a = roll_hold(output.phi_c, input.phi, input.p, params, input.Ts); + switch (current_zone) + { + case alt_zones::TAKE_OFF: + output.phi_c = 0; + output.delta_a = roll_hold(0.0, input.phi, input.p, params, input.Ts); + output.delta_t = params.max_t;//modified by kobe + output.theta_c = 1.0*3.14/180.0; + //output.theta_c = 15.0*3.14/180.0; + //ROS_WARN("TAKE_OFF"); + if (input.h >= params.alt_toz) + { + ROS_WARN("climb"); + current_zone = alt_zones::CLIMB; + ap_error_ = 0; + ap_integrator_ = 0; + ap_differentiator_ = 0; + } + break; + case alt_zones::CLIMB: + output.delta_t = params.max_t; + + //modified by kobe + if (input.Va_c < input.va) + { + output.theta_c = airspeed_with_pitch_hold(input.Va_c, input.va, params, input.Ts);//original + } + else + { + output.theta_c = altitiude_hold(input.h_c, input.h, params, input.Ts); + } + // + + if (input.h >= input.h_c - params.alt_hz) + { + ROS_WARN("hold"); + current_zone = alt_zones::ALTITUDE_HOLD; + at_error_ = 0; + at_integrator_ = 0; + at_differentiator_ = 0; + a_error_ = 0; + a_integrator_ = 0; + a_differentiator_ = 0; + } + else if (input.h <= params.alt_toz) + { + //ROS_WARN("takeoff"); + current_zone = alt_zones::TAKE_OFF; + } + break; + case alt_zones::DESCEND: + output.delta_t = decend_airspeed_oil(input.h_c, input.h, params, input.Ts); + //output.theta_c =airspeed_with_pitch_hold(input.Va_c, input.va, params, input.Ts); + output.theta_c =decend_airspeed_with_pitch_hold(input.h_c, input.h, params, input.Ts); + //ROS_INFO("Look here %f %f",output.theta_c,pitch_hold(output.theta_c, input.theta, input.q, params, input.Ts)); + if (input.h <= input.h_c + params.alt_hz) + { + ROS_WARN("hold"); + current_zone = alt_zones::ALTITUDE_HOLD; + at_error_ = 0; + at_integrator_ = 0; + at_differentiator_ = 0; + a_error_ = 0; + a_integrator_ = 0; + a_differentiator_ = 0; + } + break; + case alt_zones::ALTITUDE_HOLD: + output.delta_t = airspeed_with_throttle_hold(input.Va_c, input.va, params, input.Ts); + output.theta_c = altitiude_hold(input.h_c, input.h, params, input.Ts); + //ROS_INFO("Look here %f %f %f",output.delta_t,output.theta_c,input.Va_c); + if (input.h >= input.h_c + 200)//add by kobe + //if (input.h >= input.h_c + params.alt_hz)//original + { + ROS_WARN("desend"); + current_zone = alt_zones::DESCEND; + ap_error_ = 0; + ap_integrator_ = 0; + ap_differentiator_ = 0; + } + else if (input.h <= input.h_c - 200) + //else if (input.h <= input.h_c - params.alt_hz) + { + ROS_WARN("climb"); + current_zone = alt_zones::CLIMB; + ap_error_ = 0; + ap_integrator_ = 0; + ap_differentiator_ = 0; + } + break; + default: + break; + } + + output.current_zone = current_zone; + output.delta_e = pitch_hold(output.theta_c, input.theta, input.q, params, input.Ts); + +} + +float controller_example99::course_hold(float chi_c, float chi, float phi_ff, float r, const params_s ¶ms, float Ts) +{ + float error = chi_c - chi; + + c_integrator_ = c_integrator_ + (Ts/2.0)*(error + c_error_); + + float up = params.c_kp*error; + float ui = params.c_ki*c_integrator_; + float ud = params.c_kd*r; + + float phi_c = sat(up + ui + ud + phi_ff, 40.0*3.14/180.0, -40.0*3.14/180.0); //add by kobe + //float phi_c = sat(up + ui + ud + phi_ff, 40.0*3.14/180.0, -40.0*3.14/180.0); + if (fabs(params.c_ki) >= 0.00001) + { + float phi_c_unsat = up + ui + ud + phi_ff; + c_integrator_ = c_integrator_ + (Ts/params.c_ki)*(phi_c - phi_c_unsat); + } + + c_error_ = error; + return phi_c; +} + +float controller_example99::roll_hold(float phi_c, float phi, float p, const params_s ¶ms, float Ts) +{ + float error = phi_c - phi; + + r_integrator = r_integrator + (Ts/2.0)*(error + r_error_); + + float up = params.r_kp*error; + float ui = params.r_ki*r_integrator; + float ud = params.r_kd*p; + + float delta_a = sat(up + ui + ud,params.max_a, -params.max_a);//add by kobe,0.1,-0.1 + //float delta_a = sat(up + ui + ud, params.max_a, -params.max_a); + + if (fabs(params.r_ki) >= 0.00001) + { + float delta_a_unsat = up + ui + ud; + r_integrator = r_integrator + (Ts/params.r_ki)*(delta_a - delta_a_unsat); + } + + r_error_ = error; + return delta_a; +} + +float controller_example99::pitch_hold(float theta_c, float theta, float q, const params_s ¶ms, float Ts) +{ + float error = theta_c - theta; + + p_integrator_ = p_integrator_ + (Ts/2.0)*(error + p_error_); + + float up = params.p_kp*error; + float ui = params.p_ki*p_integrator_; + float ud = params.p_kd*q; + + float delta_e = sat(params.trim_e/params.pwm_rad_e + up + ui + ud, 0.1, -0.1);// add by kobe + //float delta_e = sat(params.trim_e/params.pwm_rad_e + up + ui + ud, params.max_e, -params.max_e); + if (fabs(params.p_ki) >= 0.00001) + { + float delta_e_unsat = params.trim_e/params.pwm_rad_e + up + ui + ud; + p_integrator_ = p_integrator_ + (Ts/params.p_ki)*(delta_e - delta_e_unsat); + } + + p_error_ = error; + return delta_e; +} + +float controller_example99::airspeed_with_pitch_hold(float Va_c, float Va, const params_s ¶ms, float Ts) +{ + float error = Va_c - Va; + + ap_integrator_ = ap_integrator_ + (Ts/2.0)*(error + ap_error_); + ap_differentiator_ = (2.0*params.tau - Ts)/(2.0*params.tau + Ts)*ap_differentiator_ + (2.0 / + (2.0*params.tau + Ts))*(error - ap_error_); + + float up = params.a_p_kp*error; + float ui = params.a_p_ki*ap_integrator_; + float ud = params.a_p_kd*ap_differentiator_; + + float theta_c = sat(up + ui + ud, 2.0*3.14/180.0, -2.0*3.14/180.0);//add by kobe + //float theta_c = sat(up + ui + ud, 20.0*3.14/180.0, -25.0*3.14/180.0); + if (fabs(params.a_p_ki) >= 0.00001) + { + float theta_c_unsat = up + ui + ud; + ap_integrator_ = ap_integrator_ + (Ts/params.a_p_ki)*(theta_c - theta_c_unsat); + } + + ap_error_ = error; + return theta_c; +} + +float controller_example99::decend_airspeed_with_pitch_hold(float h_c, float h, const params_s ¶ms, float Ts) +{ + float error = 0.01*(h_c - h); + float theta_c = sat(error, 0, -90.0*3.14/180.0); + return theta_c; +} + +float controller_example99::decend_airspeed_oil(float h_c, float h, const params_s ¶ms, float Ts) +{ + float error = pow(2,(h_c - h)/50); + float theta_t = sat(error, 1, 0); + return theta_t; +} + +float controller_example99::airspeed_with_throttle_hold(float Va_c, float Va, const params_s ¶ms, float Ts) +{ + float error = Va_c - Va; + + at_integrator_ = at_integrator_ + (Ts/2.0)*(error + at_error_); + at_differentiator_ = (2.0*params.tau - Ts)/(2.0*params.tau + Ts)*at_differentiator_ + (2.0 / + (2.0*params.tau + Ts))*(error - at_error_); + + float up = params.a_t_kp*error; + float ui = params.a_t_ki*at_integrator_; + float ud = params.a_t_kd*at_differentiator_; + + float delta_t = sat(params.trim_t + up + ui + ud, params.max_t, 0); + if (fabs(params.a_t_ki) >= 0.00001) + { + float delta_t_unsat = params.trim_t + up + ui + ud; + at_integrator_ = at_integrator_ + (Ts/params.a_t_ki)*(delta_t - delta_t_unsat); + } + + at_error_ = error; + return delta_t; +} + +float controller_example99::altitiude_hold(float h_c, float h, const params_s ¶ms, float Ts) +{ + float error = h_c - h; + + a_integrator_ = a_integrator_ + (Ts/2.0)*(error + a_error_); + a_differentiator_ = (2.0*params.tau - Ts)/(2.0*params.tau + Ts)*a_differentiator_ + (2.0 / + (2.0*params.tau + Ts))*(error - a_error_); + + float up = params.a_kp*error; + float ui = params.a_ki*a_integrator_; + float ud = params.a_kd*a_differentiator_; + + float theta_c = sat(up + ui + ud, 5.0*3.14/180.0, -5.0*3.14/180.0);//add by kobe + //float theta_c = sat(up + ui + ud, 35.0*3.14/180.0, -35.0*3.14/180.0); + if (fabs(params.a_ki) >= 0.00001) + { + float theta_c_unsat = up + ui + ud; + a_integrator_ = a_integrator_ + (Ts/params.a_ki)*(theta_c - theta_c_unsat); + } + + at_error_ = error; + return theta_c; +} + +//float controller_example99::cooridinated_turn_hold(float v, const params_s ¶ms, float Ts) +//{ +// //todo finish this if you want... +// return 0; +//} + +float controller_example99::sat(float value, float up_limit, float low_limit) +{ + float rVal; + if (value > up_limit) + rVal = up_limit; + else if (value < low_limit) + rVal = low_limit; + else + rVal = value; + + return rVal; +} + +} //end namespace diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/estimator_base.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/estimator_base.cpp new file mode 100644 index 0000000..c20e883 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/estimator_base.cpp @@ -0,0 +1,228 @@ +#include "estimator_base.h" +#include "estimator_example.h" + +namespace hector +{ + +estimator_base::estimator_base(): + nh_(ros::NodeHandle()), + nh_private_(ros::NodeHandle("~")) +{ + nh_private_.param("gps_topic", gps_topic_, "gps"); + nh_private_.param("imu_topic", imu_topic_, "imu/data"); + nh_private_.param("baro_topic", baro_topic_, "baro"); + nh_private_.param("airspeed_topic", airspeed_topic_, "airspeed"); + nh_private_.param("status_topic", status_topic_, "status"); + nh_private_.param("update_rate", update_rate_, 100.0); + params_.Ts = 1.0f/update_rate_; + params_.gravity = 9.8; + nh_private_.param("rho", params_.rho, 1.225); + nh_private_.param("sigma_accel", params_.sigma_accel, 0.0245); + nh_private_.param("sigma_n_gps", params_.sigma_n_gps, 0.21); + nh_private_.param("sigma_e_gps", params_.sigma_e_gps, 0.21); + nh_private_.param("sigma_Vg_gps", params_.sigma_Vg_gps, 0.0500); + nh_private_.param("sigma_couse_gps", params_.sigma_course_gps, 0.0045); + + gps_sub_ = nh_.subscribe(gps_topic_, 10, &estimator_base::gpsCallback, this); + imu_sub_ = nh_.subscribe(imu_topic_, 10, &estimator_base::imuCallback, this); + baro_sub_ = nh_.subscribe(baro_topic_, 10, &estimator_base::baroAltCallback, this); + airspeed_sub_ = nh_.subscribe(airspeed_topic_, 10, &estimator_base::airspeedCallback, this); + status_sub_ = nh_.subscribe(status_topic_, 1, &estimator_base::statusCallback, this); + update_timer_ = nh_.createTimer(ros::Duration(1.0/update_rate_), &estimator_base::update, this); + vehicle_state_pub_ = nh_.advertise("state", 10); + init_static_ = 0; + baro_count_ = 0; + armed_first_time_ = false; +} + +void estimator_base::update(const ros::TimerEvent &) +{ + struct output_s output; + + if (armed_first_time_) + { + estimate(params_, input_, output); + } + else + { + output.pn = output.pe = output.h = 0; + output.phi = output.theta = output.psi = 0; + output.alpha = output.beta = output.chi = 0; + output.p = output.q = output.r = 0; + output.Va = 0; + } + + input_.gps_new = false; + + hector_msgs::State msg; + msg.header.stamp = ros::Time::now(); + msg.header.frame_id = 1; // Denotes global frame + + msg.position[0] = output.pn; + msg.position[1] = output.pe; + msg.position[2] = -output.h; + if (gps_init_) + { + msg.initial_lat = init_lat_; + msg.initial_lon = init_lon_; + msg.initial_alt = init_alt_; + } + msg.Va = output.Va; + msg.alpha = output.alpha; + msg.beta = output.beta; + msg.phi = output.phi; + msg.theta = output.theta; + msg.psi = output.psi; + msg.chi = output.chi; + msg.p = output.p; + msg.q = output.q; + msg.r = output.r; + msg.Vg = output.Vg; + msg.wn = output.wn; + msg.we = output.we; + msg.quat_valid = false; + + msg.psi_deg = fmod(output.psi, 2*M_PI)*180/M_PI; //-360 to 360 + msg.psi_deg += (msg.psi_deg < -180 ? 360 : 0); + msg.psi_deg -= (msg.psi_deg > 180 ? 360 : 0); + msg.chi_deg = fmod(output.chi, 2*M_PI)*180/M_PI; //-360 to 360 + msg.chi_deg += (msg.chi_deg < -180 ? 360 : 0); + msg.chi_deg -= (msg.chi_deg > 180 ? 360 : 0); + + vehicle_state_pub_.publish(msg); +} + +void estimator_base::gpsCallback(const rosflight_msgs::GPS &msg) +{ + if (msg.fix != true || msg.NumSat < 4 || !std::isfinite(msg.latitude)) + { + input_.gps_new = false; + return; + } + if (!gps_init_) + { + gps_init_ = true; + init_alt_ = msg.altitude; + init_lat_ = msg.latitude; + init_lon_ = msg.longitude; + } + else + { + input_.gps_n = EARTH_RADIUS*(msg.latitude - init_lat_)*M_PI/180.0; + input_.gps_e = EARTH_RADIUS*cos(init_lat_*M_PI/180.0)*(msg.longitude - init_lon_)*M_PI/180.0; + input_.gps_h = msg.altitude - init_alt_; + input_.gps_Vg = msg.speed; + if (msg.speed > 0.3) + input_.gps_course = msg.ground_course; + input_.gps_new = true; + //ROS_INFO("%g %g %g",input_.gps_n,input_.gps_e,input_.gps_h); + } +} + +void estimator_base::imuCallback(const sensor_msgs::Imu &msg) +{ + input_.accel_x = msg.linear_acceleration.x; + input_.accel_y = msg.linear_acceleration.y; + input_.accel_z = msg.linear_acceleration.z; + + input_.gyro_x = msg.angular_velocity.x; + input_.gyro_y = msg.angular_velocity.y; + input_.gyro_z = msg.angular_velocity.z; +} + +void estimator_base::baroAltCallback(const rosflight_msgs::Barometer &msg) +{ + + if (armed_first_time_ && !baro_init_) + { + if (baro_count_ < 100) + { + init_static_ += msg.pressure; + init_static_vector_.push_back(msg.pressure); + input_.static_pres = 0; + baro_count_ += 1; + } + else + { + init_static_ = std::accumulate(init_static_vector_.begin(), init_static_vector_.end(), + 0.0)/init_static_vector_.size(); + baro_init_ = true; + + //Check that it got a good calibration. + std::sort(init_static_vector_.begin(), init_static_vector_.end()); + float q1 = (init_static_vector_[24] + init_static_vector_[25])/2.0; + float q3 = (init_static_vector_[74] + init_static_vector_[75])/2.0; + float IQR = q3 - q1; + float upper_bound = q3 + 2.0*IQR; + float lower_bound = q1 - 2.0*IQR; + for (int i = 0; i < 100; i++) + { + if (init_static_vector_[i] > upper_bound) + { + baro_init_ = false; + baro_count_ = 0; + init_static_vector_.clear(); + ROS_WARN("Bad baro calibration. Recalibrating"); + break; + } + else if (init_static_vector_[i] < lower_bound) + { + baro_init_ = false; + baro_count_ = 0; + init_static_vector_.clear(); + ROS_WARN("Bad baro calibration. Recalibrating"); + break; + } + } + } + } + else + { + float static_pres_old = input_.static_pres; + input_.static_pres = -msg.pressure + init_static_; + + float gate_gain = 1.35*params_.rho*params_.gravity; + if (input_.static_pres < static_pres_old - gate_gain) + { + input_.static_pres = static_pres_old - gate_gain; + } + else if (input_.static_pres > static_pres_old + gate_gain) + { + input_.static_pres = static_pres_old + gate_gain; + } + } +} + +void estimator_base::airspeedCallback(const rosflight_msgs::Airspeed &msg) +{ + float diff_pres_old = input_.diff_pres; + input_.diff_pres = msg.differential_pressure; + + float gate_gain = pow(3, 2)*params_.rho/2.0; + if (input_.diff_pres < diff_pres_old - gate_gain) + { + input_.diff_pres = diff_pres_old - gate_gain; + } + else if (input_.diff_pres > diff_pres_old + gate_gain) + { + input_.diff_pres = diff_pres_old + gate_gain; + } +} + +void estimator_base::statusCallback(const rosflight_msgs::Status &msg) +{ + if (!armed_first_time_ && msg.armed) + armed_first_time_ = true; +} + +} //end namespace + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "hector_estimator"); + hector::estimator_base *est = new hector::estimator_example(); + + ros::spin(); + + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/estimator_base_99pub.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/estimator_base_99pub.cpp new file mode 100644 index 0000000..f00e735 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/estimator_base_99pub.cpp @@ -0,0 +1,76 @@ +//* @author AIRC-DA group,questions contack kobe. + +#include "estimator_base_99pub.h" + +namespace hector +{ + +estimator_base_99pub::estimator_base_99pub(): + nh_(ros::NodeHandle()), + nh_private_(ros::NodeHandle("~")) +{ + + true_state_sub_ = nh_.subscribe("truth", 1, &estimator_base_99pub::truestateCallback, this); + nh_private_.param("update_rate", update_rate_, 100.0); + update_timer_ = nh_.createTimer(ros::Duration(1.0/update_rate_), &estimator_base_99pub::update, this); + vehicle_state99_pub_ = nh_.advertise("state29", 10); + state_init_ = false; +} + +void estimator_base_99pub::update(const ros::TimerEvent &) +{ + hector_msgs::State29 msg; + msg.header.stamp = ros::Time::now(); + msg.header.frame_id = 1; // Denotes global frame + if (state_init_) + { + msg.position_gps[0]=(true_state_.position[0]*180)/(EARTH_RADIUS*M_PI)+true_state_.initial_lat; + // pn = EARTH_RADIUS*(msg.latitude - init_lat_)*M_PI/180.0; + msg.position_gps[1]=(true_state_.position[1]*180)/(EARTH_RADIUS*cos(true_state_.initial_lat*M_PI/180.0)*M_PI)+true_state_.initial_lon; + // pe = EARTH_RADIUS*cos(init_lat_*M_PI/180.0)*(msg.longitude - init_lon_)*M_PI/180.0; + // input_.gps_h = msg.altitude - init_alt_; + msg.position_gps[2] =-true_state_.position[2]-true_state_.initial_alt; //>0 + msg.attitude_angle[0] = true_state_.phi; + msg.attitude_angle[1] = true_state_.theta; + msg.attitude_angle[2] = true_state_.psi; + msg.velocity[0] = true_state_.Vn; + msg.velocity[1] = true_state_.Ve; + msg.velocity[2] = true_state_.Vd; + msg.angular_velocity[0] = true_state_.p; + msg.angular_velocity[1] = true_state_.q; + msg.angular_velocity[2] = true_state_.r; + msg.acceleration[0] = -1; + msg.acceleration[1] = -1; + msg.acceleration[2] = -1; + msg.electric_quantity = -1; + msg.state_word = -1; + // ROS_INFO("GPS-position: %g %g %g",msg.position_gps[0],msg.position_gps[1],msg.position_gps[2]); + // ROS_INFO("xyz-position: %g %g %g",true_state_.position[0],true_state_.position[1],true_state_.position[2]); + } + else + { + // ROS_WARN("No plane truth data."); + } + + vehicle_state99_pub_.publish(msg); +} + + +void estimator_base_99pub::truestateCallback(const hector_msgs::StateConstPtr &msg) +{ + true_state_ = *msg; + state_init_ = true; +} + + +} //end namespace + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "hector_estimator_29pub"); + hector::estimator_base_99pub *cont = new hector::estimator_base_99pub(); + + ros::spin(); + + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/estimator_base_statesub.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/estimator_base_statesub.cpp new file mode 100644 index 0000000..ceb98d7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/estimator_base_statesub.cpp @@ -0,0 +1,75 @@ +//* @author AIRC-DA group,questions contack kobe. + +#include "estimator_base_statesub.h" + +namespace hector +{ + +estimator_base_statesub::estimator_base_statesub() : nh_(ros::NodeHandle()), + nh_private_(ros::NodeHandle("~")) +{ + state29_sub_ = nh_.subscribe("state29", 10, &estimator_base_statesub::state99Callback, this); + nh_private_.param("update_rate", update_rate_, 100.0); + update_timer_ = nh_.createTimer(ros::Duration(1.0 / update_rate_), &estimator_base_statesub::update, this); + vehicle_state_pub_ = nh_.advertise("state", 10); + + state_init_ = false; + init_lat_=0; /**< Initial latitude in degrees */ + init_lon_=0; /**< Initial longitude in degrees */ + init_alt_=0; //>0 +} + +void estimator_base_statesub::update(const ros::TimerEvent &) +{ + + hector_msgs::State msg; + msg.header.stamp = ros::Time::now(); + msg.header.frame_id = 1; // Denotes global frame + if (state_init_) + { + msg.position[0] = EARTH_RADIUS*(state29_.position_gps[0] - init_lat_)*M_PI/180.0; + // pn = EARTH_RADIUS*(msg.latitude - init_lat_)*M_PI/180.0; + msg.position[1] = EARTH_RADIUS*cos(init_lat_*M_PI/180.0)*(state29_.position_gps[1] - init_lon_)*M_PI/180.0; + // pe = EARTH_RADIUS*cos(init_lat_*M_PI/180.0)*(msg.longitude - init_lon_)*M_PI/180.0; + msg.position[2] = -state29_.position_gps[2]- init_alt_; //<0 + //input_.gps_h = msg.altitude - init_alt_; + msg.Wd=state29_.position_gps[0]; + msg.Jd=state29_.position_gps[1]; + msg.Va=sqrt(pow(state29_.velocity[0], 2.0) + pow(state29_.velocity[1], 2.0) + pow(state29_.velocity[2], 2.0)); + msg.Vg=msg.Va; //true for rosflight + msg.phi=state29_.attitude_angle[0]; + msg.theta=state29_.attitude_angle[1]; + msg.psi=state29_.attitude_angle[2]; + //msg.chi=msg.psi;//watch here + msg.chi = atan2(msg.Va*sin(msg.psi), msg.Va*cos(msg.psi)); + msg.p=state29_.angular_velocity[0]; + msg.q=state29_.angular_velocity[1]; + msg.r=state29_.angular_velocity[2]; + + msg.initial_lat = init_lat_; + msg.initial_lon = init_lon_; + msg.initial_alt = init_alt_; + + } + else + { + // ROS_WARN("No State29 data."); + } + vehicle_state_pub_.publish(msg); +} + +void estimator_base_statesub::state99Callback(const hector_msgs::State29ConstPtr &msg) +{ + state29_ = *msg; + state_init_ = true; +} +} // namespace hector + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "hector_estimator_statesub"); + hector::estimator_base_statesub *cont = new hector::estimator_base_statesub(); + ros::spin(); + + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/estimator_base_updata_statesub.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/estimator_base_updata_statesub.cpp new file mode 100644 index 0000000..886a221 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/estimator_base_updata_statesub.cpp @@ -0,0 +1,76 @@ +//* @author AIRC-DA group,questions contack kobe. + +#include "estimator_base_updata_statesub.h" + +namespace hector +{ + +estimator_base_updata_statesub::estimator_base_updata_statesub() : nh_(ros::NodeHandle()), + nh_private_(ros::NodeHandle("~")) +{ + state29_sub_ = nh_.subscribe("/serial_commu_up", 10, &estimator_base_updata_statesub::state99Callback, this); + nh_private_.param("update_rate", update_rate_, 100.0); + update_timer_ = nh_.createTimer(ros::Duration(1.0 / update_rate_), &estimator_base_updata_statesub::update, this); + vehicle_state_pub_ = nh_.advertise("state", 10); + + state_init_ = false; + init_lat_=0; /**< Initial latitude in degrees */ + init_lon_=0; /**< Initial longitude in degrees */ + init_alt_=0; //>0 +} + +void estimator_base_updata_statesub::update(const ros::TimerEvent &) +{ + + hector_msgs::State msg; + msg.header.stamp = ros::Time::now(); + msg.header.frame_id = 1; // Denotes global frame + if (state_init_) + { + msg.position[0] = EARTH_RADIUS*(state29_.latitude - init_lat_)*M_PI/180.0; + // pn = EARTH_RADIUS*(msg.latitude - init_lat_)*M_PI/180.0; + msg.position[1] = EARTH_RADIUS*cos(init_lat_*M_PI/180.0)*(state29_.longitude - init_lon_)*M_PI/180.0; + // pe = EARTH_RADIUS*cos(init_lat_*M_PI/180.0)*(msg.longitude - init_lon_)*M_PI/180.0; + msg.position[2] = -state29_.altitude- init_alt_; //<0 + //input_.gps_h = msg.altitude - init_alt_; + msg.Wd=state29_.latitude; + msg.Jd=state29_.longitude; + msg.Va=sqrt(pow(state29_.north_direction_speed, 2.0) + pow(state29_.east_direction_speed, 2.0) + pow(state29_.ground_direction_speed, 2.0)); + msg.Vg=msg.Va; //true for rosflight + msg.phi=state29_.roll_angle; + msg.theta=state29_.pitch_angle; + msg.psi=state29_.yaw_angle; + //msg.chi=msg.psi;//watch here + msg.chi = atan2(msg.Va*sin(msg.psi), msg.Va*cos(msg.psi)); + msg.p=state29_.angular_rate_x; + msg.q=state29_.angular_rate_y; + msg.r=state29_.angular_rate_z; + + msg.initial_lat = init_lat_; + msg.initial_lon = init_lon_; + msg.initial_alt = init_alt_; + // ROS_WARN("Recieved up-data data."); + //ROS_INFO("Hello--- %f %f %f %f",state29_.latitude,state29_.longitude,msg.Vg,state29_.altitude); + } + else + { + // ROS_WARN("No up-data data."); + } + vehicle_state_pub_.publish(msg); +} + +void estimator_base_updata_statesub::state99Callback(const hector_msgs::Up_Data_NewConstPtr &msg) +{ + state29_ = *msg; + state_init_ = true; +} +} // namespace hector + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "hector_estimator_updata_statesub"); + hector::estimator_base_updata_statesub *cont = new hector::estimator_base_updata_statesub(); + ros::spin(); + + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/estimator_example.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/estimator_example.cpp new file mode 100644 index 0000000..db62ec7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/estimator_example.cpp @@ -0,0 +1,416 @@ +#include "estimator_base.h" +#include "estimator_example.h" + +namespace hector +{ + +float radians(float degrees) +{ + return M_PI*degrees/180.0; +} + +estimator_example::estimator_example() : + estimator_base(), + xhat_a_(Eigen::Vector2f::Zero()), + P_a_(Eigen::Matrix2f::Identity()), + Q_a_(Eigen::Matrix2f::Identity()), + xhat_p_(Eigen::VectorXf::Zero(7)), + P_p_(Eigen::MatrixXf::Identity(7, 7)), + Q_p_(Eigen::MatrixXf::Identity(7, 7)), + R_p_(Eigen::MatrixXf::Zero(7, 7)), + f_p_(7), + A_p_(7, 7), + C_p_(7), + L_p_(7) +{ + P_a_ *= powf(radians(5.0f), 2); + + Q_a_(0, 0) = 0.00000001; + Q_a_(1, 1) = 0.00000001; + + P_p_ = Eigen::MatrixXf::Identity(7, 7); + P_p_(0, 0) = .03; + P_p_(1, 1) = .03; + P_p_(2, 2) = .01; + P_p_(3, 3) = radians(5.0f); + P_p_(4, 4) = .04; + P_p_(5, 5) = .04; + P_p_(6, 6) = radians(5.0f); + + Q_p_ *= 0.0001f; + Q_p_(3, 3) = 0.000001f; + + phat_ = 0; + qhat_ = 0; + rhat_ = 0; + phihat_ = 0; + thetahat_ = 0; + psihat_ = 0; + Vwhat_ = 0; + + lpf_static_ = 0; + lpf_diff_ = 0; + + N_ = 10; + + alpha_ = 0.0f; +} + +void estimator_example::estimate(const params_s ¶ms, const input_s &input, output_s &output) +{ + if (alpha_ == 0.0f) //initailze stuff that comes from params + { + R_accel_ = powf(params.sigma_accel, 2); + + R_p_(0, 0) = powf(params.sigma_n_gps, 2); + R_p_(1, 1) = powf(params.sigma_e_gps, 2); + R_p_(2, 2) = powf(params.sigma_Vg_gps, 2); + R_p_(3, 3) = powf(params.sigma_course_gps, 2); + R_p_(4, 4) = 0.001; + R_p_(5, 5) = 0.001; + + float lpf_a = 50.0; + float lpf_a1 = 8.0; + alpha_ = exp(-lpf_a*params.Ts); + alpha1_ = exp(-lpf_a1*params.Ts); + } + + // low pass filter gyros to estimate angular rates + lpf_gyro_x_ = alpha_*lpf_gyro_x_ + (1 - alpha_)*input.gyro_x; + lpf_gyro_y_ = alpha_*lpf_gyro_y_ + (1 - alpha_)*input.gyro_y; + lpf_gyro_z_ = alpha_*lpf_gyro_z_ + (1 - alpha_)*input.gyro_z; + + float phat = lpf_gyro_x_; + float qhat = lpf_gyro_y_; + float rhat = lpf_gyro_z_; + + // low pass filter static pressure sensor and invert to esimate altitude + lpf_static_ = alpha1_*lpf_static_ + (1 - alpha1_)*input.static_pres; + float hhat = lpf_static_/params.rho/params.gravity; + + // low pass filter diff pressure sensor and invert to extimate Va + lpf_diff_ = alpha1_*lpf_diff_ + (1 - alpha1_)*input.diff_pres; + + // when the plane isn't moving or moving slowly, the noise in the sensor + // will cause the differential pressure to go negative. This will catch + // those cases. + if (lpf_diff_ <= 0) + lpf_diff_ = 0.000001; + + float Vahat = sqrt(2/params.rho*lpf_diff_); + + // low pass filter accelerometers + lpf_accel_x_ = alpha_*lpf_accel_x_ + (1 - alpha_)*input.accel_x; + lpf_accel_y_ = alpha_*lpf_accel_y_ + (1 - alpha_)*input.accel_y; + lpf_accel_z_ = alpha_*lpf_accel_z_ + (1 - alpha_)*input.accel_z; + + // implement continuous-discrete EKF to estimate roll and pitch angles + // prediction step + float cp; // cos(phi) + float sp; // sin(phi) + float tt; // tan(thata) + float ct; // cos(thata) + float st; // sin(theta) + for (int i = 0; i < N_; i++) + { + cp = cosf(xhat_a_(0)); // cos(phi) + sp = sinf(xhat_a_(0)); // sin(phi) + tt = tanf(xhat_a_(1)); // tan(thata) + ct = cosf(xhat_a_(1)); // cos(thata) + + f_a_(0) = phat + (qhat*sp + rhat*cp)*tt; + f_a_(1) = qhat*cp - rhat*sp; + + A_a_ = Eigen::Matrix2f::Zero(); + A_a_(0, 0) = (qhat*cp - rhat*sp)*tt; + A_a_(0, 1) = (qhat*sp + rhat*cp)/ct/ct; + A_a_(1, 0) = -qhat*sp - rhat*cp; + + xhat_a_ += f_a_*(params.Ts/N_); + P_a_ += (A_a_*P_a_ + P_a_*A_a_.transpose() + Q_a_)*(params.Ts/N_); + } + // measurement updates + cp = cosf(xhat_a_(0)); + sp = sinf(xhat_a_(0)); + ct = cosf(xhat_a_(1)); + st = sinf(xhat_a_(1)); + Eigen::Matrix2f I; + I = Eigen::Matrix2f::Identity(); + + // x-axis accelerometer + h_a_ = qhat*Vahat*st + params.gravity*st; + C_a_ = Eigen::Vector2f::Zero(); + C_a_(1) = qhat*Vahat*ct + params.gravity*ct; + L_a_ = (P_a_*C_a_)/(R_accel_ + C_a_.transpose()*P_a_*C_a_); + P_a_ = (I - L_a_*C_a_.transpose())*P_a_; + xhat_a_ += L_a_*((hhat < 15 ? lpf_accel_x_/3 : lpf_accel_x_) - h_a_); + + // y-axis accelerometer + h_a_ = rhat*Vahat*ct - phat*Vahat*st - params.gravity*ct*sp; + C_a_ = Eigen::Vector2f::Zero(); + C_a_(0) = -params.gravity*cp*ct; + C_a_(1) = -rhat*Vahat*st - phat*Vahat*ct + params.gravity*st*sp; + L_a_ = (P_a_*C_a_)/(R_accel_ + C_a_.transpose()*P_a_*C_a_); + P_a_ = (I - L_a_*C_a_.transpose())*P_a_; + xhat_a_ += L_a_*(lpf_accel_y_ - h_a_); + + // z-axis accelerometer + h_a_ = -qhat*Vahat*ct - params.gravity*ct*cp; + C_a_ = Eigen::Vector2f::Zero(); + C_a_(0) = params.gravity*sp*ct; + C_a_(1) = (qhat*Vahat + params.gravity*cp)*st; + L_a_ = (P_a_*C_a_)/(R_accel_ + C_a_.transpose()*P_a_*C_a_); + P_a_ = (I - L_a_*C_a_.transpose())*P_a_; + xhat_a_ += L_a_*(lpf_accel_z_ - h_a_); + + check_xhat_a(); + + float phihat = xhat_a_(0); + float thetahat = xhat_a_(1); + + // implement continous-discrete EKF to estimate pn, pe, chi, Vg + // prediction step + float psidot, tmp, Vgdot; + if (fabsf(xhat_p_(2)) < 0.01f) + { + xhat_p_(2) = 0.01; // prevent devide by zero + } + + for (int i = 0; i < N_; i++) + { + psidot = (qhat*sinf(phihat) + rhat*cosf(phihat))/cosf(thetahat); + tmp = -psidot*Vahat*(xhat_p_(4)*cosf(xhat_p_(6)) + xhat_p_(5)*sinf(xhat_p_(6)))/xhat_p_(2); + Vgdot = ((Vahat*cosf(xhat_p_(6)) + xhat_p_(4))*(-psidot*Vahat*sinf(xhat_p_(6))) + (Vahat*sinf(xhat_p_( + 6)) + xhat_p_(5))*(psidot*Vahat*cosf(xhat_p_(6))))/xhat_p_(2); + + f_p_ = Eigen::VectorXf::Zero(7); + f_p_(0) = xhat_p_(2)*cosf(xhat_p_(3)); + f_p_(1) = xhat_p_(2)*sinf(xhat_p_(3)); + f_p_(2) = Vgdot; + f_p_(3) = params.gravity/xhat_p_(2)*tanf(phihat)*cosf(xhat_p_(3) - xhat_p_(6)); + f_p_(6) = psidot; + + A_p_ = Eigen::MatrixXf::Zero(7, 7); + A_p_(0, 2) = cos(xhat_p_(3)); + A_p_(0, 3) = -xhat_p_(2)*sinf(xhat_p_(3)); + A_p_(1, 2) = sin(xhat_p_(3)); + A_p_(1, 3) = xhat_p_(2)*cosf(xhat_p_(3)); + A_p_(2, 2) = -Vgdot/xhat_p_(2); + A_p_(2, 4) = -psidot*Vahat*sinf(xhat_p_(6))/xhat_p_(2); + A_p_(2, 5) = psidot*Vahat*cosf(xhat_p_(6))/xhat_p_(2); + A_p_(2, 6) = tmp; + A_p_(3, 2) = -params.gravity/powf(xhat_p_(2), 2)*tanf(phihat)*cosf(xhat_p_(3) - xhat_p_(6)); + A_p_(3, 3) = -params.gravity/xhat_p_(2)*tanf(phihat)*sinf(xhat_p_(3) - xhat_p_(6)); + A_p_(3, 6) = params.gravity/xhat_p_(2)*tanf(phihat)*sinf(xhat_p_(3) - xhat_p_(6)); + + xhat_p_ += f_p_*(params.Ts/N_); + P_p_ += (A_p_*P_p_ + P_p_*A_p_.transpose() + Q_p_)*(params.Ts/N_); + } + +// while(xhat_p(3) > radians(180.0f)) xhat_p(3) = xhat_p(3) - radians(360.0f); +// while(xhat_p(3) < radians(-180.0f)) xhat_p(3) = xhat_p(3) + radians(360.0f); +// if(xhat_p(3) > radians(180.0f) || xhat_p(3) < radians(-180.0f)) +// { +// ROS_WARN("Course estimate not wrapped from -pi to pi"); +// xhat_p(3) = 0; +// } + + // measurement updates + if (input.gps_new) + { + Eigen::MatrixXf I_p(7, 7); + I_p = Eigen::MatrixXf::Identity(7, 7); + + // gps North position + h_p_ = xhat_p_(0); + C_p_ = Eigen::VectorXf::Zero(7); + C_p_(0) = 1; + L_p_ = (P_p_*C_p_)/(R_p_(0, 0) + (C_p_.transpose()*P_p_*C_p_)); + P_p_ = (I_p - L_p_*C_p_.transpose())*P_p_; + xhat_p_ = xhat_p_ + L_p_*(input.gps_n - h_p_); + + // gps East position + h_p_ = xhat_p_(1); + C_p_ = Eigen::VectorXf::Zero(7); + C_p_(1) = 1; + L_p_ = (P_p_*C_p_)/(R_p_(1, 1) + (C_p_.transpose()*P_p_*C_p_)); + P_p_ = (I_p - L_p_*C_p_.transpose())*P_p_; + xhat_p_ = xhat_p_ + L_p_*(input.gps_e - h_p_); + + // gps ground speed + h_p_ = xhat_p_(2); + C_p_ = Eigen::VectorXf::Zero(7); + C_p_(2) = 1; + L_p_ = (P_p_*C_p_)/(R_p_(2, 2) + (C_p_.transpose()*P_p_*C_p_)); + P_p_ = (I_p - L_p_*C_p_.transpose())*P_p_; + xhat_p_ = xhat_p_ + L_p_*(input.gps_Vg - h_p_); + + // gps course + //wrap course measurement + float gps_course = fmodf(input.gps_course, radians(360.0f)); + + while (gps_course - xhat_p_(3) > radians(180.0f)) gps_course = gps_course - radians(360.0f); + while (gps_course - xhat_p_(3) < radians(-180.0f)) gps_course = gps_course + radians(360.0f); + h_p_ = xhat_p_(3); + C_p_ = Eigen::VectorXf::Zero(7); + C_p_(3) = 1; + L_p_ = (P_p_*C_p_)/(R_p_(3, 3) + (C_p_.transpose()*P_p_*C_p_)); + P_p_ = (I_p - L_p_*C_p_.transpose())*P_p_; + xhat_p_ = xhat_p_ + L_p_*(gps_course - h_p_); + +// // pseudo measurement #1 y_1 = Va*cos(psi)+wn-Vg*cos(chi) +// h_p = Vahat*cosf(xhat_p(6)) + xhat_p(4) - xhat_p(2)*cosf(xhat_p(3)); // pseudo measurement +// C_p = Eigen::VectorXf::Zero(7); +// C_p(2) = -cos(xhat_p(3)); +// C_p(3) = xhat_p(2)*sinf(xhat_p(3)); +// C_p(4) = 1; +// C_p(6) = -Vahat*sinf(xhat_p(6)); +// L_p = (P_p*C_p)/(R_p(4,4) + (C_p.transpose()*P_p*C_p)); +// P_p = (I_p - L_p*C_p.transpose())*P_p; +// xhat_p = xhat_p + L_p*(0 - h_p); + +// // pseudo measurement #2 y_2 = Va*sin(psi) + we - Vg*sin(chi) +// h_p = Vahat*sinf(xhat_p(6))+xhat_p(5)-xhat_p(2)*sinf(xhat_p(3)); // pseudo measurement +// C_p = Eigen::VectorXf::Zero(7); +// C_p(2) = -sin(xhat_p(3)); +// C_p(3) = -xhat_p(2)*cosf(xhat_p(3)); +// C_p(5) = 1; +// C_p(6) = Vahat*cosf(xhat_p(6)); +// L_p = (P_p*C_p)/(R_p(5,5) + (C_p.transpose()*P_p*C_p)); +// P_p = (I_p - L_p*C_p.transpose())*P_p; +// xhat_p = xhat_p + L_p*(0 - h_p); + + if (xhat_p_(0) > 10000 || xhat_p_(0) < -10000) + { + ROS_WARN("gps n limit reached"); + xhat_p_(0) = input.gps_n; + } + if (xhat_p_(1) > 10000 || xhat_p_(1) < -10000) + { + ROS_WARN("gps e limit reached"); + xhat_p_(1) = input.gps_e; + } + } + + bool problem = false; + int prob_index; + for (int i = 0; i < 7; i++) + { + if (!std::isfinite(xhat_p_(i))) + { + if (!problem) + { + problem = true; + prob_index = i; + } + switch (i) + { + case 0: + xhat_p_(i) = input.gps_n; + break; + case 1: + xhat_p_(i) = input.gps_e; + break; + case 2: + xhat_p_(i) = input.gps_Vg; + break; + case 3: + xhat_p_(i) = input.gps_course; + break; + case 6: + xhat_p_(i) = input.gps_course; + break; + default: + xhat_p_(i) = 0; + } + P_p_ = Eigen::MatrixXf::Identity(7, 7); + P_p_(0, 0) = .03; + P_p_(1, 1) = .03; + P_p_(2, 2) = .01; + P_p_(3, 3) = radians(5.0f); + P_p_(4, 4) = .04; + P_p_(5, 5) = .04; + P_p_(6, 6) = radians(5.0f); + } + } + if (problem) + { + ROS_WARN("position estimator reinitialized due to non-finite state %d", prob_index); + } + if (xhat_p_(6) - xhat_p_(3) > radians(360.0f) || xhat_p_(6) - xhat_p_(3) < radians(-360.0f)) + { + //xhat_p(3) = fmodf(xhat_p(3),2*M_PI); + xhat_p_(6) = fmodf(xhat_p_(6), 2*M_PI); + } + + float pnhat = xhat_p_(0); + float pehat = xhat_p_(1); + float Vghat = xhat_p_(2); + float chihat = xhat_p_(3); + float wnhat = xhat_p_(4); + float wehat = xhat_p_(5); + float psihat = xhat_p_(6); + + output.pn = pnhat; + output.pe = pehat; + output.h = hhat; + output.Va = Vahat; + output.alpha = 0; + output.beta = 0; + output.phi = phihat; + output.theta = thetahat; + output.chi = chihat; + output.p = phat; + output.q = qhat; + output.r = rhat; + output.Vg = Vghat; + output.wn = wnhat; + output.we = wehat; + output.psi = psihat; +} + +void estimator_example::check_xhat_a() +{ + if (xhat_a_(0) > radians(85.0) || xhat_a_(0) < radians(-85.0) || !std::isfinite(xhat_a_(0))) + { + if (!std::isfinite(xhat_a_(0))) + { + xhat_a_(0) = 0; + P_a_ = Eigen::Matrix2f::Identity(); + P_a_ *= powf(radians(20.0f), 2); + ROS_WARN("attiude estimator reinitialized due to non-finite roll"); + } + else if (xhat_a_(0) > radians(85.0)) + { + xhat_a_(0) = radians(82.0); + //ROS_WARN("max roll angle"); + } + else if (xhat_a_(0) < radians(-85.0)) + { + xhat_a_(0) = radians(-82.0); + //ROS_WARN("min roll angle"); + } + } + if (xhat_a_(1) > radians(80.0) || xhat_a_(1) < radians(-80.0) || !std::isfinite(xhat_a_(1))) + { + if (!std::isfinite(xhat_a_(1))) + { + xhat_a_(1) = 0; + P_a_ = Eigen::Matrix2f::Identity(); + P_a_ *= powf(radians(20.0f), 2); + ROS_WARN("attiude estimator reinitialized due to non-finite pitch"); + } + else if (xhat_a_(1) > radians(80.0)) + { + xhat_a_(1) = radians(77.0); + ROS_WARN("max pitch angle"); + } + else if (xhat_a_(1) < radians(-80.0)) + { + xhat_a_(1) = radians(-77.0); + ROS_WARN("min pitch angle"); + } + } +} + +} //end namespace diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_follower_base.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_follower_base.cpp new file mode 100644 index 0000000..744308a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_follower_base.cpp @@ -0,0 +1,162 @@ +#include "path_follower_base.h" +#include "path_follower_example.h" + +namespace hector +{ + +path_follower_base::path_follower_base() : nh_(ros::NodeHandle()), + nh_private_(ros::NodeHandle("~")) +{ + vehicle_state_sub_ = nh_.subscribe("state", 1, &path_follower_base::vehicle_state_callback, this); + bebop1_state_sub_ = nh_.subscribe("ground_truth/state", 1, &path_follower_base::bebop1_state_callback, this); + //bebop1_state_sub_ = nh_.subscribe("/test/odom", 1, &path_follower_base::bebop1_state_callback, this); + + current_path_sub_ = nh_.subscribe("current_path", 1, + &path_follower_base::current_path_callback, this); + + nh_private_.param("CHI_INFTY", params_.chi_infty, 1.0472); + nh_private_.param("K_PATH", params_.k_path, 0.025); + nh_private_.param("K_ORBIT", params_.k_orbit, 4.0); + + func_ = boost::bind(&path_follower_base::reconfigure_callback, this, _1, _2); + server_.setCallback(func_); + + update_timer_ = nh_.createTimer(ros::Duration(1.0 / update_rate_), &path_follower_base::update, this); + controller_commands_pub_ = nh_.advertise("controller_commands", 1); + + state_init_ = false; + current_path_init_ = false; +} + +void path_follower_base::update(const ros::TimerEvent &) +{ + + struct output_s output; + + if (state_init_ == true && current_path_init_ == true) + { + follow(params_, input_, output); + hector_msgs::Controller_Commands msg; + msg.chi_c = output.chi_c; + msg.landing=input_.landing; + msg.takeoff=input_.takeoff; + if (input_.Va_c_path == 0) + { + // ROS_INFO("Hello1"); + msg.Va_c = 0; + } + else + { + // ROS_INFO("Hello2"); + msg.Va_c = input_.Va_d; + } + + // ROS_INFO("what %f",msg.Va_c); + + msg.h_c = output.h_c; + msg.phi_ff = output.phi_ff; + controller_commands_pub_.publish(msg); + } +} + +void path_follower_base::vehicle_state_callback(const hector_msgs::StateConstPtr &msg) +{ + // input_.pn = msg->position[0]; /** position north */ + // input_.pe = msg->position[1]; /** position east */ + // input_.h = -msg->position[2]; /** altitude */ + // input_.chi = msg->chi; + // input_.Va = msg->Va; + + // state_init_ = true; +} +void path_follower_base::bebop1_state_callback(const nav_msgs::Odometry::ConstPtr &msg) +{ + // ROS_INFO("%g", msg->pose.pose.position.x); /** position north */ + input_.pn = msg->pose.pose.position.x; /** position north */ + input_.pe = msg->pose.pose.position.y; /** position east */ + input_.h = msg->pose.pose.position.z; /** altitude */ + input_.Va = sqrt(pow(msg->twist.twist.linear.x, 2) + pow(msg->twist.twist.linear.y, 2)); + input_.chi = path_follower_base::Quaternion_to_Euler(msg->pose.pose.orientation.x, msg->pose.pose.orientation.y, msg->pose.pose.orientation.z, msg->pose.pose.orientation.w); + // ROS_INFO("%g %g %g %g %g",input_.pn,input_.pe,input_.h,input_.Va,input_.chi); + state_init_ = true; +} + +float path_follower_base::Quaternion_to_Euler(float q0, float q1, float q2, float q3) +{ + float Radx; + float sum; + sum = sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); + if (sum == 0) + { + sum = 0.0001; + } + q0 = q0 / sum; + q1 = q1 / sum; + q2 = q2 / sum; + q3 = q3 / sum; + if (fabs(q2) < fabs(q3)) + { + Radx = asin(2.0f * (q2 * q3 + q0 * q1)); + return Radx; + } + else + { + if (q2 * q3 > 0) + { + Radx = 3.14159 - asin(2.0f * (q2 * q3 + q0 * q1)); + return Radx; + } + else + { + Radx = -3.14159 - asin(2.0f * (q2 * q3 + q0 * q1)); + return Radx; + } + } + //Radx = asin(2.0f*(q2*q3 + q0*q1)); + //Rady = atan2(-2 * q1 * q3 + 2 * q0 * q2, q3*q3 - q2 * q2 - q1 * q1 + q0 * q0); + //Radz = atan2(2 * q1*q2 - 2 * q0*q3, q2*q2 - q3*q3 + q0*q0 - q1*q1); + //return Radx; +} +void path_follower_base::current_path_callback(const hector_msgs::Current_PathConstPtr &msg) +{ + if (msg->path_type == msg->LINE_PATH) + input_.p_type = path_type::Line; + else if (msg->path_type == msg->ORBIT_PATH) + input_.p_type = path_type::Orbit; + else if (msg->path_type == msg->STAR_PATH) // add by kobe + input_.p_type = path_type::Star; + + input_.Va_d = msg->Va_d; + // ROS_INFO("hello %f",input_.Va_d); + for (int i = 0; i < 3; i++) + { + input_.r_path[i] = msg->r[i]; + input_.q_path[i] = msg->q[i]; + input_.c_orbit[i] = msg->c[i]; + } + input_.rho_orbit = msg->rho; + input_.lam_orbit = msg->lambda; + input_.h_c_path = msg->h_c; //add by kobe + input_.Va_c_path = msg->Va_d; + input_.landing = msg->landing; + input_.takeoff = msg->takeoff; + current_path_init_ = true; +} + +void path_follower_base::reconfigure_callback(hector::FollowerConfig &config, uint32_t level) +{ + params_.chi_infty = config.CHI_INFTY; + params_.k_path = config.K_PATH; + params_.k_orbit = config.K_ORBIT; +} +} // namespace hector + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "hector_path_follower"); + hector::path_follower_base *path = new hector::path_follower_example(); + + ros::spin(); + + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_follower_example.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_follower_example.cpp new file mode 100644 index 0000000..0ab25be --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_follower_example.cpp @@ -0,0 +1,81 @@ +#include "path_follower_example.h" + + +namespace hector +{ + +path_follower_example::path_follower_example() +{ +} + +void path_follower_example::follow(const params_s ¶ms, const input_s &input, output_s &output) +{ + if (input.p_type == path_type::Line) // follow straight line path specified by r and q + { + // compute wrapped version of the path angle + float chi_q = atan2f(input.q_path[1], input.q_path[0]); + + // modified by kobe + float chi=input.chi; + while (chi < -M_PI) + chi += 2*M_PI; + while (chi > M_PI) + chi -= 2*M_PI; + + + while (chi_q - chi < -M_PI) + chi_q += 2*M_PI; + while (chi_q - chi > M_PI) + chi_q -= 2*M_PI; + + float path_error = -sinf(chi_q)*(input.pn - input.r_path[0]) + cosf(chi_q)*(input.pe - input.r_path[1]); + // heading command + output.chi_c = chi_q - params.chi_infty*2/M_PI*atanf(params.k_path*path_error); + //ROS_INFO("hello1: %g %g %g %g",chi_q,input.chi,chi,output.chi_c); + + // desired altitude + output.h_c = -input.h_c_path;//h_c_path is negative;h_c is positive. + //kobe modified end + + /* ////for truth not state + while (chi_q - input.chi < -M_PI) + chi_q += 2*M_PI; + while (chi_q - input.chi > M_PI) + chi_q -= 2*M_PI; + float path_error = -sinf(chi_q)*(input.pn - input.r_path[0]) + cosf(chi_q)*(input.pe - input.r_path[1]); + // heading command + output.chi_c = chi_q - params.chi_infty*2/M_PI*atanf(params.k_path*path_error); //desired altitude + float h_d = -input.r_path[2] - sqrtf(powf((input.r_path[0] - input.pn), 2) + powf((input.r_path[1] - input.pe), + 2))*(input.q_path[2])/sqrtf(powf(input.q_path[0], 2) + powf(input.q_path[1], 2)); + // commanded altitude is desired altitude + output.h_c = h_d;// -input.r_path[2] - x// important for hover// kobe denote + */ + output.phi_ff = 0.0; + } + else if(input.p_type == path_type::Orbit)// follow a orbit path specified by c_orbit, rho_orbit, and lam_orbit + { + float d = sqrtf(powf((input.pn - input.c_orbit[0]), 2) + powf((input.pe - input.c_orbit[1]), + 2)); // distance from orbit center + // compute wrapped version of angular position on orbit + float varphi = atan2f(input.pe - input.c_orbit[1], input.pn - input.c_orbit[0]); + while ((varphi - input.chi) < -M_PI) + varphi += 2*M_PI; + while ((varphi - input.chi) > M_PI) + varphi -= 2*M_PI; + //compute orbit error + float norm_orbit_error = (d - input.rho_orbit)/input.rho_orbit; + output.chi_c = varphi + input.lam_orbit*(M_PI/2 + atanf(params.k_orbit*norm_orbit_error)); + + // commanded altitude is the height of the orbit + float h_d = -input.c_orbit[2]; + output.h_c = h_d; + output.phi_ff = 0;//(norm_orbit_error < 0.5 ? input.lam_orbit*atanf(input.Va*input.Va/(9.8*input.rho_orbit)) : 0); + } + else if(input.p_type == path_type::Star)// towards to a point in any direction on platform,r is the center;add by kobe + { + + } + output.Va_c = input.Va_d; +} + +} //end namespace diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_manager_base.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_manager_base.cpp new file mode 100644 index 0000000..35cf4f4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_manager_base.cpp @@ -0,0 +1,238 @@ +#include "path_manager_base.h" +#include "path_manager_example.h" + +namespace hector +{ + +path_manager_base::path_manager_base() : nh_(ros::NodeHandle()), /** nh_ stuff added here */ + nh_private_(ros::NodeHandle("~")) +{ + nh_private_.param("R_min", params_.R_min, 25); //25 + nh_private_.param("update_rate", update_rate_, 10.0); + + vehicle_state_sub_ = nh_.subscribe("state", 10, &path_manager_base::vehicle_state_callback, this); + bebop1_state_sub_ = nh_.subscribe("ground_truth/state", 10, &path_manager_base::bebop1_state_callback, this); + //bebop1_state_sub_ = nh_.subscribe("/test/odom", 10, &path_manager_base::bebop1_state_callback, this); + + new_waypoint_sub_ = nh_.subscribe("waypoint_path", 10, &path_manager_base::new_waypoint_callback, this); + + current_path_pub_ = nh_.advertise("current_path", 10); + goal_info_pub_ = nh_.advertise("Goal_Info", 10); + down_data_pub_ = nh_.advertise("serial_commu_down", 10); + + waypoint_received_sub_ = nh_.subscribe("new_waypoint", 10, &path_manager_base::waypoint_received_callback, this); + + update_timer_ = nh_.createTimer(ros::Duration(1.0 / update_rate_), &path_manager_base::current_path_publish, this); + + num_waypoints_ = 0; + + state_init_ = false; + + waypoint_received_ = false; +} + +void path_manager_base::waypoint_received_callback(const hector_msgs::Waypoint &msg) +{ + float ell = sqrtf((waypoint_end_.w[0] - msg.w[0]) * (waypoint_end_.w[0] - msg.w[0]) + + (waypoint_end_.w[1] - msg.w[1]) * (waypoint_end_.w[1] - msg.w[1])); + if (ell < 2.0 * params_.R_min) + { + ROS_ERROR("The distance between nodes must be larger than 2R."); + return; + } + waypoint_start_ = waypoint_end_; + + waypoint_end_.w[0] = msg.w[0]; + waypoint_end_.w[1] = msg.w[1]; + waypoint_end_.w[2] = msg.w[2]; + waypoint_end_.chi_d = msg.chi_d; + waypoint_end_.chi_valid = msg.chi_valid; + waypoint_end_.Va_d = msg.Va_d; + + waypoint_received_ = true; +} + +void path_manager_base::vehicle_state_callback(const hector_msgs::StateConstPtr &msg) +{ + vehicle_state_ = *msg; + //state_init_ = true; +} + +void path_manager_base::bebop1_state_callback(const nav_msgs::Odometry::ConstPtr &msg) +{ + bebop1_state_ = *msg; + state_init_ = true; +} + +void path_manager_base::new_waypoint_callback(const hector_msgs::Waypoint &msg) +{ + if (msg.clear_wp_list == true) + { + waypoints_.clear(); + num_waypoints_ = 0; + idx_a_ = 0; + min_distance_ = 1000000000; //add by kobe, just need to be larger than the large-enter-ball's radius. + min_distance_titude = 10000000000; + //return; + } + if (msg.set_current || num_waypoints_ == 0)//mean to set the start point as the a goal-never use---kobe denote + { + waypoint_s currentwp; + currentwp.w[0] = bebop1_state_.pose.pose.position.x; + currentwp.w[1] = bebop1_state_.pose.pose.position.y; + currentwp.w[2] = (-bebop1_state_.pose.pose.position.z > -25 ? msg.w[2] : -bebop1_state_.pose.pose.position.z); + currentwp.chi_d= path_manager_base::Quaternion_to_Euler(bebop1_state_.pose.pose.orientation.x,bebop1_state_.pose.pose.orientation.y,bebop1_state_.pose.pose.orientation.z,bebop1_state_.pose.pose.orientation.w); + // currentwp.w[0] = vehicle_state_.position[0]; + // currentwp.w[1] = vehicle_state_.position[1]; + // currentwp.w[2] = (vehicle_state_.position[2] > -25 ? msg.w[2] : vehicle_state_.position[2]); + // currentwp.chi_d = vehicle_state_.chi; + // add by kobe + currentwp.lat = vehicle_state_.Wd; + currentwp.lon = vehicle_state_.Jd; + + currentwp.chi_valid = msg.chi_valid; + currentwp.Va_d = msg.Va_d; + currentwp.landing=msg.landing; + currentwp.takeoff=msg.takeoff; + waypoints_.clear(); + waypoints_.push_back(currentwp); + num_waypoints_ = 1; + idx_a_ = 0; + min_distance_ = 10000000000; //add by kobe, just need to be larger than the large-enter-ball's radius. + min_distance_titude = 10000000000; + show = 1; + show2=1; + } + waypoint_s nextwp; + nextwp.w[0] = msg.w[0]; + nextwp.w[1] = msg.w[1]; + nextwp.w[2] = msg.w[2]; + // add by kobe + nextwp.lat=msg.lat; + nextwp.lon=msg.lon; + + nextwp.chi_d = msg.chi_d; + nextwp.chi_valid = msg.chi_valid; + nextwp.Va_d = msg.Va_d; + nextwp.landing=msg.landing; + nextwp.takeoff=msg.takeoff; + waypoints_.push_back(nextwp); + num_waypoints_++; + // ROS_INFO("num_waypoints_: %d", num_waypoints_); +} + +void path_manager_base::current_path_publish(const ros::TimerEvent &) +{ + struct input_s input; + input.pn = bebop1_state_.pose.pose.position.x; /** position north */ + input.pe = bebop1_state_.pose.pose.position.y; /** position east */ + input.h = bebop1_state_.pose.pose.position.z; /** altitude */ + input.chi =path_manager_base::Quaternion_to_Euler(bebop1_state_.pose.pose.orientation.x,bebop1_state_.pose.pose.orientation.y,bebop1_state_.pose.pose.orientation.z,bebop1_state_.pose.pose.orientation.w); + input.va = sqrt(pow(bebop1_state_.twist.twist.linear.x,2)+pow(bebop1_state_.twist.twist.linear.y,2)); + // input.pn = vehicle_state_.position[0]; /** position north */ + // input.pe = vehicle_state_.position[1]; /** position east */ + // input.h = -vehicle_state_.position[2]; /** altitude */ + // input.chi = vehicle_state_.chi; + // input.va = vehicle_state_.Va; + + //add by kobe + input.lat=vehicle_state_.Wd; + input.lon=vehicle_state_.Jd; + + struct output_s output; + + if (state_init_ == true) + { + manage(params_, input, output); + } + + hector_msgs::Current_Path current_path; + + hector_msgs::Goal_Info goal_info; + hector_msgs::Down_Data_New down_data; + // modified by kobe + if (output.flag == 1) + current_path.path_type = current_path.LINE_PATH; + else if (output.flag == 0) + current_path.path_type = current_path.ORBIT_PATH; + else if (output.flag == 2) + current_path.path_type = current_path.STAR_PATH; + + for (int i = 0; i < 3; i++) + { + current_path.r[i] = output.r[i]; + current_path.q[i] = output.q[i]; + current_path.c[i] = output.c[i]; + } + current_path.rho = output.rho; + current_path.lambda = output.lambda; + current_path.h_c = output.h_c; + current_path.Va_d = output.Va_c; //new speed + current_path.takeoff=output.takeoff; + current_path.landing=output.landing; + current_path_pub_.publish(current_path); + + goal_info.altitude=-output.h_c; + goal_info.v_d=output.Va_d; + goal_info.action=1;//desired action move + for (int i = 0; i < 2; i++) + { + goal_info.xy[i] = output.gxy[i]; + goal_info.ll[i] = output.gll[i]; + } + goal_info_pub_.publish(goal_info); // add by kobe + + down_data.latitude = output.gll[0]; + down_data.longitude = output.gll[1]; + down_data.altitude = -output.h_c; + down_data.plane_speed= output.Va_d; + down_data.status_word= 1; + //ROS_INFO("Look here %f %f %f %f",down_data.latitude,down_data.longitude,down_data.altitude,output.Va_d); + down_data_pub_.publish(down_data); // add by kobe +} + +//add by kobe +float path_manager_base::Quaternion_to_Euler(float q0, float q1, float q2, float q3) +{ + float Radx; + float sum; + sum = sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); + if (sum == 0) + { + sum = 0.0001; + } + q0 = q0 / sum; + q1 = q1 / sum; + q2 = q2 / sum; + q3 = q3 / sum; + if (fabs(q2) < fabs(q3)) + { + Radx = asin(2.0f * (q2 * q3 + q0 * q1)); + return Radx; + } + else + { + if (q2 * q3 > 0) + { + Radx = 3.14159 - asin(2.0f * (q2 * q3 + q0 * q1)); + return Radx; + } + else + { + Radx = -3.14159 - asin(2.0f * (q2 * q3 + q0 * q1)); + return Radx; + } + } +} + +} // namespace hector + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "hector_path_manager"); + hector::path_manager_base *est = new hector::path_manager_example(); + + ros::spin(); + + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_manager_example.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_manager_example.cpp new file mode 100644 index 0000000..e958014 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_manager_example.cpp @@ -0,0 +1,717 @@ +#include "path_manager_example.h" +#include "ros/ros.h" +#include + +namespace hector +{ + +path_manager_example::path_manager_example() : path_manager_base() +{ + fil_state_ = fillet_state::STRAIGHT; + // use this ! + dub_state_ = dubin_state::FIRST; +} +// done +void path_manager_example::manage(const params_s ¶ms, const input_s &input, output_s &output) +{ + + //ROS_INFO("num_waypoints_: %d",num_waypoints_); + if (num_waypoints_ < 2) + { + ROS_WARN_THROTTLE(4, "No waypoints received! Loitering about origin at 50m"); + output.flag = 0; //modified by kobe + output.Va_d = 12; + output.c[0] = 0.0f; + output.c[1] = 0.0f; + output.c[2] = -50.0f; + // Radius of orbital path (m) + output.rho = params.R_min; + // Direction of orbital path (clockwise is 1, counterclockwise is -1) + output.lambda = 1; + } + else + { + // do this, idx_a_ is initialized zero + if (waypoints_[idx_a_].chi_valid) + { + manage_dubins(params, input, output); + } + else + { + /** Switch the following for flying directly to waypoints, or filleting corners */ + manage_line(params, input, output); + //manage_fillet(params, input, output); + // manage_star(params, input, output); //add by kobe + } + } +} + +// add by kobe +void path_manager_example::manage_star(const params_s ¶ms, const input_s &input, output_s &output) +{ + Eigen::Vector3f w_start; + w_start << input.pn, input.pe, -input.h; //aircraft's position + + int idx_b; + int idx_c; + float the_distance_; + double the_distance_titude; //for latitude and longtitude + idx_b = idx_a_ + 1; + + if (idx_a_ < num_waypoints_ - 2) + { + idx_c = idx_b + 1; + } + else + { + idx_c = idx_b; + } + Eigen::Vector3f w_ip1(waypoints_[idx_c].w); + + Eigen::Vector3f w_im1(waypoints_[idx_a_].w); + Eigen::Vector3f w_i(waypoints_[idx_b].w); //the goal + + the_distance_ = sqrt(pow(w_start(0) - w_i(0), 2) + pow(w_start(1) - w_i(1), 2)); + the_distance_titude = earth_distance(input.lat, input.lon, waypoints_[idx_b].lat, waypoints_[idx_b].lon); + + output.flag = 1; //modified by kobe + output.Va_d = waypoints_[idx_b].Va_d; //modified by kobe + + //ROS_INFO("position: %g %g %g",w_start(0),w_start(1),w_start(2)); + //ROS_INFO("Current info are: %f %f %f %f", input.va, -input.h,w_start(0),w_start(1)); + + output.r[0] = w_start(0); + output.r[1] = w_start(1); + output.r[2] = w_start(2); + Eigen::Vector3f q_im1 = (w_i - w_start).normalized(); + output.q[0] = q_im1(0); + output.q[1] = q_im1(1); + output.q[2] = q_im1(2); + + output.gxy[0] = w_i(0); + output.gxy[1] = w_i(1); + output.gll[0] = waypoints_[idx_b].lat; + output.gll[1] = waypoints_[idx_b].lon; + output.h_c = w_i(2); //altitude of the goal + + if (idx_a_ == 0&&show2 == 1) + { + ROS_INFO("First goal info are: %f %f", w_i(0), w_i(1)); + ROS_INFO("Desired fly speed and height are: %f %f", output.Va_d, -w_i(2)); + show2=0; + } + //enter the slow-down area,recompute the speed + if (sqrt(pow(w_start(0) - w_i(0), 2) + pow(w_start(1) - w_i(1), 2)) < output.Va_d * 2 && idx_a_ == num_waypoints_ - 2) //enter the slowdown-ball and the goal is the last goal + { + output.Va_c = sqrt(pow(w_start(0) - w_i(0), 2) + pow(w_start(1) - w_i(1), 2))/2; + if (sqrt(pow(w_start(0) - w_i(0), 2) + pow(w_start(1) - w_i(1), 2)) < 0.5 ) + { + output.Va_c = 0; + } + // ROS_INFO("Now the speed is: %f",output.Va_c); + } + else + { + output.Va_c = output.Va_d; + } + output.landing=waypoints_[idx_b].landing; + output.takeoff=waypoints_[idx_b].takeoff; + /* //1.enter a tiny ball and switch goal + if (sqrt(pow(w_start(0) - w_i(0), 2) + pow(w_start(1) - w_i(1), 2)) < 5) //enter a tiny ball and switch goal + { + //ROS_INFO("00000o- %g %g %g", w_start(2), w_i(2), sqrt(pow(w_start(0) - w_i(0), 2) + pow(w_start(1) - w_i(1), 2))); + //ROS_INFO("last goal is: %f %f", w_i(0), w_i(1)); + //ROS_INFO("Va- %f/n", input.va); + if (idx_a_ == num_waypoints_ - 2) + { + idx_a_ = idx_a_; //do not update goal + //ROS_INFO("idx_a_- %f/n", idx_a_); + } + else + { + idx_a_++; + } + } + */ + /* + //2.enter a half-plane and switch,ahead 5 m from the goal point + Eigen::Vector3f w_i_plane; + w_i_plane=w_i; + w_i_plane(0)=w_i_plane(0)-5*( ( w_i(0)-w_im1(0) ) / ( 0.001+fabs(w_i(0)-w_im1(0)) ) ); + w_i_plane(1)=w_i_plane(1)-5*( ( w_i(1)-w_im1(1) ) / ( 0.001+fabs(w_i(1)-w_im1(1)) ) ); + if ((w_i_plane - w_start).normalized().dot((w_i_plane - w_im1).normalized())<0)//plane-method + { + if (idx_a_ == num_waypoints_ - 2) + idx_a_ = idx_a_;//do not update goal + else + idx_a_++; + } + */ + //3.Enter a large ball(large-enter-ball) first. Anyway, when the distance from the aircraft to goal become larger,switch to the next goal. + if (the_distance_ < min_distance_) + { + min_distance_ = the_distance_; + } + if (the_distance_titude < min_distance_titude) + { + min_distance_titude = the_distance_titude; + } + + // ROS_INFO("distance is : %.20f %f", earth_distance(input.lat, input.lon, waypoints_[idx_b].lat, waypoints_[idx_b].lon), sqrt(pow(w_start(0) - w_i(0), 2) + pow(w_start(1) - w_i(1), 2))); + + //ROS_INFO("000distance- %f %f", the_distance_, min_distance_); + //1.进入大圈且最å°è·ç¦»å¼€å§‹å¢žå¤§æ—¶;2.进入一个å°åœˆæ—¶ï¿½?分别针对北东å标和ç»çº¬åº¦åæ ‡ + judge_condition1 = (sqrt(pow(w_start(0) - w_i(0), 2) + pow(w_start(1) - w_i(1), 2)) < 3 && the_distance_ > min_distance_ + 1); + judge_condition2 = (earth_distance(input.lat, input.lon, waypoints_[idx_b].lat, waypoints_[idx_b].lon) < 3 && the_distance_titude > min_distance_titude + 1); + judge_condition3 = (sqrt(pow(w_start(0) - w_i(0), 2) + pow(w_start(1) - w_i(1), 2)) < 0.5); + judge_condition4 = (earth_distance(input.lat, input.lon, waypoints_[idx_b].lat, waypoints_[idx_b].lon) < 0.5); + // height judge + judge_condition5 = (sqrt(pow(w_start(2) - w_i(2), 2)) < 10); + + //notice here + judge_condition2=0; + judge_condition4=0; + + if ((judge_condition1 || judge_condition2 || judge_condition3 || judge_condition4) && judge_condition5) //switch + { + //ROS_INFO("distance- %f %f", the_distance_, min_distance_); + if (idx_a_ == num_waypoints_ - 2) + { + if (show == 1) + { + ROS_INFO("This goal is reached: %f %f", w_i(0), w_i(1)); + ROS_INFO("Current position are: %f %f", input.pn, input.pe); + ROS_INFO("No more goal, just hover and wait for the next goal."); + ROS_INFO("Desired speed and height are: %f %f", output.Va_d, -w_i(2)); + ROS_INFO("Current speed and height are: %f %f\n\n", input.va, input.h); + show = 0; + } + idx_a_ = idx_a_; //do not update goal + } + else + { + ROS_INFO("This goal is reached: %f %f", w_i(0), w_i(1)); + ROS_INFO("Current position are: %f %f", input.pn, input.pe); + ROS_INFO("Desired speed and height are: %f %f", output.Va_d, -w_i(2)); + ROS_INFO("Current speed and height are: %f %f", input.va, input.h); + ROS_INFO("New goal info are: %f %f\n\n", w_ip1(0), w_ip1(1)); + min_distance_ = sqrt(pow(w_i(0) - w_ip1(0), 2) + pow(w_i(1) - w_ip1(1), 2)); + idx_a_++; + } + } + // +} + +double path_manager_example::earth_distance(double latitude1, double longitude1, double latitude2, double longitude2) +{ + double Lat1 = latitude1 * M_PI_F / 180.00; // 纬度 + double Lat2 = latitude2 * M_PI_F / 180.00; + double a = Lat1 - Lat2; //两点纬度之差 + double b = longitude1 * M_PI_F / 180.00 - longitude2 * M_PI_F / 180.00; //ç»åº¦ä¹‹å·® + double s = 2 * asin(sqrt(pow(sin(a / 2), 2) + cos(Lat1) * cos(Lat2) * pow(sin(b / 2), 2))); //计算两点è·ç¦»çš„公�?/better when value is very samll + //double s2 = acos(cos(Lat1)*cos(Lat2)*cos(b)+sin(Lat1)*sin(Lat2));//计算两点è·ç¦»çš„公�? + s = s * EARTH_RADIUS; //弧长乘地çƒåŠå¾„(åŠå¾„为米�? + //s2 = s2 * EARTH_RADIUS;//弧长乘地çƒåŠå¾„(åŠå¾„为米�? + return s; +} + +void path_manager_example::manage_line(const params_s ¶ms, const input_s &input, output_s &output) +{ + Eigen::Vector3f p; + p << input.pn, input.pe, -input.h; + + int idx_b; + int idx_c; + if (idx_a_ == num_waypoints_ - 1) + { + idx_b = 0; + idx_c = 1; + } + else if (idx_a_ == num_waypoints_ - 2) + { + idx_b = num_waypoints_ - 1; + idx_c = 0; + } + else + { + idx_b = idx_a_ + 1; + idx_c = idx_b + 1; + } + + Eigen::Vector3f w_im1(waypoints_[idx_a_].w); + Eigen::Vector3f w_i(waypoints_[idx_b].w); + Eigen::Vector3f w_ip1(waypoints_[idx_c].w); + + output.flag = true; + output.Va_d = waypoints_[idx_a_].Va_d; + output.r[0] = w_im1(0); + output.r[1] = w_im1(1); + output.r[2] = w_im1(2); + Eigen::Vector3f q_im1 = (w_i - w_im1).normalized(); + Eigen::Vector3f q_i = (w_ip1 - w_i).normalized(); + output.q[0] = q_im1(0); + output.q[1] = q_im1(1); + output.q[2] = q_im1(2); + + Eigen::Vector3f n_i = (q_im1 + q_i).normalized(); + if ((p - w_i).dot(n_i) > 0.0f) + { + if (idx_a_ == num_waypoints_ - 1) + idx_a_ = 0; + else + idx_a_++; + } +} +void path_manager_example::manage_fillet(const params_s ¶ms, const input_s &input, output_s &output) +{ + if (num_waypoints_ < 3) //since it fillets don't make sense between just two points + { + manage_line(params, input, output); + return; + } + + Eigen::Vector3f p; + p << input.pn, input.pe, -input.h; + + int idx_b; + int idx_c; + if (idx_a_ == num_waypoints_ - 1) + { + idx_b = 0; + idx_c = 1; + } + else if (idx_a_ == num_waypoints_ - 2) + { + idx_b = num_waypoints_ - 1; + idx_c = 0; + } + else + { + idx_b = idx_a_ + 1; + idx_c = idx_b + 1; + } + + Eigen::Vector3f w_im1(waypoints_[idx_a_].w); + Eigen::Vector3f w_i(waypoints_[idx_b].w); + Eigen::Vector3f w_ip1(waypoints_[idx_c].w); + + float R_min = params.R_min; + + output.Va_d = waypoints_[idx_a_].Va_d; + output.r[0] = w_im1(0); + output.r[1] = w_im1(1); + output.r[2] = w_im1(2); + Eigen::Vector3f q_im1 = (w_i - w_im1).normalized(); + Eigen::Vector3f q_i = (w_ip1 - w_i).normalized(); + float beta = acosf(-q_im1.dot(q_i)); + + Eigen::Vector3f z; + switch (fil_state_) + { + case fillet_state::STRAIGHT: + output.flag = 1; //modified by kobe + output.q[0] = q_im1(0); + output.q[1] = q_im1(1); + output.q[2] = q_im1(2); + output.c[0] = 1; + output.c[1] = 1; + output.c[2] = 1; + output.rho = 1; + output.lambda = 1; + z = w_i - q_im1 * (R_min / tanf(beta / 2.0)); + if ((p - z).dot(q_im1) > 0) + fil_state_ = fillet_state::ORBIT; + break; + case fillet_state::ORBIT: + output.flag = 0; //modified by kobe + output.q[0] = q_i(0); + output.q[1] = q_i(1); + output.q[2] = q_i(2); + Eigen::Vector3f c = w_i - (q_im1 - q_i).normalized() * (R_min / sinf(beta / 2.0)); + output.c[0] = c(0); + output.c[1] = c(1); + output.c[2] = c(2); + output.rho = R_min; + output.lambda = ((q_im1(0) * q_i(1) - q_im1(1) * q_i(0)) > 0 ? 1 : -1); + z = w_i + q_i * (R_min / tanf(beta / 2.0)); + if ((p - z).dot(q_i) > 0) + { + if (idx_a_ == num_waypoints_ - 1) + idx_a_ = 0; + else + idx_a_++; + fil_state_ = fillet_state::STRAIGHT; + } + break; + } +} + +void path_manager_example::manage_dubins(const params_s ¶ms, const input_s &input, output_s &output) +{ + Eigen::Vector3f p; + //ROS_INFO("input.pn: %f, input.pe: %f, -input.h: %f",input.pn, input.pe, -input.h); + p << input.pn, input.pe, -input.h; + + /* uint8 path_type # Indicates strait line or orbital path + float32 Va_d # Desired airspeed (m/s) + float32[3] r # Vector to origin of straight line path (m) + float32[3] q # Unit vector, desired direction of travel for line path + float32[3] c # Center of orbital path (m) + float32 rho # Radius of orbital path (m) + int8 lambda # Direction of orbital path (clockwise is 1, counterclockwise is -1) + + uint8 ORBIT_PATH = 0 + uint8 LINE_PATH = 1 + + int8 CLOCKWISE = 1 + int8 COUNT_CLOCKWISE = -1 */ + + output.Va_d = waypoints_[idx_a_].Va_d; + output.r[0] = 0; + output.r[1] = 0; + output.r[2] = 0; + output.q[0] = 0; + output.q[1] = 0; + output.q[2] = 0; + output.c[0] = 0; + output.c[1] = 0; + output.c[2] = 0; + //ROS_INFO("dub_state_: %d",dub_state_); + switch (dub_state_) + { + case dubin_state::FIRST: + // path planning + // Algorithm11 P211 + dubinsParameters(waypoints_[0], waypoints_[1], params.R_min); + + waypoint_start_ = waypoints_[0]; + waypoint_end_ = waypoints_[1]; + + output.flag = 0; //modified by kobe + output.c[0] = dubinspath_.cs(0); + output.c[1] = dubinspath_.cs(1); + output.c[2] = dubinspath_.cs(2); + output.rho = dubinspath_.R; + output.lambda = dubinspath_.lams; + // p: current pos + // w1: waypoint 1 + // q1: unit vector of H1 + if ((p - dubinspath_.w1).dot(dubinspath_.q1) >= 0) // start in H1 + { + dub_state_ = dubin_state::BEFORE_H1_WRONG_SIDE; + } + else + { + dub_state_ = dubin_state::BEFORE_H1; + } + break; + case dubin_state::BEFORE_H1: + //waypoint_received_ = false; + output.flag = 0; //modified by kobe + output.c[0] = dubinspath_.cs(0); + output.c[1] = dubinspath_.cs(1); + output.c[2] = dubinspath_.cs(2); + output.rho = dubinspath_.R; + output.lambda = dubinspath_.lams; + if ((p - dubinspath_.w1).dot(dubinspath_.q1) >= 0) // entering H1 + { + dub_state_ = dubin_state::STRAIGHT; + } + break; + case dubin_state::BEFORE_H1_WRONG_SIDE: + //waypoint_received_ = false; + output.flag = 0; //modified by kobe + output.c[0] = dubinspath_.cs(0); + output.c[1] = dubinspath_.cs(1); + output.c[2] = dubinspath_.cs(2); + output.rho = dubinspath_.R; + output.lambda = dubinspath_.lams; + if ((p - dubinspath_.w1).dot(dubinspath_.q1) < 0) // exit H1 + { + dub_state_ = dubin_state::BEFORE_H1; + } + break; + case dubin_state::STRAIGHT: + output.flag = 1; //modified by kobe + output.r[0] = dubinspath_.w1(0); + output.r[1] = dubinspath_.w1(1); + output.r[2] = dubinspath_.w1(2); + // output.r[0] = dubinspath_.z1(0); + // output.r[1] = dubinspath_.z1(1); + // output.r[2] = dubinspath_.z1(2); + output.q[0] = dubinspath_.q1(0); + output.q[1] = dubinspath_.q1(1); + output.q[2] = dubinspath_.q1(2); + output.rho = 1; + output.lambda = 1; + //ROS_INFO("pos: [%f,%f,%f],w2: [%f,%f,%f],q1: [%f,%f,%f]",p[0],p[1],p[2],dubinspath_.w2[0],dubinspath_.w2[1],dubinspath_.w2[2],dubinspath_.q1[0],dubinspath_.q1[1],dubinspath_.q1[2]); + //ROS_INFO("w3: [%f,%f,%f]",dubinspath_.w3[0],dubinspath_.w3[1],dubinspath_.w3[2]); + //ROS_INFO("w1: [%f,%f,%f]",dubinspath_.w1[0],dubinspath_.w1[1],dubinspath_.w1[2]); + + if (waypoint_received_) + { + //start new path + // plan new Dubin's path to next waypoint configuration + waypoint_start_.w[0] = p[0]; + waypoint_start_.w[1] = p[1]; + waypoint_start_.w[2] = p[2]; + waypoint_start_.chi_d = 0; + waypoint_start_.chi_valid = true; + waypoint_start_.Va_d = 12; + dubinsParameters(waypoint_start_, waypoint_end_, params.R_min); + waypoint_received_ = false; + + if ((p - dubinspath_.w1).dot(dubinspath_.q1) >= 0) // start in H1 + { + dub_state_ = dubin_state::BEFORE_H1_WRONG_SIDE; + } + else + { + dub_state_ = dubin_state::BEFORE_H1; + } + } + else + { + if ((p - dubinspath_.w2).dot(dubinspath_.q1) >= 0) // entering H2 + { + if ((p - dubinspath_.w3).dot(dubinspath_.q3) >= 0) // start in H3 + { + dub_state_ = dubin_state::BEFORE_H3_WRONG_SIDE; + } + else + { + dub_state_ = dubin_state::BEFORE_H3; + } + } + } + break; + case dubin_state::BEFORE_H3: + output.flag = 0; //modified by kobe + output.c[0] = dubinspath_.ce(0); + output.c[1] = dubinspath_.ce(1); + output.c[2] = dubinspath_.ce(2); + output.rho = dubinspath_.R; + output.lambda = dubinspath_.lame; + if ((p - dubinspath_.w3).dot(dubinspath_.q3) >= 0) // entering H3 + { + if (!waypoint_received_) + { + if ((p - dubinspath_.w1).dot(dubinspath_.q1) >= 0) // start in H1 + { + //dub_state_ = dubin_state::BEFORE_H1_WRONG_SIDE; + dub_state_ = dubin_state::BEFORE_H3_WRONG_SIDE; + } + else + { + //dub_state_ = dubin_state::BEFORE_H1; + dub_state_ = dubin_state::BEFORE_H3; + } + } + else + { + //start new path + // plan new Dubin's path to next waypoint configuration + dubinsParameters(waypoint_start_, waypoint_end_, params.R_min); + waypoint_received_ = false; + + if ((p - dubinspath_.w1).dot(dubinspath_.q1) >= 0) // start in H1 + { + dub_state_ = dubin_state::BEFORE_H1_WRONG_SIDE; + } + else + { + dub_state_ = dubin_state::BEFORE_H1; + } + } + } + break; + case dubin_state::BEFORE_H3_WRONG_SIDE: + output.flag = 0; //modified by kobe + output.c[0] = dubinspath_.ce(0); + output.c[1] = dubinspath_.ce(1); + output.c[2] = dubinspath_.ce(2); + output.rho = dubinspath_.R; + output.lambda = dubinspath_.lame; + /* + if ((p - dubinspath_.w3).dot(dubinspath_.q3) < 0) // exit H3 + { + if(!waypoint_received_) + //dub_state_ = dubin_state::BEFORE_H1; + dub_state_ = dubin_state::BEFORE_H3; + else + dub_state_ = dubin_state::BEFORE_H1; + } +*/ + if ((p - dubinspath_.w3).dot(dubinspath_.q3) < 0) // exit H3 + dub_state_ = dubin_state::BEFORE_H3; + else + dub_state_ = dubin_state::BEFORE_H3_WRONG_SIDE; + + break; + } +} + +Eigen::Matrix3f path_manager_example::rotz(float theta) +{ + Eigen::Matrix3f R; + R << cosf(theta), -sinf(theta), 0, + sinf(theta), cosf(theta), 0, + 0, 0, 1; + + return R; +} +// done +float path_manager_example::mo(float in) +{ + float val; + if (in > 0) + val = fmod(in, 2.0 * M_PI_F); + else + { + float n = floorf(in / 2.0 / M_PI_F); + val = in - n * 2.0 * M_PI_F; + } + return val; +} + +void path_manager_example::dubinsParameters(const waypoint_s start_node, const waypoint_s end_node, float R) +{ + float ell = sqrtf((start_node.w[0] - end_node.w[0]) * (start_node.w[0] - end_node.w[0]) + + (start_node.w[1] - end_node.w[1]) * (start_node.w[1] - end_node.w[1])); + if (ell < 2.0 * R) + { + ROS_ERROR("SHOULD NOT HAPPEN: The distance between nodes must be larger than 2R."); + } + else + { + dubinspath_.ps(0) = start_node.w[0]; + dubinspath_.ps(1) = start_node.w[1]; + dubinspath_.ps(2) = start_node.w[2]; + dubinspath_.chis = start_node.chi_d; + dubinspath_.pe(0) = end_node.w[0]; + dubinspath_.pe(1) = end_node.w[1]; + dubinspath_.pe(2) = end_node.w[2]; + dubinspath_.chie = end_node.chi_d; + + Eigen::Vector3f crs = dubinspath_.ps; + crs(0) += R * (cosf(M_PI_2_F) * cosf(dubinspath_.chis) - sinf(M_PI_2_F) * sinf(dubinspath_.chis)); + crs(1) += R * (sinf(M_PI_2_F) * cosf(dubinspath_.chis) + cosf(M_PI_2_F) * sinf(dubinspath_.chis)); + Eigen::Vector3f cls = dubinspath_.ps; + cls(0) += R * (cosf(-M_PI_2_F) * cosf(dubinspath_.chis) - sinf(-M_PI_2_F) * sinf(dubinspath_.chis)); + cls(1) += R * (sinf(-M_PI_2_F) * cosf(dubinspath_.chis) + cosf(-M_PI_2_F) * sinf(dubinspath_.chis)); + Eigen::Vector3f cre = dubinspath_.pe; + cre(0) += R * (cosf(M_PI_2_F) * cosf(dubinspath_.chie) - sinf(M_PI_2_F) * sinf(dubinspath_.chie)); + cre(1) += R * (sinf(M_PI_2_F) * cosf(dubinspath_.chie) + cosf(M_PI_2_F) * sinf(dubinspath_.chie)); + Eigen::Vector3f cle = dubinspath_.pe; + cle(0) += R * (cosf(-M_PI_2_F) * cosf(dubinspath_.chie) - sinf(-M_PI_2_F) * sinf(dubinspath_.chie)); + cle(1) += R * (sinf(-M_PI_2_F) * cosf(dubinspath_.chie) + cosf(-M_PI_2_F) * sinf(dubinspath_.chie)); + + float theta, theta2; + // compute L1 + theta = atan2f(cre(1) - crs(1), cre(0) - crs(0)); + float L1 = (crs - cre).norm() + R * mo(2.0 * M_PI_F + mo(theta - M_PI_2_F) - mo(dubinspath_.chis - M_PI_2_F)) + R * mo(2.0 * M_PI_F + mo(dubinspath_.chie - M_PI_2_F) - mo(theta - M_PI_2_F)); + + // compute L2 + ell = (cle - crs).norm(); + theta = atan2f(cle(1) - crs(1), cle(0) - crs(0)); + float L2; + if (2.0 * R > ell) + L2 = 9999.0f; + else + { + theta2 = theta - M_PI_2_F + asinf(2.0 * R / ell); + L2 = sqrtf(ell * ell - 4.0 * R * R) + R * mo(2.0 * M_PI_F + mo(theta2) - mo(dubinspath_.chis - M_PI_2_F)) + R * mo(2.0 * M_PI_F + mo(theta2 + M_PI_F) - mo(dubinspath_.chie + M_PI_2_F)); + } + + // compute L3 + ell = (cre - cls).norm(); + theta = atan2f(cre(1) - cls(1), cre(0) - cls(0)); + float L3; + if (2.0 * R > ell) + L3 = 9999.0f; + else + { + theta2 = acosf(2.0 * R / ell); + L3 = sqrtf(ell * ell - 4 * R * R) + R * mo(2.0 * M_PI_F + mo(dubinspath_.chis + M_PI_2_F) - mo(theta + theta2)) + R * mo(2.0 * M_PI_F + mo(dubinspath_.chie - M_PI_2_F) - mo(theta + theta2 - M_PI_F)); + } + + // compute L4 + theta = atan2f(cle(1) - cls(1), cle(0) - cls(0)); + float L4 = (cls - cle).norm() + R * mo(2.0 * M_PI_F + mo(dubinspath_.chis + M_PI_2_F) - mo(theta + M_PI_2_F)) + R * mo(2.0 * M_PI_F + mo(theta + M_PI_2_F) - mo(dubinspath_.chie + M_PI_2_F)); + + // L is the minimum distance + int idx = 1; + dubinspath_.L = L1; + if (L2 < dubinspath_.L) + { + dubinspath_.L = L2; + idx = 2; + } + if (L3 < dubinspath_.L) + { + dubinspath_.L = L3; + idx = 3; + } + if (L4 < dubinspath_.L) + { + dubinspath_.L = L4; + idx = 4; + } + + Eigen::Vector3f e1; + // e1.zero(); + e1(0) = 1; + e1(1) = 0; + e1(2) = 0; + switch (idx) + { + case 1: + dubinspath_.cs = crs; + dubinspath_.lams = 1; + dubinspath_.ce = cre; + dubinspath_.lame = 1; + dubinspath_.q1 = (cre - crs).normalized(); + dubinspath_.w1 = dubinspath_.cs + (rotz(-M_PI_2_F) * dubinspath_.q1) * R; + dubinspath_.w2 = dubinspath_.ce + (rotz(-M_PI_2_F) * dubinspath_.q1) * R; + break; + case 2: + dubinspath_.cs = crs; + dubinspath_.lams = 1; + dubinspath_.ce = cle; + dubinspath_.lame = -1; + ell = (cle - crs).norm(); + theta = atan2f(cle(1) - crs(1), cle(0) - crs(0)); + theta2 = theta - M_PI_2_F + asinf(2.0 * R / ell); + dubinspath_.q1 = rotz(theta2 + M_PI_2_F) * e1; + dubinspath_.w1 = dubinspath_.cs + (rotz(theta2) * e1) * R; + dubinspath_.w2 = dubinspath_.ce + (rotz(theta2 + M_PI_F) * e1) * R; + break; + case 3: + dubinspath_.cs = cls; + dubinspath_.lams = -1; + dubinspath_.ce = cre; + dubinspath_.lame = 1; + ell = (cre - cls).norm(); + theta = atan2f(cre(1) - cls(1), cre(0) - cls(0)); + theta2 = acosf(2.0 * R / ell); + dubinspath_.q1 = rotz(theta + theta2 - M_PI_2_F) * e1; + dubinspath_.w1 = dubinspath_.cs + (rotz(theta + theta2) * e1) * R; + dubinspath_.w2 = dubinspath_.ce + (rotz(theta + theta2 - M_PI_F) * e1) * R; + break; + case 4: + dubinspath_.cs = cls; + dubinspath_.lams = -1; + dubinspath_.ce = cle; + dubinspath_.lame = -1; + dubinspath_.q1 = (cle - cls).normalized(); + dubinspath_.w1 = dubinspath_.cs + (rotz(M_PI_2_F) * dubinspath_.q1) * R; + dubinspath_.w2 = dubinspath_.ce + (rotz(M_PI_2_F) * dubinspath_.q1) * R; + break; + } + dubinspath_.w3 = dubinspath_.pe; + dubinspath_.q3 = rotz(dubinspath_.chie) * e1; + dubinspath_.R = R; + } +} + +} // namespace hector diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_planner.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_planner.cpp new file mode 100644 index 0000000..6a4110a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_planner.cpp @@ -0,0 +1,63 @@ +#include +#include +#define EARTH_RADIUS 6378145.0f +#define num_waypoints 3 +float pn2latitude(float pn,float init_lat_) +{ + return (pn*180)/(EARTH_RADIUS*M_PI)+init_lat_; +} + +float pe2longtitude(float pe,float init_lat_,float init_lon_) +{ + return (pe*180)/(EARTH_RADIUS*cos(init_lat_*M_PI/180.0)*M_PI)+init_lon_; +} + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "hector_simple_path_planner"); + + ros::NodeHandle nh_; + ros::Publisher waypointPublisher = nh_.advertise("waypoint_path", 10); + + float Va = 3; + int tmp; + tmp = 7; //notice here + float wps[tmp * num_waypoints] = + { + // pn,pe,altitude,-,va,lat,lon + // 20, 10, -10, 0, 3, pn2latitude(20,0), pe2longtitude(0,0,0), + // 30, 20, -10, 0, Va, pn2latitude(30,0), pe2longtitude(30,0,0), + // 0, 20, -12, 0, 5, pn2latitude(0,0), pe2longtitude(20,0,0), + 0, 10, -10, 0, 3, pn2latitude(20,0), pe2longtitude(0,0,0), + }; + + for (int i(0); i < num_waypoints; i++) + { + ros::Duration(0.5).sleep(); + + hector_msgs::Waypoint new_waypoint; + + new_waypoint.w[0] = wps[i * tmp + 0]; + new_waypoint.w[1] = wps[i * tmp + 1]; + new_waypoint.w[2] = wps[i * tmp + 2]; + new_waypoint.chi_d = wps[i * tmp + 3]; + new_waypoint.Va_d = wps[i * tmp + 4]; + // add by kobe + new_waypoint.lat = wps[i * tmp + 5]; + new_waypoint.lon = wps[i * tmp + 6]; + + new_waypoint.chi_valid = false; //kobe + + if (i == 0) + new_waypoint.set_current = true; + else + new_waypoint.set_current = false; + + new_waypoint.clear_wp_list = false; + + waypointPublisher.publish(new_waypoint); + } + ros::Duration(1.5).sleep(); + + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_point_transfer.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_point_transfer.cpp new file mode 100644 index 0000000..f9a8dcc --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/path_point_transfer.cpp @@ -0,0 +1,93 @@ +#include "path_point_transfer.h" +// #include "path_point_transfer.h" +#define EARTH_RADIUS 6378137.0f //6378145.0f + +namespace hector +{ + +float init_lat_ = 41.71671500; /**< Initial latitude in degrees */ +float init_lon_ = 87.53306850; /**< Initial longitude in degrees */ +float init_alt_ = 1180; //>0 1180 + +float latitude2pn(float latitude, float init_lat_) +{ + return EARTH_RADIUS * (latitude - init_lat_) * M_PI / 180.0; +} + +float longtitude2pe(float longitude, float init_lat_, float init_lon_) +{ + return EARTH_RADIUS * cos(init_lat_ * M_PI / 180.0) * (longitude - init_lon_) * M_PI / 180.0; +} + +path_point_transfer::path_point_transfer() : nh_(ros::NodeHandle()), /** nh_ stuff added here */ + nh_private_(ros::NodeHandle("~")) +{ + nh_private_.param("update_rate", update_rate_, 10.0); + + // vehicle_state_sub_ = nh_.subscribe("state", 1000, &path_point_transfer::vehicle_state_callback, this); + bebop1_state_sub_ = nh_.subscribe("ground_truth/state", 10, &path_point_transfer::bebop1_state_callback, this); + new_waypoint_sub_ = nh_.subscribe("serial_commu_down", 1000, &path_point_transfer::new_waypoint_callback, this); + + current_path_pub_ = nh_.advertise("current_path", 1000); + + update_timer_ = nh_.createTimer(ros::Duration(1.0 / update_rate_), &path_point_transfer::current_path_publish, this); + + state_init_ = false; + + waypoint_received_ = false; +} + +path_point_transfer::~path_point_transfer() +{ + // stop(); +} + +// void path_point_transfer::vehicle_state_callback(const hector_msgs::StateConstPtr &msg) +// { +// vehicle_state_ = *msg; +// state_init_ = true; +// } + +void path_point_transfer::bebop1_state_callback(const nav_msgs::Odometry::ConstPtr &msg) +{ + bebop1_state_ = *msg; + state_init_ = true; +} + +void path_point_transfer::new_waypoint_callback(const hector_msgs::Down_Data_NewConstPtr &msg) +{ + point_state_ = *msg; + waypoint_received_ = true; +} + +void path_point_transfer::current_path_publish(const ros::TimerEvent &) +{ + Eigen::Vector3f w_start; + Eigen::Vector3f w_end; + w_start << bebop1_state_.pose.pose.position.x, bebop1_state_.pose.pose.position.y, bebop1_state_.pose.pose.position.z; //aircraft's position + w_end << latitude2pn(point_state_.latitude, init_lat_), longtitude2pe(point_state_.longitude, init_lat_, init_lon_), -point_state_.altitude; + ROS_WARN("startpn,%g,startpe,%g,pn,%g,pe,%g",vehicle_state_.position[0], vehicle_state_.position[1],latitude2pn(point_state_.latitude, init_lat_), longtitude2pe(point_state_.longitude, init_lat_, init_lon_)); + Eigen::Vector3f q_1 = (w_end - w_start).normalized(); + hector_msgs::Current_Path current_path; + current_path.path_type = current_path.LINE_PATH; + current_path.Va_d = point_state_.plane_speed; + for (int i = 0; i < 3; i++) + { + current_path.r[i] = w_start[i]; + current_path.q[i] = q_1[i]; + } + current_path.h_c = -point_state_.altitude; //current_path.h_c<0 å’Œstate统一 + current_path_pub_.publish(current_path); +} + +} // namespace hector + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "hector_path_point_transfer"); + hector::path_point_transfer *cont = new hector::path_point_transfer(); + // hector::path_point_transfer pp; + ros::spin(); + + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/pseudo_controller_base.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/pseudo_controller_base.cpp new file mode 100644 index 0000000..ae93773 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/pseudo_controller_base.cpp @@ -0,0 +1,212 @@ +#include "pseudo_controller_base.h" +#include "pseudo_controller_example.h" +// modified by kobe +namespace hector +{ + +pseudo_controller_base::pseudo_controller_base(): + nh_(ros::NodeHandle()), + nh_private_(ros::NodeHandle()) +{ + //ROS_INFO("hello"); + vehicle_state_sub_ = nh_.subscribe("state", 10, &pseudo_controller_base::vehicle_state_callback, this); + bebop1_state_sub_ = nh_.subscribe("ground_truth/state", 10, &pseudo_controller_base::bebop1_state_callback, this); + //bebop1_state_sub_ = nh_.subscribe("/test/odom", 10, &pseudo_controller_base::bebop1_state_callback, this); + + + + controller_commands_sub_ = nh_.subscribe("controller_commands", 10, &pseudo_controller_base::controller_commands_callback,this); + + memset(&vehicle_state_, 0, sizeof(vehicle_state_)); + memset(&bebop1_state_, 0, sizeof(bebop1_state_)); + + memset(&controller_commands_, 0, sizeof(controller_commands_)); + + nh_private_.param("TRIM_T", params_.trim_t, 0.3); + + nh_private_.param("ALT_TOZ", params_.alt_toz, 1.5); + nh_private_.param("ALT_HZ", params_.alt_hz, 0.2); + nh_private_.param("TAU", params_.tau, 5.0); + nh_private_.param("COURSE_KP", params_.c_kp, 0.7329); + //nh_private_.param("COURSE_KD", params_.c_kd, 0.0); + nh_private_.param("COURSE_KI", params_.c_ki, 0.0); + + nh_private_.param("AS_PITCH_KI", params_.a_p_ki, 0.0); + nh_private_.param("AS_THR_KP", params_.a_t_kp, 0.9); + nh_private_.param("AS_THR_KD", params_.a_t_kd, 0.0); + nh_private_.param("AS_THR_KI", params_.a_t_ki, 0.0); + nh_private_.param("ALT_KP", params_.a_kp, 0.045); + nh_private_.param("ALT_KD", params_.a_kd, 0.0); + nh_private_.param("ALT_KI", params_.a_ki, 0.0); + + //nh_private_.param("MAX_A", params_.max_a, 0.523);//rotate_trans + //nh_private_.param("MAX_T", params_.max_t, 1.0); + nh_private_.param("MAX_T", params_.max_t, 200.0); + + func_ = boost::bind(&pseudo_controller_base::reconfigure_callback, this, _1, _2); + server_.setCallback(func_); + + //pesudors_pub_ = nh_.advertise("command", 10); + pesudors_pub_ = nh_.advertise("cmd_vel", 10); + internals_pub_ = nh_.advertise("controller_inners", 10); + act_pub_timer_ = nh_.createTimer(ros::Duration(1.0/100.0), &pseudo_controller_base::actuator_controls_publish, this); + + command_recieved_ = false; +} + +void pseudo_controller_base::vehicle_state_callback(const hector_msgs::StateConstPtr &msg) +{ + vehicle_state_ = *msg; +} + +void pseudo_controller_base::bebop1_state_callback(const nav_msgs::Odometry::ConstPtr &msg) +{ + bebop1_state_ = *msg; +} + +void pseudo_controller_base::controller_commands_callback(const hector_msgs::Controller_CommandsConstPtr &msg) +{ + command_recieved_ = true; + controller_commands_ = *msg; +} + +void pseudo_controller_base::reconfigure_callback(hector::ControllerConfig &config, uint32_t level) +{ + params_.trim_t = config.TRIM_T; + + params_.c_kp = config.COURSE_KP; + //params_.c_kd = config.COURSE_KD; + params_.c_ki = config.COURSE_KI; + + params_.a_p_ki = config.AS_PITCH_KI; + + params_.a_t_kp = config.AS_THR_KP; + params_.a_t_kd = config.AS_THR_KD; + params_.a_t_ki = config.AS_THR_KI; + + params_.a_kp = config.ALT_KP; + params_.a_kd = config.ALT_KD; + params_.a_ki = config.ALT_KI; + +} + + +void pseudo_controller_base::actuator_controls_publish(const ros::TimerEvent &) +{ + struct input_s input; + //input.h = -vehicle_state_.position[2]; + //input.va = vehicle_state_.Va; + //input.chi = vehicle_state_.chi; + input.h = bebop1_state_.pose.pose.position.z; /** altitude */ + input.va = sqrt(pow(bebop1_state_.twist.twist.linear.x,2)+pow(bebop1_state_.twist.twist.linear.y,2)); + input.chi =pseudo_controller_base::Quaternion_to_Euler(bebop1_state_.pose.pose.orientation.x,bebop1_state_.pose.pose.orientation.y,bebop1_state_.pose.pose.orientation.z,bebop1_state_.pose.pose.orientation.w); + // ROS_INFO("LOOK here1: %f",input.chi); + input.Va_c = controller_commands_.Va_c; + input.h_c = controller_commands_.h_c;//3>controller_commands_.h_c)?3:controller_commands_.h_c; + input.chi_c = controller_commands_.chi_c; + input.takeoff = controller_commands_.takeoff; + input.landing = controller_commands_.landing; + input.Ts = 0.01f; + if (controller_commands_.Va_c==0) + { + reached=1; + } + struct output_s output; + + if (command_recieved_ == true) + { + control(params_, input, output); + + //convert_to_pwm(output); + geometry_msgs::Twist cmd_vel; + //rosflight_msgs::Command pseudors; + /* publish pseudors controls */ + cmd_vel.linear.x = output.forward_trans;//head vel + cmd_vel.linear.y = output.left_right_trans; + cmd_vel.linear.z = output.up_down_trans; + cmd_vel.angular.x = 0; + cmd_vel.angular.y = 0;//output.roll_trans; +if (input.va > 0.1) + cmd_vel.angular.z = output.rotate_trans;//output.rotate_trans +else +cmd_vel.angular.z = 0; + + pesudors_pub_.publish(cmd_vel); + //ROS_INFO("hello %f",bebop1_state_.pose.pose.position.z); + // ROS_INFO("x-y-z-w: %f %f %f %f",cmd_vel.linear.x,cmd_vel.linear.y,cmd_vel.linear.z,cmd_vel.angular.z); + // ROS_INFO("six: %f %f %f %f %f %f\n",input.h,input.h_c,input.va,input.Va_c,input.chi,input.chi_c); + // ROS_INFO("position: %f %f %f",bebop1_state_.pose.pose.position.x,bebop1_state_.pose.pose.position.y,bebop1_state_.pose.pose.position.z); + if (internals_pub_.getNumSubscribers() > 0) + { + hector_msgs::Controller_Internals inners; + //sinners.phi_c = output.phi_c; + //inners.theta_c = output.theta_c; + switch (output.current_zone) + { + case alt_zones::TAKE_OFF: + inners.alt_zone = inners.ZONE_TAKE_OFF; + break; + case alt_zones::CLIMB: + inners.alt_zone = inners.ZONE_CLIMB; + break; + case alt_zones::DESCEND: + inners.alt_zone = inners.ZONE_DESEND; + break; + case alt_zones::ALTITUDE_HOLD: + inners.alt_zone = inners.ZONE_ALTITUDE_HOLD; + break; + default: + break; + } + inners.aux_valid = false; + internals_pub_.publish(inners); + } + } +} + +float pseudo_controller_base::Quaternion_to_Euler(float q0,float q1,float q2,float q3) +{ + float Radx; + float sum; + sum = sqrt(q0*q0 + q1*q1 + q2*q2 + q3*q3); + if (sum==0) + { + sum=0.0001; + } + q0 = q0 / sum; + q1 = q1 / sum; + q2 = q2 / sum; + q3 = q3 / sum; + + // ROS_INFO("LOOK here2: %f",asin(2.0f*(q2*q3 + q0*q1))); + if (fabs(q2)0) + { + Radx = 3.14159-asin(2.0f*(q2*q3 + q0*q1)); + return Radx; + } + else + { + Radx = -3.14159-asin(2.0f*(q2*q3 + q0*q1)); + return Radx; + } + } +} + +} //end namespace + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "hector_controller"); + hector::pseudo_controller_base *cont = new hector::pseudo_controller_example(); + + ros::spin(); + + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/pseudo_controller_example.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/pseudo_controller_example.cpp new file mode 100644 index 0000000..df3453a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/pseudo_controller_example.cpp @@ -0,0 +1,326 @@ +#include "pseudo_controller_example.h" +//modified by kobe +namespace hector +{ + +pseudo_controller_example::pseudo_controller_example() : pseudo_controller_base() +{ + current_zone = alt_zones::PREPARE; + //current_zone = alt_zones::TAKE_OFF; + c_error_ = 0; + c_integrator_ = 0; + r_error_ = 0; + r_integrator_ = 0; + a_error_ = 0; + a_integrator_ = 0; + at_error_ = 0; + at_integrator_ = 0; + ap_error_ = 0; + ap_integrator_ = 0; +} + +void pseudo_controller_example::control(const params_s ¶ms, const input_s &input, output_s &output) +{ + output.up_down_trans = 0; + output.forward_trans = 0; + output.rotate_trans = 0; + output.left_right_trans = 0; + + output.rotate_value=pseudo_course(input.chi, input.chi_c); + output.rotate_trans = output.rotate_value;//pseudo_course_hold(input.chi, input.chi_c, params, input.Ts); + + + if (input.landing==true) // protect-landing first + { + current_zone = alt_zones::LANDING; + } + if (input.takeoff==true && current_zone==alt_zones::LANDING) + { + current_zone = alt_zones::PREPARE; + } + + switch (current_zone) + { + case alt_zones::PREPARE: + output.up_down_trans = 0.5; + output.forward_trans = 0; + output.left_right_trans = 0; + output.rotate_trans=0; + if (input.h >= 1) // + { + ROS_DEBUG("TAKEOFF"); + current_zone = alt_zones::TAKE_OFF; + } + break; + case alt_zones::TAKE_OFF: + //output.rotate_trans = 1.5*pseudo_course_hold(input.chi, input.chi_c, params, input.Ts);//recover + //output.forward_trans = 0.7;//0.1 * pseudo_throttle_hold(input.Va_c, input.va, params, input.Ts); + output.forward_trans = input.Va_c;//pseudo_throttle_hold(input.Va_c, input.va, params, input.Ts); + output.up_down_trans = pow(1.1,input.h)*pseudo_pitch_hold(input.h_c, input.h, params, input.Ts); + //output.up_down_trans = 0.01 * pseudo_pitch_hold(input.h_c, input.h, params, input.Ts); + //if (input.h >= params.alt_toz) //alt_toz=1.5//recovery + //output.left_right_trans = 1.5*pseudo_left_right(input.chi, input.chi_c, output.forward_trans); + if (input.h >= 1.5) // + { + ROS_DEBUG("climb"); + current_zone = alt_zones::CLIMB; + ap_error_ = 0; + ap_integrator_ = 0; + ap_differentiator_ = 0; + } + break; + case alt_zones::CLIMB: + output.forward_trans = input.Va_c;//sat(input.Va_c*cos(output.rotate_trans),5,0.5);//pseudo_throttle_hold(input.Va_c, input.va, params, input.Ts); + //output.forward_trans = 0.8;//0.1 * pseudo_throttle_hold(input.Va_c, input.va, params, input.Ts); + output.left_right_trans = 0;//sat(input.Va_c*sin(output.rotate_trans),5,-5);//pseudo_left_right(input.chi, input.chi_c, output.forward_trans); + output.up_down_trans = pseudo_pitch_hold(input.h_c, input.h, params, input.Ts); + output.rotate_trans = output.rotate_value;//pseudo_course_hold(input.chi, input.chi_c, params, input.Ts); + + //output.left_right_trans = 0.1 * pseudo_left_right(input.chi, input.chi_c, output.forward_trans); + //output.up_down_trans = 0.01 * pseudo_pitch_hold(input.h_c, input.h, params, input.Ts); + //output.rotate_trans = 0.3*pseudo_course_hold(input.chi, input.chi_c, params, input.Ts); + ////if (input.h >= input.h_c - params.alt_hz) //alt_hz=0.2//recovery + if (input.h >= input.h_c - 0.3) //alt_hz=0.2 + { + ROS_DEBUG("hold"); + current_zone = alt_zones::ALTITUDE_HOLD; + at_error_ = 0; + at_integrator_ = 0; + at_differentiator_ = 0; + a_error_ = 0; + a_integrator_ = 0; + a_differentiator_ = 0; + } + //else if (input.h <= params.alt_toz) //1.5//recovery + // else if (input.h <= 1) //1.5 + // { + // ROS_DEBUG("takeoff"); + // current_zone = alt_zones::TAKE_OFF; // Is that necessary? + // } + break; + case alt_zones::DESCEND: + output.forward_trans = input.Va_c;//sat(input.Va_c*cos(output.rotate_trans),5,0.5);//pseudo_throttle_hold(input.Va_c, input.va, params, input.Ts); + output.left_right_trans = 0;//sat(input.Va_c*sin(output.rotate_trans),5,-5);//pseudo_left_right(input.chi, input.chi_c, output.forward_trans); + output.rotate_trans = output.rotate_value;//pseudo_course_hold(input.chi, input.chi_c, params, input.Ts); + output.up_down_trans = pseudo_pitch_hold(input.h_c, input.h, params, input.Ts); + + //output.forward_trans = 0.1 * pseudo_throttle_hold(input.Va_c, input.va, params, input.Ts); + //output.left_right_trans = 0.1 * pseudo_left_right(input.chi, input.chi_c, output.forward_trans); + //output.rotate_trans = pseudo_course_hold(input.chi, input.chi_c, params, input.Ts); + //output.up_down_trans = 0.1 * pseudo_pitch_hold(input.h_c, input.h, params, input.Ts); + //if (input.h <= input.h_c + params.alt_hz)//recovery + if (input.h <= input.h_c + 0.3) + { + if (input.h < 0) //modify later + { + ROS_DEBUG("landing"); + current_zone = alt_zones::LANDING; + // output.forward_trans = sat(input.Va_c*cos(output.rotate_trans),1,0);//pseudo_throttle_hold(input.Va_c, input.va, params, input.Ts) * 0.5; + // output.up_down_trans = pseudo_pitch_hold(input.h_c, input.h, params, input.Ts) / 2; + // output.rotate_trans = output.rotate_value;//pseudo_course_hold(input.chi, input.chi_c, params, input.Ts); + } + else + { + ROS_DEBUG("hold"); + current_zone = alt_zones::ALTITUDE_HOLD; + at_error_ = 0; + at_integrator_ = 0; + at_differentiator_ = 0; + a_error_ = 0; + a_integrator_ = 0; + a_differentiator_ = 0; + } + } + break; + case alt_zones::ALTITUDE_HOLD: + output.forward_trans = input.Va_c;//sat(input.Va_c*cos(output.rotate_trans),5,0.5);//pseudo_throttle_hold(input.Va_c, input.va, params, input.Ts); + output.left_right_trans = 0;//sat(input.Va_c*sin(output.rotate_trans),5,-5);//0.5*pseudo_left_right(input.chi, input.chi_c, output.forward_trans); + output.up_down_trans = pseudo_altitiude_hold(input.h_c, input.h, params, input.Ts); + output.rotate_trans = output.rotate_value;//pseudo_course_hold(input.chi, input.chi_c, params, input.Ts); + //output.forward_trans = 1;//0.1 * pseudo_throttle_hold(input.Va_c, input.va, params, input.Ts); + //output.left_right_trans = pseudo_left_right(input.chi, input.chi_c, output.forward_trans); + //output.up_down_trans = 0.1 * pseudo_altitiude_hold(input.h_c, input.h, params, input.Ts); + //output.rotate_trans = 0.7*pseudo_course_hold(input.chi, input.chi_c, params, input.Ts); + //if (input.h >= input.h_c + params.alt_hz)//recovery + if (input.h >= input.h_c + 0.3) + { + ROS_DEBUG("desend"); + current_zone = alt_zones::DESCEND; + ap_error_ = 0; + ap_integrator_ = 0; + ap_differentiator_ = 0; + } + //else if (input.h <= input.h_c - params.alt_hz)//recovery + else if (input.h <= input.h_c - 0.3) + { + ROS_DEBUG("climb"); + current_zone = alt_zones::CLIMB; + ap_error_ = 0; + ap_integrator_ = 0; + ap_differentiator_ = 0; + } + break; + case alt_zones::LANDING: + ROS_DEBUG("landing"); + current_zone = alt_zones::LANDING; + ap_error_ = 0; + ap_integrator_ = 0; + ap_differentiator_ = 0; + output.forward_trans = 0; + if (input.h < 0.6) + { + output.up_down_trans = 0; + } + else + { + output.up_down_trans = -input.h/3; + } + + output.rotate_trans =0; + output.left_right_trans = 0; + break; + default: + break; + } + + output.current_zone = current_zone; + //output.delta_e = pitch_hold(output.theta_c, input.theta, input.q, params, input.Ts); + //output.up_down_trans=pseudo_pitch_hold(output.theta_c, input.theta, input.q, params, input.Ts); +} + +float pseudo_controller_example::pseudo_course(float chi, float chi_c) +{ + chi_c=sat(chi_c,3.14159,-3.14159); + chi=sat(chi,3.14159,-3.14159); + float rotate = sat(chi_c-chi,2*3.14159,-2*3.14159);//-pi to pi + // float lr; + // if (rotate>3.14159) + // { + // lr=-1; + // } + // else if(rotate<-3.14159) + // { + // lr=1; + // } + //rotate=rotate+lr*2*3.14159;//more easier to rotate + + // rotate=sat(rotate,3.14159/4,-3.14159/4);//limit + return rotate; +} + +float pseudo_controller_example::pseudo_left_right(float chi, float chi_c, float forward_trans) +{ + float error= chi_c-chi; + float a = fabs(forward_trans); + float x = (3.14 / 4 > fabs(error)) ? fabs(error) : 3.14 / 4; + float b = tan(x); + float c = error / (fabs(error + 0.001)); + float left_right_trans = sat(a * b * c, forward_trans, -forward_trans); + + return left_right_trans; +} + +float pseudo_controller_example::pseudo_course_hold(float chi, float chi_c, const params_s ¶ms, float Ts) +{ + float error = chi_c-chi; + + //c_integrator_ = c_integrator_ + (Ts / 2.0) * (error + c_error_); + + //float up = params.c_kp * error; + //float ui = params.c_ki * c_integrator_; + + float rotate_trans = sat((error + c_error_) / 2, 45.0 * 3.14 / 180.0, -45.0 * 3.14 / 180.0); + //if (fabs(params.c_ki) >= 0.00001) + //{ + //float rotate_trans_unsat = up + ui; + //c_integrator_ = c_integrator_ + (Ts / params.c_ki) * (rotate_trans - rotate_trans_unsat); + //} + + c_error_ = error; + return rotate_trans; +} + +float pseudo_controller_example::pseudo_pitch_hold(float h_c, float h, const struct params_s ¶ms, float Ts) +{ + float error = h_c - h; + //ap_integrator_ = ap_integrator_ + (Ts / 2.0) * (error + ap_error_); + // float up = 0.5 * error; + //float ui = params.a_p_ki * ap_integrator_; + //float up_down_trans = sat(up + ui, 0.8, -0.8);//recovery + float up_down_trans = sat(0.5 * error, 2, -2); + //if (fabs(params.a_p_ki) >= 0.00001) + //{ + //float up_down_trans_unsat = up + ui; + //ap_integrator_ = ap_integrator_ + (Ts / params.a_p_ki) * (up_down_trans - up_down_trans_unsat); + //} + // ap_error_ = error; + return up_down_trans; +} + +float pseudo_controller_example::pseudo_throttle_hold(float Va_c, float Va, const params_s ¶ms, float Ts) +{ + float error = Va_c - Va; + + //at_integrator_ = at_integrator_ + (Ts / 2.0) * (error + at_error_); + //at_differentiator_ = (2.0 * params.tau - Ts) / (2.0 * params.tau + Ts) * at_differentiator_ + (2.0 /(2.0 * params.tau + Ts)) *(error - at_error_); + + float up = params.a_t_kp * error; + //float ui = params.a_t_ki * at_integrator_; + //float ud = params.a_t_kd * at_differentiator_; + + //float forward_trans = sat(Va + up + ui + ud, params.max_t, 0.1); + float forward_trans = sat(Va+error, params.max_t, 0.5); + //if (fabs(params.a_t_ki) >= 0.00001) + //{ + //float forward_trans_unsat = params.trim_t + up + ui + ud; + //at_integrator_ = at_integrator_ + (Ts / params.a_t_ki) * (forward_trans - forward_trans_unsat); + //} + + //at_error_ = error; + return forward_trans; +} + +float pseudo_controller_example::pseudo_altitiude_hold(float h_c, float h, const params_s ¶ms, float Ts) +{ + float error = h_c - h; + + //a_integrator_ = a_integrator_ + (Ts / 2.0) * (error + a_error_); + //a_differentiator_ = (2.0 * params.tau - Ts) / (2.0 * params.tau + Ts) * a_differentiator_ + (2.0 /(2.0 * params.tau + Ts)) * (error - a_error_); + float up = 0.7 * error; + //float up = params.a_kp * error; + //ROS_INFO("hello %f",params.a_kp); + //float ui = params.a_ki * a_integrator_; + //float ud = params.a_kd * a_differentiator_; + + //float up_down_trans = sat(up + ui + ud, 0.8, -0.8);//recovery + float up_down_trans = sat(up, 2, -2); + //if (fabs(params.a_ki) >= 0.00001) + //{ + //float up_down_trans_unsat = up + ui + ud; + //a_integrator_ = a_integrator_ + (Ts / params.a_ki) * (up_down_trans - up_down_trans_unsat); + //} + + // at_error_ = error; + return up_down_trans; +} + +//float pseudo_controller_example::cooridinated_turn_hold(float v, const params_s ¶ms, float Ts) +//{ +// //todo finish this if you want... +// return 0; +//} + +float pseudo_controller_example::sat(float value, float up_limit, float low_limit) +{ + float rVal; + if (value > up_limit) + rVal = up_limit; + else if (value < low_limit) + rVal = low_limit; + else + rVal = value; + + return rVal; +} + +} // namespace hector diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/simple_takeoff.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/simple_takeoff.cpp new file mode 100644 index 0000000..f3b22c4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/simple_takeoff.cpp @@ -0,0 +1,29 @@ +#include +#include + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "hector_simple_takeoff"); + + ros::NodeHandle nh_; + ros::Publisher velPublisher = nh_.advertise("/cmd_vel", 10); + + geometry_msgs::Twist cmd_vel; + + cmd_vel.linear.x = 0; + cmd_vel.linear.y = 0; + cmd_vel.linear.z = 0.5; + cmd_vel.angular.x = 0; + cmd_vel.angular.y = 0; + cmd_vel.angular.z = 0; + + while (ros::ok()) + { + velPublisher.publish(cmd_vel); + ros::Duration(0.01).sleep(); + } + + ros::spin(); + + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/udp_recv_image.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/udp_recv_image.cpp new file mode 100644 index 0000000..b408055 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/udp_recv_image.cpp @@ -0,0 +1,254 @@ +/************************************************************************ + * * + * Author: ake * + * Date: 2018-10-23 * + * Description: recv image of the camera to server with udp * + * * + *************************************************************************/ +#include "udp_recv_image.h" + +namespace hector +{ + +udp_recv_image::udp_recv_image():nh_(ros::NodeHandle()),it(nh_) +{ + image_pub = it.advertise("udp_image",1); + + memset(&my_addr, 0, sizeof(my_addr)); + my_addr.sin_family = AF_INET; + my_addr.sin_addr.s_addr = INADDR_ANY; + + my_addr.sin_port = htons(8888); + sin_size = sizeof(struct sockaddr_in); + + if((server_sockfd = socket(PF_INET, SOCK_DGRAM, 0)) < 0) + { + perror("socket error"); + return; + } + + if(bind(server_sockfd, (struct sockaddr *)&my_addr, sizeof(struct sockaddr)) < 0) + { + perror("bind error"); + return; + } + struct timeval tv_out; + tv_out.tv_sec = 3; + tv_out.tv_usec = 0; + setsockopt(server_sockfd, SOL_SOCKET, SO_RCVTIMEO, &tv_out,sizeof(tv_out)); + int sockbufsize = 1024*1024*10; + setsockopt(server_sockfd, SOL_SOCKET, SO_RCVBUF, &sockbufsize, sizeof(sockbufsize)); + +} + +udp_recv_image::~udp_recv_image() +{ + +} + +void udp_recv_image::udp_close() +{ + close(server_sockfd); +} + +void udp_recv_image::recv_image() +{ + sensor_msgs::ImagePtr msg; + struct RecvStatus recvS; + timespec t1,t2; + int nCount = 0; + bool bFlag = false; + char bufS[20]; + // int num = 1; + int count = 0; + unsigned int size = 0; + char tmpBuf[1024*1024]; + cv::Mat image_recv; + std::vector buf; + std::vector params; + std::string comprType = ".jpg"; + int quality = 100; + int compr = cv::IMWRITE_JPEG_QUALITY; + params.push_back(compr); + params.push_back(quality); + clock_gettime(CLOCK_MONOTONIC, &t1); + while(ros::ok()) + { + // std::cout<<"-----------------------------------------pos 1------------------------------------------\n"; + memset(frameBuffer,0,BUF_SIZE); + int len = recvfrom(server_sockfd, frameBuffer, sizeof(PackageHeader)+UDP_MAX_SIZE, 0, (struct sockaddr *)&remote_addr, &sin_size); + // std::cout<<"-----------------------------------------pos 2------------------------------------------\n"; + // std::cout<<"len = "< 0) + { + // std::cout<<"-----------------------------------------pos 3------------------------------------------\n"; + bFlag = true; + packageHead = (PackageHeader*)frameBuffer; + if(packageHead->uDataPackageCurrIndex == 1) + { + count = 0; + size = 0; + bzero(tmpBuf, packageHead->uDataSize); + + } + count++; + size += packageHead->uTransPackageSize-packageHead->uTransPackageHdrSize; + // std::cout<<"1111111111111111111111111111111111111111111111111111\n"; + memcpy(tmpBuf+packageHead->uDataPackageOffset, frameBuffer + packageHead->uTransPackageHdrSize,packageHead->uTransPackageSize-packageHead->uTransPackageHdrSize); + // std::cout<<"2222222222222222222222222222222222222222222222222222\n"; + if(count == packageHead->uDataPackageNum) + { + if(size == packageHead->uDataSize) + { + buf.resize(packageHead->uDataSize); + buf.assign(tmpBuf, tmpBuf+packageHead->uDataSize); + cv::imdecode(cv::Mat(buf), cv::IMREAD_COLOR, &image_recv); + msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image_recv).toImageMsg(); + image_pub.publish(msg); + nCount++; + // usleep(50); + // cv::imshow("test subscribe", cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8)->image); + // cv::waitKey(30); + clock_gettime(CLOCK_MONOTONIC, &t2); + std::cout<<"time: "<uDataPackageCurrIndex; + recvS.flag = -1; + bzero(bufS, 20); + memcpy(bufS, (char*)&recvS,sizeof(recvS)); + sendto(server_sockfd,bufS, sizeof(recvS), 0, (struct sockaddr *)&remote_addr, sin_size); + } + + } +// if(len > 0) +// { +// // memcpy(&packageHead, frameBuffer, sizeof(struct PackageHeader)); +// packageHead = (PackageHeader*)frameBuffer; +// // int *flag = new int[packageHead->uDataPackageNum]; +// // for(int j = 0; j < packageHead->uDataPackageNum; j++) +// // { +// // flag[j] = 0; +// // } +// // std::cout<<"-------------1 start-----------------------\n"; +// // std::cout<<"packageHead.uDataPackageCurrIndex = "<uDataPackageCurrIndex<uDataPackageCurrIndex == num) +// { +// // std::cout<<"-------------2 start-----------------------\n"; +// // std::cout<<"packageHead.uDataPackageCurrIndex = "<uDataPackageCurrIndex<channels) +// // { +// // case 1: +// // image_recv = cv::Mat(packageHead->rows,packageHead->cols,CV_8UC1); +// // break; +// // case 2: +// // image_recv = cv::Mat(packageHead->rows, packageHead->cols,CV_8UC2); +// // break; +// // case 3: +// // image_recv = cv::Mat(packageHead->rows, packageHead->cols,CV_8UC3); +// // break; +// // case 4: +// // image_recv = cv::Mat(packageHead->rows, packageHead->cols,CV_8UC4); +// // break; +// // } +// while(num <= packageHead->uDataPackageNum) +// { +// if(num == packageHead->uDataPackageCurrIndex) +// { +// size += packageHead->uTransPackageSize-packageHead->uTransPackageHdrSize; +// if(size > packageHead->uDataSize) +// { +// perror("error image data, too big."); +// size = 0; +// num = 1; +// break; +// } +// if(packageHead->uDataPackageOffset > packageHead->uDataSize) +// { +// perror("error image data, format error."); +// size = 0; +// num = 1; +// break; +// } +// // std::cout<<"size = "<uDataSize<uDataPackageNum="<uDataPackageNum<<"\tpackageHead->uDataPackageCurrIndex="<uDataPackageCurrIndex<uDataPackageNum == packageHead->uDataPackageCurrIndex)) +// { +// // std::cout<<"packageHead.uDataPackageNum= "<uDataPackageNum<uDataSize)) +// { +// msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image_recv).toImageMsg(); +// image_pub.publish(msg); +// usleep(50); +// cv::imshow("test subscribe", cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8)->image); +// cv::waitKey(30); +// } +// num = 1; +// size = 0; +// break; + +// } +// num++; + +// } + +// memset(frameBuffer,0,BUFSIZE); + +// len = recvfrom(server_sockfd, frameBuffer, sizeof(PackageHeader)+UDP_MAX_SIZE, 0, (struct sockaddr *)&remote_addr, &sin_size); +// if(len < 0 ) +// { + +// recvS.index = num; +// recvS.flag = -1; +// sendto(server_sockfd,(char*)&recvS, sizeof(recvS), 0, (struct sockaddr *)&remote_addr, sin_size); +// num = 1; +// size = 0; +// break; +// } + +// } +// num = 1; +// size = 0; +// } +// } + } +} + +} + +int main(int argc, char **argv) +{ + ros::init(argc,argv,"udp_recv_image"); + hector::udp_recv_image image_recv; + + image_recv.recv_image(); + + image_recv.udp_close(); + return 0; +} \ No newline at end of file diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/udp_send_image.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/udp_send_image.cpp new file mode 100644 index 0000000..ae36bb3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector/src/udp_send_image.cpp @@ -0,0 +1,323 @@ +/************************************************************************ + * * + * Author: ake * + * Date: 2018-10-23 * + * Description: send image of the camera to server with udp * + * * + ************************************************************************/ +#include "udp_send_image.h" + +namespace hector +{ + +udp_send_image::udp_send_image(): + nh_(ros::NodeHandle()), + it(nh_) +{ + std::string server_ip, sub_topic; + int server_port; + ros::param::get("~server_ip",server_ip); + ros::param::get("~server_port",server_port); + ros::param::get("~sub_topic",sub_topic); + std::cout<<"server_ip: "<image); +// cv::imshow("test subscribe", cv_bridge::toCvCopy(tem_msg, sensor_msgs::image_encodings::BGR8)->image); +// cv::waitKey(30); +// } +// catch(cv_bridge::Exception& e) +// { +// ROS_ERROR("Could not convert from '%s' to 'BGR8'", tem_msg->encoding.c_str()); +// } + struct RecvStatus recvS; + unsigned int dstLength; + int currentPacketIndex = 0; + int nLength = 0; + int dataLength = 0; + int packetNum = 0; + int lastPaketSize = 0; + cv::Mat img_send = cv_bridge::toCvCopy(tem_msg, sensor_msgs::image_encodings::BGR8)->image; + //compress the img + std::vector buf; + std::vector params; + std::string comprType = ".jpg"; + int quality = 100; + int compr = cv::IMWRITE_JPEG_QUALITY; + params.push_back(compr); + params.push_back(quality); + cv::imencode(comprType.c_str(), img_send,buf,params); + // std::cout<<"buf.size() = "< +#include +#include +#include + +//串å£ç›¸å…³çš„头文件 +#include /*标准输入输出定义*/ +#include /*标准函数库定义*/ +#include /*Unix 标准函数定义*/ +#include +#include +#include /*文件控制定义*/ +#include /*PPSIX 终端控制定义*/ +#include /*错误å·å®šä¹‰*/ +#include +#include +#include + +//å®å®šä¹‰ +#define FALSE -1 +#define TRUE 0 +#define TAIL 0xFFFA55AF +#define REC_BUFFER_SIZE 200 +#define DOWN_CHECK_LEN 24 +#define UP_CHECK_LEN 68 + +//#define BUFSIZ 200 + +// typedef struct +// { +// double plane_info_double[6]; //存放ç»åº¦ã€çº¬åº¦ã€é«˜åº¦ã€æ»šè½¬è§’ã€ä¿¯ä»°è§’ã€å航角 +// int plane_info_int; //å­˜æ”¾æ— äººæœºç¼–å· +// float plane_info_float[9]; //航迹速度(目å‰æ²¡æœ‰ç”¨ï¼‰ +// unsigned char sum_check[4]; //累加校验ç ï¼ˆç›®å‰æ²¡æœ‰ç”¨ï¼‰ +// unsigned char header[4]; //(目å‰æ²¡æœ‰ç”¨ï¼‰ +// } Scom_up_protocal; + +typedef struct +{ + double plane_info_double[2]; //存放无人机ç»åº¦ã€çº¬åº¦ã€é«˜åº¦ã€æ»šè½¬è§’ã€ä¿¯ä»°è§’ã€å航角 + double camera_info_double[2]; //存放相机ç»åº¦ã€çº¬åº¦ + float plane_info_float[7]; //存放无人机高度ã€æ»šè½¬è§’ã€ä¿¯ä»°è§’ã€å航角ã€åŒ—东地三方å‘速度 + float camera_info_float[4]; //存放相机高度ã€æ»šè½¬è§’ã€ä¿¯ä»°è§’ã€å航角 + unsigned int ID; //å­˜æ”¾æ— äººæœºç¼–å· + char name[20]; +} Scom_up_protocal; + +// struct scom_protocal +// { +// int plane_info_int[3]; //存放ç»åº¦ã€çº¬åº¦ã€é«˜åº¦ +// float plane_info_float; //航迹速度 +// }; + +namespace hector +{ + +using std::string; + +/** @brief async write buffer */ +class Udp_commu_send +{ + public: + Udp_commu_send() + { + std::string client_ip; + int client_port = 0; + ros::param::get("~client_ip", client_ip); + ros::param::get("~client_port", client_port); + if(client_ip.empty()) + { + client_ip = "192.168.1.15"; + } + if(client_port == 0) + { + client_port = 8000; + } + ROS_ERROR("port is: %d\n", client_port); + memset(&remote_addr, 0, sizeof(remote_addr)); //æ•°æ®åˆå§‹åŒ–--清零 + remote_addr.sin_family = AF_INET; //设置为IP通信 + remote_addr.sin_addr.s_addr = inet_addr(client_ip.c_str()); //æœåŠ¡å™¨IP地å€"172.18.0.3" + remote_addr.sin_port = htons(client_port); //æœåŠ¡å™¨ç«¯å£å· + // remote_addr.sin_port = htons(8000); + + /*创建客户端套接字--IPv4å议,é¢å‘无连接通信,UDPåè®®*/ + if ((client_sockfd = socket(PF_INET, SOCK_DGRAM, 0)) < 0) + { + perror("socket error"); + } + sin_size = sizeof(struct sockaddr_in); + + task_send_data = (Scom_up_protocal *)malloc(sizeof(Scom_up_protocal)); + // sub = n.subscribe("/fixedwing_0/udp_send_state", 1, &Udp_commu_send::upsendCallback, this); + sub = n.subscribe("udp_send_state", 10, &Udp_commu_send::upsendCallback, this); + //write_thread_ = new boost::thread(boost::bind(&Serial_commu_send::write_handle, this)); + //write_thread_ -> detach(); + }; + ~Udp_commu_send() + { + free(task_send_data); + delete write_thread_; + }; + + void write_handle() + { + unsigned char temp = num; + sleep(0.1); + if ((num == temp) && flag == 1) + tcflush(fd, TCOFLUSH); + }; + + void upsendCallback(const rosplane_msgs::Udp_Send_State::ConstPtr &msg) + { + // printf("*************************The data to send is:\n"); + // ROS_INFO("I heard: msg.status_word is: %d\n", msg->status_word); + // ROS_INFO("I heard: msg.longitude is %f\n", msg->longitude); + // ROS_INFO("I heard: msg.latitude is %f\n", msg->latitude); + // ROS_INFO("I heard: msg.altitude is: %f\n", msg->altitude); + // ROS_INFO("I heard: msg.roll_angle is: %f\n", msg->roll_angle); + double i = 50; + + //***************串å£å‘é€æ•°æ® ************* + // unsigned char scom_protocal::serial_num_increase = 0; + + // task_send_data->plane_info_int[0] = msg->longitude * (int)(pow(10, 7)); + // task_send_data->plane_info_int[1] = msg->latitude * (int)(pow(10, 7)); + // task_send_data->plane_info_int[2] = msg->altitude * (int)(pow(10, 2)); + + // task_send_data->plane_info_int = msg->status_word; + // task_send_data->plane_info_int = 0; + + // task_send_data->plane_info_double[0] = msg->longitude; + // task_send_data->plane_info_double[1] = msg->latitude; + // task_send_data->plane_info_double[2] = msg->altitude; + // task_send_data->plane_info_double[3] = msg->roll_angle; + // task_send_data->plane_info_double[4] = msg->pitch_angle; + // task_send_data->plane_info_double[5] = msg->yaw_angle; + // task_send_data->plane_info_float[0] = msg->angular_rate_x; + // task_send_data->plane_info_float[1] = msg->angular_rate_y; + // task_send_data->plane_info_float[2] = msg->angular_rate_z; + // task_send_data->plane_info_float[3] = msg->north_direction_speed; + // task_send_data->plane_info_float[4] = msg->east_direction_speed; + // task_send_data->plane_info_float[5] = msg->ground_direction_speed; + // task_send_data->plane_info_float[6] = msg->acceleration_x; + // task_send_data->plane_info_float[7] = msg->acceleration_y; + // task_send_data->plane_info_float[8] = msg->acceleration_z; + + task_send_data->ID = 0; + task_send_data->plane_info_double[0] = msg->longitude; + task_send_data->plane_info_double[1] = msg->latitude; + task_send_data->plane_info_float[0] = msg->altitude; + task_send_data->plane_info_float[1] = msg->roll_angle * 180.0 / M_PI; + task_send_data->plane_info_float[2] = msg->pitch_angle * 180.0 / M_PI; + task_send_data->plane_info_float[3] = msg->yaw_angle * 180.0 / M_PI; + task_send_data->plane_info_float[4] = msg->north_direction_speed; + task_send_data->plane_info_float[5] = msg->east_direction_speed; + task_send_data->plane_info_float[6] = msg->ground_direction_speed; + task_send_data->camera_info_double[0] = msg->longitude_camera; + task_send_data->camera_info_double[1] = msg->latitude_camera; + task_send_data->camera_info_float[0] = msg->altitude_camera; + task_send_data->camera_info_float[1] = msg->roll_angle_camera * 180.0 / M_PI; + task_send_data->camera_info_float[2] = msg->pitch_angle_camera * 180.0 / M_PI; + task_send_data->camera_info_float[3] = msg->yaw_angle_camera * 180.0 / M_PI; + // task_send_data->name = msg->name; + // strcpy(task_send_data->name, msg->name); + // strcpy(task_send_data->name, "fixedwing_0"); + // å‘char[20]赋值 + int j; + for (j = 0; j < msg->name.length(); j++) + { + task_send_data->name[j] = msg->name[j]; + } + task_send_data->name[j] = '\0'; + // printf("%s\n", p); + // cout << p; + + // printf("UDP_send..........................................................\n"); + /*å‘æœåŠ¡å™¨å‘é€æ•°æ®åŒ…*/ + int len = sendto(client_sockfd, (char *)(&task_send_data->plane_info_double[0]), sizeof(Scom_up_protocal), 0, (struct sockaddr *)&remote_addr, sizeof(struct sockaddr)); + sleep(0.001); + + // int len = UART0_Send((char *)(&task_send_data->header[0]), sizeof(scom_protocal)); + // printf("UDP_send over..........................................................\n"); + + // if (len > 0) + // printf(" %f ms time send %d byte data send successfully\n", i, len); + // else + // printf("send data failed!\n"); + }; + + int get_fd() + { + return fd; + }; + void udp_Close() + { + close(client_sockfd); + } + + private: + Scom_up_protocal *task_send_data; + int fd; + unsigned char num; + int flag; + + boost::thread *write_thread_; + + ros::NodeHandle n; + ros::Subscriber sub; + + int client_sockfd; + + struct sockaddr_in remote_addr; //æœåŠ¡å™¨ç«¯ç½‘络地å€ç»“构体 + int sin_size; + char buf[BUFSIZ]; //æ•°æ®ä¼ é€çš„缓冲区 +}; + +} // namespace hector + +int main(int argc, char **argv) +{ + + ros::init(argc, argv, "udp_send_0"); + + // int err; + + hector::Udp_commu_send send; + + ros::spin(); + /*关闭套接字*/ + send.udp_Close(); + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/CMakeLists.txt new file mode 100644 index 0000000..df968db --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/CMakeLists.txt @@ -0,0 +1,30 @@ +cmake_minimum_required(VERSION 2.8.3) +project(hector_msgs) + +find_package(catkin REQUIRED COMPONENTS + std_msgs + message_generation +) + +add_message_files( + FILES + Controller_Commands.msg + Current_Path.msg + Goal_Info.msg + Controller_Internals.msg + State.msg + State29.msg + Up_Data_New.msg + Down_Data_New.msg + Formation_Type.msg + Waypoint.msg +) + +generate_messages( + DEPENDENCIES + std_msgs +) + +catkin_package( + CATKIN_DEPENDS std_msgs +) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Controller_Commands.msg b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Controller_Commands.msg new file mode 100644 index 0000000..2dbe3d8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Controller_Commands.msg @@ -0,0 +1,11 @@ +# Controller commands output from the path follower, input to autopilot controller + +# @warning Va_c, h_c and chi_c have always to be valid, the aux array is optional +float32 Va_c # Commanded airspeed (m/s) +float32 h_c # Commanded altitude (m) +float32 chi_c # Commanded course (rad) +float32 phi_ff # feed forward command for orbits (rad) +float32[4] aux # Optional auxiliary commands +bool aux_valid # Auxiliary commands valid +bool takeoff +bool landing diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Controller_Internals.msg b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Controller_Internals.msg new file mode 100644 index 0000000..620facd --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Controller_Internals.msg @@ -0,0 +1,13 @@ +# Controller internals (inner loops, states) output from the autopilot controller, for now just for debuging and ploting + +# @warning theta_c, phi_c and alt_zone have always to be valid, the aux array is optional +float32 theta_c # Commanded pitch (rad) +float32 phi_c # Commanded roll (rad) +uint8 alt_zone # Zone in the altitude state machine +float32[4] aux # Optional auxiliary commands +bool aux_valid # Auxiliary commands valid + +uint8 ZONE_TAKE_OFF = 0 +uint8 ZONE_CLIMB = 1 +uint8 ZONE_DESEND = 2 +uint8 ZONE_ALTITUDE_HOLD = 3 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Current_Path.msg b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Current_Path.msg new file mode 100644 index 0000000..612d862 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Current_Path.msg @@ -0,0 +1,23 @@ +# Current path output from the path manager, input to path follower + +# @warning Va_d have always to be valid, +# r and q need to be valid if path_type == LINE_PATH +# c, rho, and, lambda need to be valid if path_type == ORBIT_PATH +uint8 path_type # Indicates strait line or orbital path +float32 Va_d # Desired airspeed (m/s) +float32[3] r # Vector to origin of straight line path (m) +float32[3] q # Unit vector, desired direction of travel for line path +float32[3] c # Center of orbital path (m) +float32 rho # Radius of orbital path (m) +float32 h_c # desire altitude (m) add by kobe +int8 lambda # Direction of orbital path (clockwise is 1, counterclockwise is -1) + +uint8 ORBIT_PATH = 0 +uint8 LINE_PATH = 1 +uint8 STAR_PATH = 2 #add by kobe + +int8 CLOCKWISE = 1 +int8 COUNT_CLOCKWISE = -1 + +bool landing +bool takeoff diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Down_Data_New.msg b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Down_Data_New.msg new file mode 100644 index 0000000..693434f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Down_Data_New.msg @@ -0,0 +1,5 @@ +int32 status_word +float32 longitude +float32 latitude +float32 altitude +float32 plane_speed #desired speed diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Formation_Type.msg b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Formation_Type.msg new file mode 100644 index 0000000..f82ebe0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Formation_Type.msg @@ -0,0 +1,7 @@ +# Vehicle state 'x_hat' output from the estimator or from simulator + +Header header + +# Original States +# @warning roll, pitch and yaw have always to be valid, the quaternion is optional +float32 formation_type # Airspeed (m/s) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Goal_Info.msg b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Goal_Info.msg new file mode 100644 index 0000000..778325b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Goal_Info.msg @@ -0,0 +1,8 @@ +# Current path goal output from the path manager, add by kobe + +float32 v_d # Desired airspeed (m/s) +float32[2] xy # x-y-coordinate (m) +float32[2] ll # latitude-longtitude +int32 action # expected action move +float32 altitude # desire altitude (m) + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/State.msg b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/State.msg new file mode 100644 index 0000000..1a035a2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/State.msg @@ -0,0 +1,37 @@ +# Vehicle state 'x_hat' output from the estimator or from simulator + +Header header + +# Original States +# @warning roll, pitch and yaw have always to be valid, the quaternion is optional +float32[3] position # north, east, down (m) +float32 Va # Airspeed (m/s) +float32 alpha # Angle of attack (rad) +float32 beta # Slide slip angle (rad) +float32 phi # Roll angle (rad) +float32 theta # Pitch angle (rad) +float32 psi # Yaw angle (rad) +float32 chi # Course angle (rad) +float32 p # Body frame rollrate (rad/s) +float32 q # Body frame pitchrate (rad/s) +float32 r # Body frame yawrate (rad/s) +float32 Vg # Groundspeed (m/s) +float32 wn # Windspeed north component (m/s) +float32 we # Windspeed east component (m/s) + +# add by kobe +float32 Wd # latitude -90--90 +float32 Jd # longtitude -180--180 +float32 Vn # v-north speed or x +float32 Ve # v-east or y +float32 Vd # v-down or z + + +# Additional States for convenience +float32[4] quat # Quaternion (wxyz, NED) +bool quat_valid # Quaternion valid +float32 chi_deg # Wrapped course angle (deg) +float32 psi_deg # Wrapped yaw angle (deg) +float32 initial_lat # Initial/origin latitude (lat. deg) +float32 initial_lon # Initial/origin longitude (lon. deg) +float32 initial_alt # Initial/origin altitude (m) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/State29.msg b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/State29.msg new file mode 100644 index 0000000..d446ad4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/State29.msg @@ -0,0 +1,13 @@ +# Vehicle state 'x_hat' output from the estimator or from simulator + +Header header + +# Original States +# @warning roll, pitch and yaw have always to be valid, the quaternion is optional +float32[3] position_gps # latitude (lat. deg), longitude (lon. deg), altitude (m) +float32[3] attitude_angle # Roll angle (rad), Pitch angle (rad), Yaw angle (rad) +float32[3] velocity # V_north (m/s), V_east (m/s), V_ground (m/s) +float32[3] angular_velocity # Body frame rollrate (rad/s), Body frame pitchrate (rad/s), Body frame yawrate (rad/s) +float32[3] acceleration # Body frame x (m/s^2), Body frame y (m/s^2), Body frame z (m/s^2) +float32 electric_quantity # Quantity of electric charge +int8 state_word # Control Status Word diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Up_Data_New.msg b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Up_Data_New.msg new file mode 100644 index 0000000..a0d4e49 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Up_Data_New.msg @@ -0,0 +1,16 @@ +int32 status_word +float32 longitude +float32 latitude +float32 altitude # (m) +float32 roll_angle #(rad) +float32 pitch_angle +float32 yaw_angle +float32 angular_rate_x #Body frame rollrate (rad/s) +float32 angular_rate_y #Body frame pitchrate (rad/s) +float32 angular_rate_z #Body frame yawrate (rad/s) +float32 north_direction_speed #(m/s) +float32 east_direction_speed +float32 ground_direction_speed +float32 acceleration_x #(m/s^2) +float32 acceleration_y +float32 acceleration_z diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Waypoint (å¤ä»¶).msg b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Waypoint (å¤ä»¶).msg new file mode 100644 index 0000000..531183a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Waypoint (å¤ä»¶).msg @@ -0,0 +1,15 @@ +# New waypoint, input to path manager + +# @warning w and Va_d always have to be valid; the chi_d is optional. +float32[3] w # Waypoint in local NED (m) + +# add by kobe +float32 lat # latitude +float32 lon # longtitude + +float32 chi_d # Desired course at this waypoint (rad) +bool chi_valid # Desired course valid (dubin or fillet paths) +float32 Va_d # Desired airspeed (m/s) +bool set_current # Sets this waypoint to be executed now! Starts a new list +bool clear_wp_list # Removes all waypoints and returns to origin. The rest of + # this message will be ignored diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Waypoint.msg b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Waypoint.msg new file mode 100644 index 0000000..839277d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/msg/Waypoint.msg @@ -0,0 +1,17 @@ +# New waypoint, input to path manager + +# @warning w and Va_d always have to be valid; the chi_d is optional. +float32[3] w # Waypoint in local NED (m) + +# add by kobe +float32 lat # latitude +float32 lon # longtitude + +float32 chi_d # Desired course at this waypoint (rad) +bool chi_valid # Desired course valid (dubin or fillet paths) +float32 Va_d # Desired airspeed (m/s) +bool set_current # Sets this waypoint to be executed now! Starts a new list +bool clear_wp_list # Removes all waypoints and returns to origin. The rest of + # this message will be ignored +bool landing +bool takeoff diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/package.xml new file mode 100644 index 0000000..a66fa12 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/Guide_on_rosplane/hector_msgs/package.xml @@ -0,0 +1,25 @@ + + + hector_msgs + 0.0.0 + Message definitions for the hector package + + Gary Ellingson + + Gary Ellingson + + BSD + + catkin + + message_generation + std_msgs + geometry_msgs + std_msgs + geometry_msgs + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor.rosinstall b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor.rosinstall new file mode 100644 index 0000000..93239bd --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor.rosinstall @@ -0,0 +1,4 @@ +- git: {local-name: hector_quadrotor, uri: 'https://github.com/tu-darmstadt-ros-pkg/hector_quadrotor.git', version: indigo-devel} +- git: {local-name: hector_localization, uri: 'https://github.com/tu-darmstadt-ros-pkg/hector_localization.git', version: catkin} +- git: {local-name: hector_gazebo, uri: 'https://github.com/tu-darmstadt-ros-pkg/hector_gazebo.git', version: indigo-devel} +- git: {local-name: hector_models, uri: 'https://github.com/tu-darmstadt-ros-pkg/hector_models.git', version: indigo-devel} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor/CHANGELOG.rst b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor/CHANGELOG.rst new file mode 100644 index 0000000..b1514ca --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor/CHANGELOG.rst @@ -0,0 +1,26 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package hector_quadrotor +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.5 (2015-03-28) +------------------ + +0.3.4 (2015-02-22) +------------------ + +0.3.3 (2014-09-01) +------------------ +* moved simulation package dependencies from hector_quadrotor metapackage to hector_quadrotor_gazebo +* Contributors: Johannes Meyer + +0.3.2 (2014-03-30) +------------------ +* added packages hector_quadrotor_controller and hector_quadrotor_controller_gazebo to meta-package +* Contributors: Johannes Meyer + +0.3.1 (2013-12-26) +------------------ + +0.3.0 (2013-09-11) +------------------ +* Catkinized stack hector_quadrotor and integrated hector_quadrotor_demo package from former hector_quadrotor_apps stack diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor/CMakeLists.txt new file mode 100644 index 0000000..a4e0651 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor/CMakeLists.txt @@ -0,0 +1,4 @@ +cmake_minimum_required(VERSION 2.8.3) +project(hector_quadrotor) +find_package(catkin REQUIRED) +catkin_metapackage() diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor/package.xml new file mode 100644 index 0000000..6278fbd --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor/package.xml @@ -0,0 +1,30 @@ + + hector_quadrotor + 0.3.5 + hector_quadrotor contains packages related to modeling, control and simulation of quadrotor UAV systems + Johannes Meyer + + BSD + + http://ros.org/wiki/hector_quadrotor + https://github.com/tu-darmstadt-ros-pkg/hector_quadrotor/issues + + Johannes Meyer + Stefan Kohlbrecher + + + catkin + + + + + + hector_quadrotor_controller + hector_quadrotor_description + hector_quadrotor_model + hector_quadrotor_teleop + hector_uav_msgs + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/CHANGELOG.rst b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/CHANGELOG.rst new file mode 100644 index 0000000..b502c46 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/CHANGELOG.rst @@ -0,0 +1,46 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package hector_quadrotor_controller +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.5 (2015-03-28) +------------------ +* updated angular/z controller parameters +* Remove redundant callback queue in twist_controller, use root_nh queue as per ros_control API +* Add controller timeout to allow faster shutdown of spawner +* Contributors: Johannes Meyer, Paul Bovbel + +0.3.4 (2015-02-22) +------------------ +* improved automatic landing detection and shutdown on rollovers +* slightly updated velocity controller limits and gains +* Contributors: Johannes Meyer + +0.3.3 (2014-09-01) +------------------ +* fixed some compiler warnings and missing return values +* increased integral gain for attitude stabilization (fix #12) +* make a copy of the root NodeHandle in all controllers + For some reason deconstructing the TwistController resulted in a pure virtual function call without this patch. +* Contributors: Johannes Meyer + +0.3.2 (2014-03-30) +------------------ +* Fix boost 1.53 issues + changed boost::shared_dynamic_cast to boost::dynamic_pointer_cast and + boost::shared_static_cast to boost::static_pointer_cast +* use a separate callback queue thread for the TwistController +* added optional twist limit in pose controller +* Contributors: Christopher Hrabia, Johannes Meyer + +0.3.1 (2013-12-26) +------------------ +* New controller implementation using ros_control +* Added pose controller +* Added motor controller that controls motor voltages from wrench commands +* Contributors: Johannes Meyer + +0.3.0 (2013-09-11) +------------------ +* Catkinized stack hector_quadrotor and integrated hector_quadrotor_demo package from former hector_quadrotor_apps stack +* Propulsion and aerodynamics models are in hector_quadrotor_model package now. +* Gazebo plugins are in hector_quadrotor_gazebo_plugins package now. diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/CMakeLists.txt new file mode 100644 index 0000000..c3fca45 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/CMakeLists.txt @@ -0,0 +1,78 @@ +cmake_minimum_required(VERSION 2.8.3) +project(hector_quadrotor_controller) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS roscpp geometry_msgs sensor_msgs nav_msgs hector_uav_msgs std_srvs hardware_interface controller_interface) +include_directories(include ${catkin_INCLUDE_DIRS}) + +## System dependencies are found with CMake's conventions +find_package(Boost REQUIRED COMPONENTS system) + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + INCLUDE_DIRS include + LIBRARIES hector_quadrotor_controller + CATKIN_DEPENDS roscpp geometry_msgs sensor_msgs nav_msgs hector_uav_msgs std_srvs hardware_interface controller_interface + DEPENDS +) + +########### +## Build ## +########### + +add_library(hector_quadrotor_controller src/quadrotor_interface.cpp src/pid.cpp) +target_link_libraries(hector_quadrotor_controller ${catkin_LIBRARIES}) +add_dependencies(hector_quadrotor_controller hector_uav_msgs_generate_messages_cpp) + +add_library(hector_quadrotor_pose_controller src/pose_controller.cpp) +target_link_libraries(hector_quadrotor_pose_controller hector_quadrotor_controller) + +add_library(hector_quadrotor_twist_controller src/twist_controller.cpp) +target_link_libraries(hector_quadrotor_twist_controller hector_quadrotor_controller ${BOOST_LIBRARIES}) + +add_library(hector_quadrotor_motor_controller src/motor_controller.cpp) +target_link_libraries(hector_quadrotor_motor_controller hector_quadrotor_controller) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executables and/or libraries for installation +install(TARGETS hector_quadrotor_controller hector_quadrotor_pose_controller hector_quadrotor_twist_controller hector_quadrotor_motor_controller + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +## Mark cpp header files for installation +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" +) + +## Mark other files for installation (e.g. launch and bag files, etc.) +install(DIRECTORY launch params DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) +install(FILES + plugin.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/include/hector_quadrotor_controller/handles.h b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/include/hector_quadrotor_controller/handles.h new file mode 100644 index 0000000..641ad18 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/include/hector_quadrotor_controller/handles.h @@ -0,0 +1,536 @@ +//================================================================================================= +// Copyright (c) 2013, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#ifndef HECTOR_QUADROTOR_CONTROLLER_HANDLES_H +#define HECTOR_QUADROTOR_CONTROLLER_HANDLES_H + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace hector_quadrotor_controller { + +class QuadrotorInterface; + +using geometry_msgs::Pose; +using geometry_msgs::Point; +using geometry_msgs::Quaternion; +using geometry_msgs::Twist; +using geometry_msgs::Vector3; +using geometry_msgs::Wrench; +using sensor_msgs::Imu; +using hector_uav_msgs::MotorStatus; +using hector_uav_msgs::MotorCommand; +using hector_uav_msgs::AttitudeCommand; +using hector_uav_msgs::YawrateCommand; +using hector_uav_msgs::ThrustCommand; + +template +class Handle_ +{ +public: + typedef T ValueType; + typedef Handle_ Base; + + Handle_(const std::string& name, const std::string& field = std::string()) : interface_(0), name_(name), field_(field), value_(0) {} + Handle_(QuadrotorInterface *interface, const std::string& name, const std::string& field = std::string()) : interface_(interface), name_(name), field_(field), value_(0) {} + Handle_(QuadrotorInterface *interface, const ValueType *source, const std::string& name, const std::string& field = std::string()) : interface_(interface), name_(name), field_(field) { *this = source; } + virtual ~Handle_() {} + + virtual const std::string& getName() const { return name_; } + virtual const std::string& getField() const { return field_; } + + virtual bool connected() const { return get(); } + virtual void reset() { value_ = 0; } + + Derived& operator=(const ValueType *source) { value_ = source; return static_cast(*this); } + const ValueType *get() const { return value_; } + const ValueType &operator*() const { return *value_; } + +protected: + QuadrotorInterface *interface_; + const std::string name_; + const std::string field_; + const ValueType *value_; +}; + +class PoseHandle : public Handle_ +{ +public: + using Base::operator=; + + PoseHandle() : Base("pose") {} + PoseHandle(QuadrotorInterface *interface) : Base(interface, "pose") {} + PoseHandle(QuadrotorInterface *interface, const Pose *pose) : Base(interface, pose, "pose") {} + virtual ~PoseHandle() {} + + const ValueType& pose() const { return *get(); } + + void getEulerRPY(double &roll, double &pitch, double &yaw) const; + double getYaw() const; + Vector3 toBody(const Vector3& nav) const; + Vector3 fromBody(const Vector3& nav) const; +}; +typedef boost::shared_ptr PoseHandlePtr; + +class TwistHandle : public Handle_ +{ +public: + using Base::operator=; + + TwistHandle() : Base("twist") {} + TwistHandle(QuadrotorInterface *interface) : Base(interface, "twist") {} + TwistHandle(QuadrotorInterface *interface, const Twist *twist) : Base(interface, twist, "twist") {} + virtual ~TwistHandle() {} + + const ValueType& twist() const { return *get(); } +}; +typedef boost::shared_ptr TwistHandlePtr; + +class AccelerationHandle : public Handle_ +{ +public: + using Base::operator=; + + AccelerationHandle(QuadrotorInterface *interface, const Vector3 *acceleration) : Base(interface, acceleration, "acceleration") {} + virtual ~AccelerationHandle() {} + + const ValueType& acceleration() const { return *get(); } +}; +typedef boost::shared_ptr AccelerationHandlePtr; + +class StateHandle : public PoseHandle, public TwistHandle +{ +public: + StateHandle() {} + StateHandle(QuadrotorInterface *interface, const Pose *pose, const Twist *twist) : PoseHandle(interface, pose), TwistHandle(interface, twist) {} + virtual ~StateHandle() {} + + virtual bool connected() const { return PoseHandle::connected() && TwistHandle::connected(); } +}; +typedef boost::shared_ptr PoseHandlePtr; + +class ImuHandle : public Handle_ +{ +public: + using Base::operator=; + + ImuHandle() : Base("imu") {} + ImuHandle(QuadrotorInterface *interface, const Imu *imu) : Base(interface, imu, "imu") {} + virtual ~ImuHandle() {} + + const ValueType& imu() const { return *get(); } +}; +typedef boost::shared_ptr ImuHandlePtr; + +class MotorStatusHandle : public Handle_ +{ +public: + using Base::operator=; + + MotorStatusHandle() : Base("motor_status") {} + MotorStatusHandle(QuadrotorInterface *interface, const MotorStatus *motor_status) : Base(interface, motor_status, "motor_status") {} + virtual ~MotorStatusHandle() {} + + const ValueType& motorStatus() const { return *get(); } +}; +typedef boost::shared_ptr MotorStatusHandlePtr; + +class CommandHandle +{ +public: + CommandHandle() : interface_(0), new_value_(false) {} + CommandHandle(QuadrotorInterface *interface, const std::string& name, const std::string& field) : interface_(interface), name_(name), field_(field), new_value_(false) {} + virtual ~CommandHandle() {} + + virtual const std::string& getName() const { return name_; } + virtual const std::string& getField() const { return field_; } + virtual bool connected() const = 0; + virtual void reset() {} + + void *get() const { return 0; } + + bool enabled(); + bool start(); + void stop(); + void disconnect(); + + template T* ownData(T* data) { my_.reset(data); return data; } + + template bool connectFrom(const Derived& output) { + Derived *me = dynamic_cast(this); + if (!me) return false; + ROS_DEBUG("Connected output port '%s (%p)' to input port '%s (%p)'", output.getName().c_str(), &output, me->getName().c_str(), me); + return (*me = output.get()).connected(); + } + + template bool connectTo(Derived& input) const { + const Derived *me = dynamic_cast(this); + if (!me) return false; + ROS_DEBUG("Connected output port '%s (%p)' to input port '%s (%p)'", me->getName().c_str(), me, input.getName().c_str(), &input); + return (input = me->get()).connected(); + } + +private: + QuadrotorInterface *interface_; + const std::string name_; + const std::string field_; + boost::shared_ptr my_; + +protected: + mutable bool new_value_; + bool wasNew() const { bool old = new_value_; new_value_ = false; return old; } +}; +typedef boost::shared_ptr CommandHandlePtr; + +namespace internal { + template struct FieldAccessor { + static typename Derived::ValueType *get(void *) { return 0; } + }; +} + +template +class CommandHandle_ : public Parent +{ +public: + typedef T ValueType; + typedef CommandHandle_ Base; + + CommandHandle_() : command_(0) {} + CommandHandle_(const Parent &other) : Parent(other), command_(0) {} + CommandHandle_(QuadrotorInterface *interface, const std::string& name, const std::string& field = std::string()) : Parent(interface, name, field), command_(0) {} + virtual ~CommandHandle_() {} + + virtual bool connected() const { return get(); } + virtual void reset() { command_ = 0; Parent::reset(); } + + using Parent::operator=; + Derived& operator=(ValueType *source) { command_ = source; return static_cast(*this); } + ValueType *get() const { return command_ ? command_ : internal::FieldAccessor::get(Parent::get()); } + ValueType &operator*() const { return *command_; } + + ValueType& command() { return *get(); } + const ValueType& getCommand() const { this->new_value_ = false; return *get(); } + void setCommand(const ValueType& command) { this->new_value_ = true; *get() = command; } + bool getCommand(ValueType& command) const { command = *get(); return this->wasNew(); } + + bool update(ValueType& command) const { + if (!connected()) return false; + command = getCommand(); + return true; + } + +protected: + ValueType *command_; +}; + +class PoseCommandHandle : public CommandHandle_ +{ +public: + using Base::operator=; + + PoseCommandHandle() {} + PoseCommandHandle(QuadrotorInterface *interface, const std::string& name, const std::string& field = std::string()) : Base(interface, name, field) {} + PoseCommandHandle(Pose* command) { *this = command; } + virtual ~PoseCommandHandle() {} +}; +typedef boost::shared_ptr PoseCommandHandlePtr; + +class HorizontalPositionCommandHandle : public CommandHandle_ +{ +public: + using Base::operator=; + + HorizontalPositionCommandHandle() {} + HorizontalPositionCommandHandle(const PoseCommandHandle& other) : Base(other) {} + HorizontalPositionCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name, "position.xy") {} + HorizontalPositionCommandHandle(Point* command) { *this = command; } + virtual ~HorizontalPositionCommandHandle() {} + + using Base::getCommand; + virtual bool getCommand(double &x, double &y) const { + x = get()->x; + y = get()->y; + return wasNew(); + } + + using Base::setCommand; + virtual void setCommand(double x, double y) + { + this->new_value_ = true; + get()->x = x; + get()->y = y; + } + + using Base::update; + bool update(Pose& command) const { + if (!connected()) return false; + getCommand(command.position.x, command.position.y); + return true; + } + + void getError(const PoseHandle &pose, double &x, double &y) const; +}; +typedef boost::shared_ptr HorizontalPositionCommandHandlePtr; + +namespace internal { + template <> struct FieldAccessor { + static Point *get(Pose *pose) { return &(pose->position); } + }; +} + +class HeightCommandHandle : public CommandHandle_ +{ +public: + using Base::operator=; + + HeightCommandHandle() {} + HeightCommandHandle(const PoseCommandHandle& other) : Base(other) {} + HeightCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name, "position.z") {} + HeightCommandHandle(double *command) { *this = command; } + virtual ~HeightCommandHandle() {} + + using Base::update; + bool update(Pose& command) const { + if (!connected()) return false; + command.position.z = getCommand(); + return true; + } + + double getError(const PoseHandle &pose) const; +}; +typedef boost::shared_ptr HeightCommandHandlePtr; + +namespace internal { + template <> struct FieldAccessor { + static double *get(Pose *pose) { return &(pose->position.z); } + }; +} + +class HeadingCommandHandle : public CommandHandle_ +{ +public: + using Base::operator=; + + HeadingCommandHandle() {} + HeadingCommandHandle(const PoseCommandHandle& other) : Base(other), scalar_(0) {} + HeadingCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name, "orientation.yaw"), scalar_(0) {} + HeadingCommandHandle(Quaternion *command) { *this = command; } + virtual ~HeadingCommandHandle() {} + + using Base::getCommand; + double getCommand() const; + + using Base::setCommand; + void setCommand(double command); + + using Base::update; + bool update(Pose& command) const; + + double getError(const PoseHandle &pose) const; + +protected: + double *scalar_; +}; +typedef boost::shared_ptr HeadingCommandHandlePtr; + +namespace internal { + template <> struct FieldAccessor { + static Quaternion *get(Pose *pose) { return &(pose->orientation); } + }; +} + +class TwistCommandHandle : public CommandHandle_ +{ +public: + + using Base::operator=; + + TwistCommandHandle() {} + TwistCommandHandle(QuadrotorInterface *interface, const std::string& name, const std::string& field = std::string()) : Base(interface, name, field) {} + TwistCommandHandle(Twist* command) { *this = command; } + virtual ~TwistCommandHandle() {} +}; +typedef boost::shared_ptr TwistCommandHandlePtr; + +class HorizontalVelocityCommandHandle : public CommandHandle_ +{ +public: + using Base::operator=; + + HorizontalVelocityCommandHandle() {} + HorizontalVelocityCommandHandle(const TwistCommandHandle& other) : Base(other) {} + HorizontalVelocityCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name, "linear.xy") {} + HorizontalVelocityCommandHandle(Vector3* command) { *this = command; } + virtual ~HorizontalVelocityCommandHandle() {} + + using Base::getCommand; + bool getCommand(double &x, double &y) const { + x = get()->x; + y = get()->y; + return true; + } + + using Base::setCommand; + void setCommand(double x, double y) + { + get()->x = x; + get()->y = y; + } + + using Base::update; + bool update(Twist& command) const { + if (!connected()) return false; + getCommand(command.linear.x, command.linear.y); + return true; + } +}; +typedef boost::shared_ptr HorizontalVelocityCommandHandlePtr; + +namespace internal { + template <> struct FieldAccessor { + static Vector3 *get(Twist *twist) { return &(twist->linear); } + }; +} + +class VerticalVelocityCommandHandle : public CommandHandle_ +{ +public: + using Base::operator=; + + VerticalVelocityCommandHandle() {} + VerticalVelocityCommandHandle(const TwistCommandHandle& other) : Base(other) {} + VerticalVelocityCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name, "linear.z") {} + VerticalVelocityCommandHandle(double* command) { *this = command; } + virtual ~VerticalVelocityCommandHandle() {} + + using Base::update; + bool update(Twist& command) const { + if (!connected()) return false; + command.linear.z = *get(); + return true; + } +}; +typedef boost::shared_ptr VerticalVelocityCommandHandlePtr; + +namespace internal { + template <> struct FieldAccessor { + static double *get(Twist *twist) { return &(twist->linear.z); } + }; +} + +class AngularVelocityCommandHandle : public CommandHandle_ +{ +public: + using Base::operator=; + + AngularVelocityCommandHandle() {} + AngularVelocityCommandHandle(const TwistCommandHandle& other) : Base(other) {} + AngularVelocityCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name, "angular.z") {} + AngularVelocityCommandHandle(double* command) { *this = command; } + virtual ~AngularVelocityCommandHandle() {} + + using Base::update; + bool update(Twist& command) const { + if (!connected()) return false; + command.linear.z = *get(); + return true; + } +}; +typedef boost::shared_ptr AngularVelocityCommandHandlePtr; + +namespace internal { + template <> struct FieldAccessor { + static double *get(Twist *twist) { return &(twist->angular.z); } + }; +} + +class WrenchCommandHandle : public CommandHandle_ +{ +public: + using Base::operator=; + + WrenchCommandHandle() {} + WrenchCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name) {} + virtual ~WrenchCommandHandle() {} +}; +typedef boost::shared_ptr WrenchCommandHandlePtr; + +class MotorCommandHandle : public CommandHandle_ +{ +public: + using Base::operator=; + + MotorCommandHandle() {} + MotorCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name) {} + virtual ~MotorCommandHandle() {} +}; +typedef boost::shared_ptr MotorCommandHandlePtr; + +class AttitudeCommandHandle : public CommandHandle_ +{ +public: + using Base::operator=; + + AttitudeCommandHandle() {} + AttitudeCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name) {} + virtual ~AttitudeCommandHandle() {} +}; +typedef boost::shared_ptr AttitudeCommandHandlePtr; + +class YawrateCommandHandle : public CommandHandle_ +{ +public: + using Base::operator=; + + YawrateCommandHandle() {} + YawrateCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name) {} + virtual ~YawrateCommandHandle() {} +}; +typedef boost::shared_ptr YawrateCommandHandlePtr; + +class ThrustCommandHandle : public CommandHandle_ +{ +public: + using Base::operator=; + + ThrustCommandHandle() {} + ThrustCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name) {} + virtual ~ThrustCommandHandle() {} +}; +typedef boost::shared_ptr ThrustCommandHandlePtr; + +} // namespace hector_quadrotor_controller + +#endif // HECTOR_QUADROTOR_CONTROLLER_HANDLES_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/include/hector_quadrotor_controller/pid.h b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/include/hector_quadrotor_controller/pid.h new file mode 100644 index 0000000..f7601c3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/include/hector_quadrotor_controller/pid.h @@ -0,0 +1,45 @@ +#ifndef HECTOR_QUADROTOR_CONTROLLER_PID_H +#define HECTOR_QUADROTOR_CONTROLLER_PID_H + +#include + +namespace hector_quadrotor_controller { + +class PID +{ +public: + struct parameters { + parameters(); + bool enabled; + double time_constant; + double k_p; + double k_i; + double k_d; + double limit_i; + double limit_output; + } parameters_; + + struct state { + state(); + double p, i, d; + double input, dinput; + double dx; + } state_; + +public: + PID(); + PID(const parameters& parameters); + ~PID(); + + void init(const ros::NodeHandle ¶m_nh); + void reset(); + + double update(double input, double x, double dx, const ros::Duration& dt); + double update(double error, double dx, const ros::Duration& dt); + + double getFilteredControlError(double& filtered_error, double time_constant, const ros::Duration& dt); +}; + +} // namespace hector_quadrotor_controller + +#endif // HECTOR_QUADROTOR_CONTROLLER_PID_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/include/hector_quadrotor_controller/quadrotor_interface.h b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/include/hector_quadrotor_controller/quadrotor_interface.h new file mode 100644 index 0000000..e077e66 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/include/hector_quadrotor_controller/quadrotor_interface.h @@ -0,0 +1,143 @@ +//================================================================================================= +// Copyright (c) 2013, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#ifndef HECTOR_QUADROTOR_CONTROLLER_QUADROTOR_INTERFACE_H +#define HECTOR_QUADROTOR_CONTROLLER_QUADROTOR_INTERFACE_H + +#include + +#include + +#include +#include + +namespace hector_quadrotor_controller { + +using namespace hardware_interface; + +class QuadrotorInterface : public HardwareInterface +{ +public: + QuadrotorInterface(); + virtual ~QuadrotorInterface(); + + virtual PoseHandlePtr getPose() { return PoseHandlePtr(); } + virtual TwistHandlePtr getTwist() { return TwistHandlePtr(); } + virtual AccelerationHandlePtr getAcceleration() { return AccelerationHandlePtr(); } + virtual ImuHandlePtr getSensorImu() { return ImuHandlePtr(); } + virtual MotorStatusHandlePtr getMotorStatus() { return MotorStatusHandlePtr(); } + + virtual bool getMassAndInertia(double &mass, double inertia[3]) { return false; } + + template boost::shared_ptr getHandle() + { + return boost::shared_ptr(new HandleType(this)); + } + + template boost::shared_ptr addInput(const std::string& name) + { + boost::shared_ptr input = getInput(name); + if (input) return input; + + // create new input handle + input.reset(new HandleType(this, name)); + inputs_[name] = input; + + // connect to output of same name + if (outputs_.count(name)) { + boost::shared_ptr output = boost::dynamic_pointer_cast(outputs_.at(name)); + output->connectTo(*input); + } + + return input; + } + + template boost::shared_ptr addOutput(const std::string& name) + { + boost::shared_ptr output = getOutput(name); + if (output) return output; + + // create new output handle + output.reset(new HandleType(this, name)); + outputs_[name] = output; + *output = output->ownData(new typename HandleType::ValueType()); + + //claim resource + claim(name); + + // connect to output of same name + if (inputs_.count(name)) { + boost::shared_ptr input = boost::dynamic_pointer_cast(inputs_.at(name)); + output->connectTo(*input); + } + + return output; + } + + template boost::shared_ptr getOutput(const std::string& name) const + { + if (!outputs_.count(name)) return boost::shared_ptr(); + return boost::static_pointer_cast(outputs_.at(name)); + } + + template boost::shared_ptr getInput(const std::string& name) const + { + if (!inputs_.count(name)) return boost::shared_ptr(); + return boost::static_pointer_cast(inputs_.at(name)); + } + + template typename HandleType::ValueType const* getCommand(const std::string& name) const + { + boost::shared_ptr output = getOutput(name); + if (!output || !output->connected()) return 0; + return &(output->command()); + } + + virtual const Pose *getPoseCommand() const; + virtual const Twist *getTwistCommand() const; + virtual const Wrench *getWrenchCommand() const; + virtual const MotorCommand *getMotorCommand() const; + + bool enabled(const CommandHandle *handle) const; + bool start(const CommandHandle *handle); + void stop(const CommandHandle *handle); + + void disconnect(const CommandHandle *handle); + +private: +// typedef std::list< CommandHandlePtr > HandleList; +// std::map inputs_; +// std::map outputs_; + std::map inputs_; + std::map outputs_; + std::map enabled_; +}; + +} // namespace hector_quadrotor_controller + +#endif // HECTOR_QUADROTOR_CONTROLLER_QUADROTOR_INTERFACE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/launch/controller.launch b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/launch/controller.launch new file mode 100644 index 0000000..e239ce4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/launch/controller.launch @@ -0,0 +1,7 @@ + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/package.xml new file mode 100644 index 0000000..6c43842 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/package.xml @@ -0,0 +1,42 @@ + + hector_quadrotor_controller + 0.3.5 + hector_quadrotor_controller provides libraries and a node for quadrotor control using ros_control. + Johannes Meyer + + BSD + + http://ros.org/wiki/hector_quadrotor_controller + https://github.com/tu-darmstadt-ros-pkg/hector_quadrotor/issues + + Johannes Meyer + + + catkin + + + roscpp + geometry_msgs + sensor_msgs + nav_msgs + hector_uav_msgs + std_srvs + hardware_interface + controller_interface + + + roscpp + geometry_msgs + sensor_msgs + nav_msgs + hector_uav_msgs + std_srvs + hardware_interface + controller_interface + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/params/controller.yaml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/params/controller.yaml new file mode 100644 index 0000000..981e152 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/params/controller.yaml @@ -0,0 +1,50 @@ +controller: + pose: + type: hector_quadrotor_controller/PoseController + xy: + k_p: 2.0 + k_i: 0.0 + k_d: 0.0 + limit_output: 5.0 + z: + k_p: 2.0 + k_i: 0.0 + k_d: 0.0 + limit_output: 5.0 + yaw: + k_p: 2.0 + k_i: 0.0 + k_d: 0.0 + limit_output: 1.0 + twist: + type: hector_quadrotor_controller/TwistController + linear/xy: + k_p: 5.0 + k_i: 1.0 + k_d: 0.0 + limit_output: 10.0 + time_constant: 0.05 + linear/z: + k_p: 5.0 + k_i: 1.0 + k_d: 0.0 + limit_output: 10.0 + time_constant: 0.05 + angular/xy: + k_p: 10.0 + k_i: 5.0 + k_d: 5.0 + time_constant: 0.01 + angular/z: + k_p: 5.0 + k_i: 2.5 + k_d: 0.0 + limit_output: 3.0 + time_constant: 0.1 + limits: + load_factor: 1.5 + force/z: 30.0 + torque/xy: 10.0 + torque/z: 1.0 + motor: + type: hector_quadrotor_controller/MotorController diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/plugin.xml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/plugin.xml new file mode 100644 index 0000000..954de2b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/plugin.xml @@ -0,0 +1,23 @@ + + + + + The PoseController controls the quadrotor's pose and outputs velocity commands. + + + + + + + The TwistController controls the quadrotor's twist (linear and angular velocity) by applying torque and thrust similar to a real quadrotor. + + + + + + + The MotorController calculates the output voltages of the four motors from the commanded thrust and torque using a simple linearized model. + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/motor_controller.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/motor_controller.cpp new file mode 100644 index 0000000..68bba5b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/motor_controller.cpp @@ -0,0 +1,186 @@ +//================================================================================================= +// Copyright (c) 2013, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include +#include + +#include +#include + +#include +#include + +namespace hector_quadrotor_controller { + +using namespace controller_interface; + +class MotorController : public controller_interface::Controller +{ +public: + MotorController() + : node_handle_(0) + {} + + ~MotorController() + { + if (node_handle_) { + node_handle_->shutdown(); + delete node_handle_; + node_handle_ = 0; + } + } + + bool init(QuadrotorInterface *interface, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) + { + // get interface handles + wrench_input_ = interface->addInput("wrench"); + motor_output_ = interface->addOutput("motor"); + + // initialize NodeHandle + delete node_handle_; + node_handle_ = new ros::NodeHandle(root_nh); + + // load parameters + controller_nh.getParam("force_per_voltage", parameters_.force_per_voltage = 0.559966216); + controller_nh.getParam("torque_per_voltage", parameters_.torque_per_voltage = 7.98598e-3); + controller_nh.getParam("lever", parameters_.lever = 0.275); + root_nh.param("base_link_frame", base_link_frame_, "base_link"); + + // TODO: calculate these parameters from the quadrotor_propulsion parameters +// quadrotor_propulsion: +// k_t: 0.015336864714397 +// k_m: -7.011631909766668e-5 + +// CT2s: -1.3077e-2 +// CT1s: -2.5224e-4 +// CT0s: 1.538190483976698e-5 + + return true; + } + + void reset() + { + wrench_.wrench.force.x = 0.0; + wrench_.wrench.force.y = 0.0; + wrench_.wrench.force.z = 0.0; + wrench_.wrench.torque.x = 0.0; + wrench_.wrench.torque.y = 0.0; + wrench_.wrench.torque.z = 0.0; + + motor_.force.assign(4, 0.0); + motor_.torque.assign(4, 0.0); + motor_.frequency.clear(); + motor_.voltage.assign(4, 0.0); + } + + void wrenchCommandCallback(const geometry_msgs::WrenchStampedConstPtr& command) + { + wrench_ = *command; + if (wrench_.header.stamp.isZero()) wrench_.header.stamp = ros::Time::now(); + + // start controller if it not running + if (!isRunning()) this->startRequest(wrench_.header.stamp); + } + + void starting(const ros::Time &time) + { + reset(); + motor_output_->start(); + } + + void stopping(const ros::Time &time) + { + motor_output_->stop(); + } + + void update(const ros::Time& time, const ros::Duration& period) + { + // Get wrench command input + if (wrench_input_->connected() && wrench_input_->enabled()) { + wrench_.wrench = wrench_input_->getCommand(); + } + + // Update output + if (wrench_.wrench.force.z > 0.0) { + + double nominal_thrust_per_motor = wrench_.wrench.force.z / 4.0; + motor_.force[0] = nominal_thrust_per_motor - wrench_.wrench.torque.y / 2.0 / parameters_.lever; + motor_.force[1] = nominal_thrust_per_motor - wrench_.wrench.torque.x / 2.0 / parameters_.lever; + motor_.force[2] = nominal_thrust_per_motor + wrench_.wrench.torque.y / 2.0 / parameters_.lever; + motor_.force[3] = nominal_thrust_per_motor + wrench_.wrench.torque.x / 2.0 / parameters_.lever; + + double nominal_torque_per_motor = wrench_.wrench.torque.z / 4.0; + motor_.voltage[0] = motor_.force[0] / parameters_.force_per_voltage + nominal_torque_per_motor / parameters_.torque_per_voltage; + motor_.voltage[1] = motor_.force[1] / parameters_.force_per_voltage - nominal_torque_per_motor / parameters_.torque_per_voltage; + motor_.voltage[2] = motor_.force[2] / parameters_.force_per_voltage + nominal_torque_per_motor / parameters_.torque_per_voltage; + motor_.voltage[3] = motor_.force[3] / parameters_.force_per_voltage - nominal_torque_per_motor / parameters_.torque_per_voltage; + + motor_.torque[0] = motor_.voltage[0] * parameters_.torque_per_voltage; + motor_.torque[1] = motor_.voltage[1] * parameters_.torque_per_voltage; + motor_.torque[2] = motor_.voltage[2] * parameters_.torque_per_voltage; + motor_.torque[3] = motor_.voltage[3] * parameters_.torque_per_voltage; + + if (motor_.voltage[0] < 0.0) motor_.voltage[0] = 0.0; + if (motor_.voltage[1] < 0.0) motor_.voltage[1] = 0.0; + if (motor_.voltage[2] < 0.0) motor_.voltage[2] = 0.0; + if (motor_.voltage[3] < 0.0) motor_.voltage[3] = 0.0; + + } else { + reset(); + } + + // set wrench output + motor_.header.stamp = time; + motor_.header.frame_id = "base_link"; + motor_output_->setCommand(motor_); + } + +private: + WrenchCommandHandlePtr wrench_input_; + MotorCommandHandlePtr motor_output_; + + ros::NodeHandle *node_handle_; + ros::Subscriber wrench_subscriber_; + ros::ServiceServer engage_service_server_; + ros::ServiceServer shutdown_service_server_; + + geometry_msgs::WrenchStamped wrench_; + hector_uav_msgs::MotorCommand motor_; + std::string base_link_frame_; + + struct { + double force_per_voltage; // coefficient for linearized volts to force conversion for a single motor [N / V] + double torque_per_voltage; // coefficient for linearized volts to force conversion for a single motor [Nm / V] + double lever; // the lever arm from origin to the motor axes (symmetry assumption) [m] + } parameters_; +}; + +} // namespace hector_quadrotor_controller + +#include +PLUGINLIB_EXPORT_CLASS(hector_quadrotor_controller::MotorController, controller_interface::ControllerBase) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/pid.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/pid.cpp new file mode 100644 index 0000000..bc8e3e5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/pid.cpp @@ -0,0 +1,152 @@ +//================================================================================================= +// Copyright (c) 2013, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include +#include + +namespace hector_quadrotor_controller { + +PID::state::state() + : p(std::numeric_limits::quiet_NaN()) + , i(0.0) + , d(std::numeric_limits::quiet_NaN()) + , input(std::numeric_limits::quiet_NaN()) + , dinput(0.0) + , dx(std::numeric_limits::quiet_NaN()) +{ +} + +PID::parameters::parameters() + : enabled(true) + , time_constant(0.0) + , k_p(0.0) + , k_i(0.0) + , k_d(0.0) + , limit_i(std::numeric_limits::quiet_NaN()) + , limit_output(std::numeric_limits::quiet_NaN()) +{ +} + +PID::PID() +{} + +PID::PID(const parameters& params) + : parameters_(params) +{} + +PID::~PID() +{} + +void PID::init(const ros::NodeHandle ¶m_nh) +{ + param_nh.getParam("enabled", parameters_.enabled); + param_nh.getParam("k_p", parameters_.k_p); + param_nh.getParam("k_i", parameters_.k_i); + param_nh.getParam("k_d", parameters_.k_d); + param_nh.getParam("limit_i", parameters_.limit_i); + param_nh.getParam("limit_output", parameters_.limit_output); + param_nh.getParam("time_constant", parameters_.time_constant); +} + +void PID::reset() +{ + state_ = state(); +} + +template static inline T& checknan(T& value) +{ + if (std::isnan(value)) value = T(); + return value; +} + +double PID::update(double input, double x, double dx, const ros::Duration& dt) +{ + if (!parameters_.enabled) return 0.0; + double dt_sec = dt.toSec(); + + // low-pass filter input + if (std::isnan(state_.input)) state_.input = input; + if (dt_sec + parameters_.time_constant > 0.0) { + state_.dinput = (input - state_.input) / (dt_sec + parameters_.time_constant); + state_.input = (dt_sec * input + parameters_.time_constant * state_.input) / (dt_sec + parameters_.time_constant); + } + + return update(state_.input - x, dx, dt); +} + +double PID::update(double error, double dx, const ros::Duration& dt) +{ + if (!parameters_.enabled) return 0.0; + if (std::isnan(error)) return 0.0; + double dt_sec = dt.toSec(); + + // integral error + state_.i += error * dt_sec; + if (parameters_.limit_i > 0.0) + { + if (state_.i > parameters_.limit_i) state_.i = parameters_.limit_i; + if (state_.i < -parameters_.limit_i) state_.i = -parameters_.limit_i; + } + + // differential error + if (dt_sec > 0.0 && !std::isnan(state_.p) && !std::isnan(state_.dx)) { + state_.d = (error - state_.p) / dt_sec + state_.dx - dx; + } else { + state_.d = -dx; + } + state_.dx = dx; + + // proportional error + state_.p = error; + + // calculate output... + double output = parameters_.k_p * state_.p + parameters_.k_i * state_.i + parameters_.k_d * state_.d; + int antiwindup = 0; + if (parameters_.limit_output > 0.0) + { + if (output > parameters_.limit_output) { output = parameters_.limit_output; antiwindup = 1; } + if (output < -parameters_.limit_output) { output = -parameters_.limit_output; antiwindup = -1; } + } + if (antiwindup && (error * dt_sec * antiwindup > 0.0)) state_.i -= error * dt_sec; + + checknan(output); + return output; +} + +double PID::getFilteredControlError(double& filtered_error, double time_constant, const ros::Duration& dt) +{ + double dt_sec = dt.toSec(); + filtered_error = checknan(filtered_error); + if (dt_sec + time_constant > 0.0) { + filtered_error = (time_constant * filtered_error + dt_sec * state_.p) / (dt_sec + time_constant); + } + return filtered_error; +} + +} // namespace hector_quadrotor_controller + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/pose_controller.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/pose_controller.cpp new file mode 100644 index 0000000..d1f8f55 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/pose_controller.cpp @@ -0,0 +1,204 @@ +//================================================================================================= +// Copyright (c) 2013, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace hector_quadrotor_controller { + +using namespace controller_interface; + +class PoseController : public controller_interface::Controller +{ +public: + PoseController() {} + + ~PoseController() {} + + bool init(QuadrotorInterface *interface, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) + { + // get interface handles + pose_ = interface->getPose(); + twist_ = interface->getTwist(); + + pose_input_ = interface->addInput("pose"); + twist_input_ = interface->addInput("pose/twist"); + twist_limit_ = interface->addInput("pose/twist_limit"); + twist_output_ = interface->addOutput("twist"); + + node_handle_ = root_nh; + + // subscribe to commanded pose and velocity + pose_subscriber_ = node_handle_.subscribe("command/pose", 1, boost::bind(&PoseController::poseCommandCallback, this, _1)); + twist_subscriber_ = node_handle_.subscribe("command/twist", 1, boost::bind(&PoseController::twistCommandCallback, this, _1)); + + // initialize PID controllers + pid_.x.init(ros::NodeHandle(controller_nh, "xy")); + pid_.y.init(ros::NodeHandle(controller_nh, "xy")); + pid_.z.init(ros::NodeHandle(controller_nh, "z")); + pid_.yaw.init(ros::NodeHandle(controller_nh, "yaw")); + + return true; + } + + void reset() + { + pid_.x.reset(); + pid_.y.reset(); + pid_.z.reset(); + pid_.yaw.reset(); + } + + void poseCommandCallback(const geometry_msgs::PoseStampedConstPtr& command) + { + pose_command_ = *command; + if (!(pose_input_->connected())) *pose_input_ = &(pose_command_.pose); + pose_input_->start(); + + ros::Time start_time = command->header.stamp; + if (start_time.isZero()) start_time = ros::Time::now(); + if (!isRunning()) this->startRequest(start_time); + } + + void twistCommandCallback(const geometry_msgs::TwistStampedConstPtr& command) + { + twist_command_ = *command; + if (!(twist_input_->connected())) *twist_input_ = &(twist_command_.twist); + twist_input_->start(); + + ros::Time start_time = command->header.stamp; + if (start_time.isZero()) start_time = ros::Time::now(); + if (!isRunning()) this->startRequest(start_time); + } + + void starting(const ros::Time &time) + { + reset(); + twist_output_->start(); + } + + void stopping(const ros::Time &time) + { + twist_output_->stop(); + } + + void update(const ros::Time& time, const ros::Duration& period) + { + Twist output; + + // check command timeout + // TODO + + // return if no pose command is available + if (pose_input_->enabled()) { + // control horizontal position + double error_n, error_w; + HorizontalPositionCommandHandle(*pose_input_).getError(*pose_, error_n, error_w); + output.linear.x = pid_.x.update(error_n, twist_->twist().linear.x, period); + output.linear.y = pid_.y.update(error_w, twist_->twist().linear.y, period); + + // control height + output.linear.z = pid_.z.update(HeightCommandHandle(*pose_input_).getError(*pose_), twist_->twist().linear.z, period); + + // control yaw angle + output.angular.z = pid_.yaw.update(HeadingCommandHandle(*pose_input_).getError(*pose_), twist_->twist().angular.z, period); + } + + // add twist command if available + if (twist_input_->enabled()) + { + output.linear.x += twist_input_->getCommand().linear.x; + output.linear.y += twist_input_->getCommand().linear.y; + output.linear.z += twist_input_->getCommand().linear.z; + output.angular.x += twist_input_->getCommand().angular.x; + output.angular.y += twist_input_->getCommand().angular.y; + output.angular.z += twist_input_->getCommand().angular.z; + } + + // limit twist + if (twist_limit_->enabled()) + { + double linear_xy = sqrt(output.linear.x*output.linear.x + output.linear.y*output.linear.y); + double limit_linear_xy = std::max(twist_limit_->get()->linear.x, twist_limit_->get()->linear.y); + if (limit_linear_xy > 0.0 && linear_xy > limit_linear_xy) { + output.linear.x *= limit_linear_xy / linear_xy; + output.linear.y *= limit_linear_xy / linear_xy; + } + if (twist_limit_->get()->linear.z > 0.0 && fabs(output.linear.z) > twist_limit_->get()->linear.z) { + output.linear.z *= twist_limit_->get()->linear.z / fabs(output.linear.z); + } + double angular_xy = sqrt(output.angular.x*output.angular.x + output.angular.y*output.angular.y); + double limit_angular_xy = std::max(twist_limit_->get()->angular.x, twist_limit_->get()->angular.y); + if (limit_angular_xy > 0.0 && angular_xy > limit_angular_xy) { + output.angular.x *= limit_angular_xy / angular_xy; + output.angular.y *= limit_angular_xy / angular_xy; + } + if (twist_limit_->get()->angular.z > 0.0 && fabs(output.angular.z) > twist_limit_->get()->angular.z) { + output.angular.z *= twist_limit_->get()->angular.z / fabs(output.angular.z); + } + } + + // set twist output + twist_output_->setCommand(output); + } + +private: + PoseHandlePtr pose_; + PoseCommandHandlePtr pose_input_; + TwistHandlePtr twist_; + TwistCommandHandlePtr twist_input_; + TwistCommandHandlePtr twist_limit_; + TwistCommandHandlePtr twist_output_; + + geometry_msgs::PoseStamped pose_command_; + geometry_msgs::TwistStamped twist_command_; + + ros::NodeHandle node_handle_; + ros::Subscriber pose_subscriber_; + ros::Subscriber twist_subscriber_; + + struct { + PID x; + PID y; + PID z; + PID yaw; + } pid_; +}; + +} // namespace hector_quadrotor_controller + +#include +PLUGINLIB_EXPORT_CLASS(hector_quadrotor_controller::PoseController, controller_interface::ControllerBase) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/quadrotor_interface.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/quadrotor_interface.cpp new file mode 100644 index 0000000..4cdef65 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/quadrotor_interface.cpp @@ -0,0 +1,195 @@ +//================================================================================================= +// Copyright (c) 2013, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include + +#include + +namespace hector_quadrotor_controller { + +QuadrotorInterface::QuadrotorInterface() +{} + +QuadrotorInterface::~QuadrotorInterface() +{} + +bool QuadrotorInterface::enabled(const CommandHandle *handle) const +{ + if (!handle || !handle->connected()) return false; + std::string resource = handle->getName(); + return enabled_.count(resource) > 0; +} + +bool QuadrotorInterface::start(const CommandHandle *handle) +{ + if (!handle || !handle->connected()) return false; + if (enabled(handle)) return true; + std::string resource = handle->getName(); + enabled_[resource] = handle; + ROS_DEBUG_NAMED("quadrotor_interface", "Enabled %s control", resource.c_str()); + return true; +} + +void QuadrotorInterface::stop(const CommandHandle *handle) +{ + if (!handle) return; + if (!enabled(handle)) return; + std::string resource = handle->getName(); + std::map::iterator it = enabled_.lower_bound(resource); + if (it != enabled_.end() && it->second == handle) enabled_.erase(it); + ROS_DEBUG_NAMED("quadrotor_interface", "Disabled %s control", resource.c_str()); +} + +void QuadrotorInterface::disconnect(const CommandHandle *handle) +{ + if (!handle) return; + std::string resource = handle->getName(); + if (inputs_.count(resource)) { + const CommandHandlePtr& input = inputs_.at(resource); + if (input.get() != handle) input->reset(); + } + if (outputs_.count(resource)) { + const CommandHandlePtr& output = outputs_.at(resource); + if (output.get() != handle) output->reset(); + } +} + +const Pose *QuadrotorInterface::getPoseCommand() const { return getCommand("pose"); } +const Twist *QuadrotorInterface::getTwistCommand() const { return getCommand("twist"); } +const Wrench *QuadrotorInterface::getWrenchCommand() const { return getCommand("wrench"); } +const MotorCommand *QuadrotorInterface::getMotorCommand() const { return getCommand("motor"); } + +void PoseHandle::getEulerRPY(double &roll, double &pitch, double &yaw) const +{ + const Quaternion::_w_type& w = pose().orientation.w; + const Quaternion::_x_type& x = pose().orientation.x; + const Quaternion::_y_type& y = pose().orientation.y; + const Quaternion::_z_type& z = pose().orientation.z; + roll = atan2(2.*y*z + 2.*w*x, z*z - y*y - x*x + w*w); + pitch = -asin(2.*x*z - 2.*w*y); + yaw = atan2(2.*x*y + 2.*w*z, x*x + w*w - z*z - y*y); +} + +double PoseHandle::getYaw() const +{ + const Quaternion::_w_type& w = pose().orientation.w; + const Quaternion::_x_type& x = pose().orientation.x; + const Quaternion::_y_type& y = pose().orientation.y; + const Quaternion::_z_type& z = pose().orientation.z; + return atan2(2.*x*y + 2.*w*z, x*x + w*w - z*z - y*y); +} + +Vector3 PoseHandle::toBody(const Vector3& nav) const +{ + const Quaternion::_w_type& w = pose().orientation.w; + const Quaternion::_x_type& x = pose().orientation.x; + const Quaternion::_y_type& y = pose().orientation.y; + const Quaternion::_z_type& z = pose().orientation.z; + Vector3 body; + body.x = (w*w+x*x-y*y-z*z) * nav.x + (2.*x*y + 2.*w*z) * nav.y + (2.*x*z - 2.*w*y) * nav.z; + body.y = (2.*x*y - 2.*w*z) * nav.x + (w*w-x*x+y*y-z*z) * nav.y + (2.*y*z + 2.*w*x) * nav.z; + body.z = (2.*x*z + 2.*w*y) * nav.x + (2.*y*z - 2.*w*x) * nav.y + (w*w-x*x-y*y+z*z) * nav.z; + return body; +} + +Vector3 PoseHandle::fromBody(const Vector3& body) const +{ + const Quaternion::_w_type& w = pose().orientation.w; + const Quaternion::_x_type& x = pose().orientation.x; + const Quaternion::_y_type& y = pose().orientation.y; + const Quaternion::_z_type& z = pose().orientation.z; + Vector3 nav; + nav.x = (w*w+x*x-y*y-z*z) * body.x + (2.*x*y - 2.*w*z) * body.y + (2.*x*z + 2.*w*y) * body.z; + nav.y = (2.*x*y + 2.*w*z) * body.x + (w*w-x*x+y*y-z*z) * body.y + (2.*y*z - 2.*w*x) * body.z; + nav.z = (2.*x*z - 2.*w*y) * body.x + (2.*y*z + 2.*w*x) * body.y + (w*w-x*x-y*y+z*z) * body.z; + return nav; +} + +void HorizontalPositionCommandHandle::getError(const PoseHandle &pose, double &x, double &y) const +{ + getCommand(x, y); + x -= pose.get()->position.x; + y -= pose.get()->position.y; +} + +double HeightCommandHandle::getError(const PoseHandle &pose) const +{ + return getCommand() - pose.get()->position.z; +} + +void HeadingCommandHandle::setCommand(double command) +{ + if (get()) { + get()->x = 0.0; + get()->y = 0.0; + get()->z = sin(command / 2.); + get()->w = cos(command / 2.); + } + + if (scalar_) { + *scalar_ = command; + } +} + +double HeadingCommandHandle::getCommand() const { + if (scalar_) return *scalar_; + const Quaternion::_w_type& w = get()->w; + const Quaternion::_x_type& x = get()->x; + const Quaternion::_y_type& y = get()->y; + const Quaternion::_z_type& z = get()->z; + return atan2(2.*x*y + 2.*w*z, x*x + w*w - z*z - y*y); +} + +bool HeadingCommandHandle::update(Pose& command) const { + if (get()) { + command.orientation = *get(); + return true; + } + if (scalar_) { + command.orientation.x = 0.0; + command.orientation.y = 0.0; + command.orientation.z = sin(*scalar_ / 2.); + command.orientation.x = cos(*scalar_ / 2.); + return true; + } + return false; +} + +double HeadingCommandHandle::getError(const PoseHandle &pose) const { + static const double M_2PI = 2.0 * M_PI; + double error = getCommand() - pose.getYaw() + M_PI; + error -= floor(error / M_2PI) * M_2PI; + return error - M_PI; +} + +bool CommandHandle::enabled() { return interface_->enabled(this); } +bool CommandHandle::start() { return interface_->start(this); } +void CommandHandle::stop() { interface_->stop(this); } +void CommandHandle::disconnect() { interface_->disconnect(this); } + +} // namespace hector_quadrotor_controller diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/twist_controller (å¤ä»¶).cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/twist_controller (å¤ä»¶).cpp new file mode 100644 index 0000000..44107e9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/twist_controller (å¤ä»¶).cpp @@ -0,0 +1,328 @@ +//================================================================================================= +// Copyright (c) 2013, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include +#include + +#include + +#include +#include +#include + +#include +#include + +#include + +#include + +namespace hector_quadrotor_controller { + +using namespace controller_interface; + +class TwistController : public controller_interface::Controller +{ +public: + TwistController() + {} + + ~TwistController() + {} + + bool init(QuadrotorInterface *interface, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) + { + // get interface handles + pose_ = interface->getPose(); + twist_ = interface->getTwist(); + acceleration_ = interface->getAcceleration(); + twist_input_ = interface->addInput("twist"); + wrench_output_ = interface->addOutput("wrench"); + node_handle_ = root_nh; + + // subscribe to commanded twist (geometry_msgs/TwistStamped) and cmd_vel (geometry_msgs/Twist) + twist_subscriber_ = node_handle_.subscribe("command/twist", 1, boost::bind(&TwistController::twistCommandCallback, this, _1)); + cmd_vel_subscriber_ = node_handle_.subscribe("/fixedwing/cmd_vel", 1, boost::bind(&TwistController::cmd_velCommandCallback, this, _1)); + + // engage/shutdown service servers + engage_service_server_ = node_handle_.advertiseService("engage", boost::bind(&TwistController::engageCallback, this, _1, _2)); + shutdown_service_server_ = node_handle_.advertiseService("shutdown", boost::bind(&TwistController::shutdownCallback, this, _1, _2)); + + // initialize PID controllers + pid_.linear.x.init(ros::NodeHandle(controller_nh, "linear/xy")); + pid_.linear.y.init(ros::NodeHandle(controller_nh, "linear/xy")); + pid_.linear.z.init(ros::NodeHandle(controller_nh, "linear/z")); + pid_.angular.x.init(ros::NodeHandle(controller_nh, "angular/xy")); + pid_.angular.y.init(ros::NodeHandle(controller_nh, "angular/xy")); + pid_.angular.z.init(ros::NodeHandle(controller_nh, "angular/z")); + + // load other parameters + controller_nh.getParam("auto_engage", auto_engage_ = true); + controller_nh.getParam("limits/load_factor", load_factor_limit = 1.5); + controller_nh.getParam("limits/force/z", limits_.force.z); + controller_nh.getParam("limits/torque/xy", limits_.torque.x); + controller_nh.getParam("limits/torque/xy", limits_.torque.y); + controller_nh.getParam("limits/torque/z", limits_.torque.z); + root_nh.param("base_link_frame", base_link_frame_, "base_link"); + + // get mass and inertia from QuadrotorInterface + interface->getMassAndInertia(mass_, inertia_); + + command_given_in_stabilized_frame_ = false; + + return true; + } + + void reset() + { + pid_.linear.x.reset(); + pid_.linear.y.reset(); + pid_.linear.z.reset(); + pid_.angular.x.reset(); + pid_.angular.y.reset(); + pid_.angular.z.reset(); + + wrench_.wrench.force.x = 0.0; + wrench_.wrench.force.y = 0.0; + wrench_.wrench.force.z = 0.0; + wrench_.wrench.torque.x = 0.0; + wrench_.wrench.torque.y = 0.0; + wrench_.wrench.torque.z = 0.0; + + linear_z_control_error_ = 0.0; + motors_running_ = false; + } + + void twistCommandCallback(const geometry_msgs::TwistStampedConstPtr& command) + { + boost::mutex::scoped_lock lock(command_mutex_); + + command_ = *command; + if (command_.header.stamp.isZero()) command_.header.stamp = ros::Time::now(); + command_given_in_stabilized_frame_ = false; + + // start controller if it not running + if (!isRunning()) this->startRequest(command_.header.stamp); + } + + void cmd_velCommandCallback(const geometry_msgs::TwistConstPtr& command) + { + boost::mutex::scoped_lock lock(command_mutex_); + + command_.twist = *command; + command_.header.stamp = ros::Time::now(); + command_given_in_stabilized_frame_ = true; + + // start controller if it not running + if (!isRunning()) this->startRequest(command_.header.stamp); + } + + bool engageCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&) + { + boost::mutex::scoped_lock lock(command_mutex_); + + ROS_INFO_NAMED("twist_controller", "Engaging motors!"); + motors_running_ = true; + return true; + } + + bool shutdownCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&) + { + boost::mutex::scoped_lock lock(command_mutex_); + + ROS_INFO_NAMED("twist_controller", "Shutting down motors!"); + motors_running_ = false; + return true; + } + + void starting(const ros::Time &time) + { + reset(); + wrench_output_->start(); + } + + void stopping(const ros::Time &time) + { + wrench_output_->stop(); + } + + void update(const ros::Time& time, const ros::Duration& period) + { + boost::mutex::scoped_lock lock(command_mutex_); + + // Get twist command input + if (twist_input_->connected() && twist_input_->enabled()) { + command_.twist = twist_input_->getCommand(); + command_given_in_stabilized_frame_ = false; + } + + // Get current state and command + Twist command = command_.twist; + Twist twist = twist_->twist(); + Twist twist_body; + twist_body.linear = pose_->toBody(twist.linear); + twist_body.angular = pose_->toBody(twist.angular); + + // Transform to world coordinates if necessary (yaw only) + if (command_given_in_stabilized_frame_) { + double yaw = pose_->getYaw(); + Twist transformed = command; + transformed.linear.x = cos(yaw) * command.linear.x - sin(yaw) * command.linear.y; + transformed.linear.y = sin(yaw) * command.linear.x + cos(yaw) * command.linear.y; + transformed.angular.x = cos(yaw) * command.angular.x - sin(yaw) * command.angular.y; + transformed.angular.y = sin(yaw) * command.angular.x + cos(yaw) * command.angular.y; + command = transformed; + } + + // Get gravity and load factor + const double gravity = 9.8065; + double load_factor = 1. / ( pose_->pose().orientation.w * pose_->pose().orientation.w + - pose_->pose().orientation.x * pose_->pose().orientation.x + - pose_->pose().orientation.y * pose_->pose().orientation.y + + pose_->pose().orientation.z * pose_->pose().orientation.z ); + // Note: load_factor could be NaN or Inf...? + if (load_factor_limit > 0.0 && !(load_factor < load_factor_limit)) load_factor = load_factor_limit; + + // Auto engage/shutdown + if (auto_engage_) { + if (!motors_running_ && command.linear.z > 0.1 && load_factor > 0.0) { + motors_running_ = true; + ROS_INFO_NAMED("twist_controller", "Engaging motors!"); + } else if (motors_running_ && command.linear.z < -0.1 /* && (twist.linear.z > -0.1 && twist.linear.z < 0.1) */) { + double shutdown_limit = 0.25 * std::min(command.linear.z, -0.5); + if (linear_z_control_error_ > 0.0) linear_z_control_error_ = 0.0; // positive control errors should not affect shutdown + if (pid_.linear.z.getFilteredControlError(linear_z_control_error_, 5.0, period) < shutdown_limit) { + motors_running_ = false; + ROS_INFO_NAMED("twist_controller", "Shutting down motors!"); + } else { + ROS_DEBUG_STREAM_NAMED("twist_controller", "z control error = " << linear_z_control_error_ << " >= " << shutdown_limit); + } + } else { + linear_z_control_error_ = 0.0; + } + + // flip over? + if (motors_running_ && load_factor < 0.0) { + motors_running_ = false; + ROS_WARN_NAMED("twist_controller", "Shutting down motors due to flip over!"); + } + } + + // Update output + if (motors_running_) { + Vector3 acceleration_command; + acceleration_command.x = pid_.linear.x.update(command.linear.x, twist.linear.x, acceleration_->acceleration().x, period); + acceleration_command.y = pid_.linear.y.update(command.linear.y, twist.linear.y, acceleration_->acceleration().y, period); + acceleration_command.z = pid_.linear.z.update(command.linear.z, twist.linear.z, acceleration_->acceleration().z, period) + gravity; + Vector3 acceleration_command_body = pose_->toBody(acceleration_command); + + ROS_DEBUG_STREAM_NAMED("twist_controller", "twist.linear: [" << twist.linear.x << " " << twist.linear.y << " " << twist.linear.z << "]"); + ROS_DEBUG_STREAM_NAMED("twist_controller", "twist_body.angular: [" << twist_body.angular.x << " " << twist_body.angular.y << " " << twist_body.angular.z << "]"); + ROS_DEBUG_STREAM_NAMED("twist_controller", "twist_command.linear: [" << command.linear.x << " " << command.linear.y << " " << command.linear.z << "]"); + ROS_DEBUG_STREAM_NAMED("twist_controller", "twist_command.angular: [" << command.angular.x << " " << command.angular.y << " " << command.angular.z << "]"); + ROS_DEBUG_STREAM_NAMED("twist_controller", "acceleration: [" << acceleration_->acceleration().x << " " << acceleration_->acceleration().y << " " << acceleration_->acceleration().z << "]"); + ROS_DEBUG_STREAM_NAMED("twist_controller", "acceleration_command_world: [" << acceleration_command.x << " " << acceleration_command.y << " " << acceleration_command.z << "]"); + ROS_DEBUG_STREAM_NAMED("twist_controller", "acceleration_command_body: [" << acceleration_command_body.x << " " << acceleration_command_body.y << " " << acceleration_command_body.z << "]"); + + wrench_.wrench.torque.x = inertia_[0] * pid_.angular.x.update(-acceleration_command_body.y / gravity, 0.0, twist_body.angular.x, period); + wrench_.wrench.torque.y = inertia_[1] * pid_.angular.y.update( acceleration_command_body.x / gravity, 0.0, twist_body.angular.y, period); + wrench_.wrench.torque.z = inertia_[2] * pid_.angular.z.update( command.angular.z, twist.angular.z, 0.0, period); + wrench_.wrench.force.x = 0.0; + wrench_.wrench.force.y = 0.0; + wrench_.wrench.force.z = mass_ * ((acceleration_command.z - gravity) * load_factor + gravity); + + if (limits_.force.z > 0.0 && wrench_.wrench.force.z > limits_.force.z) wrench_.wrench.force.z = limits_.force.z; + if (wrench_.wrench.force.z <= std::numeric_limits::min()) wrench_.wrench.force.z = std::numeric_limits::min(); + if (limits_.torque.x > 0.0) { + if (wrench_.wrench.torque.x > limits_.torque.x) wrench_.wrench.torque.x = limits_.torque.x; + if (wrench_.wrench.torque.x < -limits_.torque.x) wrench_.wrench.torque.x = -limits_.torque.x; + } + if (limits_.torque.y > 0.0) { + if (wrench_.wrench.torque.y > limits_.torque.y) wrench_.wrench.torque.y = limits_.torque.y; + if (wrench_.wrench.torque.y < -limits_.torque.y) wrench_.wrench.torque.y = -limits_.torque.y; + } + if (limits_.torque.z > 0.0) { + if (wrench_.wrench.torque.z > limits_.torque.z) wrench_.wrench.torque.z = limits_.torque.z; + if (wrench_.wrench.torque.z < -limits_.torque.z) wrench_.wrench.torque.z = -limits_.torque.z; + } + + ROS_DEBUG_STREAM_NAMED("twist_controller", "wrench_command.force: [" << wrench_.wrench.force.x << " " << wrench_.wrench.force.y << " " << wrench_.wrench.force.z << "]"); + ROS_DEBUG_STREAM_NAMED("twist_controller", "wrench_command.torque: [" << wrench_.wrench.torque.x << " " << wrench_.wrench.torque.y << " " << wrench_.wrench.torque.z << "]"); + + } else { + reset(); + } + + // set wrench output + wrench_.header.stamp = time; + wrench_.header.frame_id = base_link_frame_; + wrench_output_->setCommand(wrench_.wrench); + } + +private: + PoseHandlePtr pose_; + TwistHandlePtr twist_; + AccelerationHandlePtr acceleration_; + TwistCommandHandlePtr twist_input_; + WrenchCommandHandlePtr wrench_output_; + + ros::NodeHandle node_handle_; + ros::Subscriber twist_subscriber_; + ros::Subscriber cmd_vel_subscriber_; + ros::ServiceServer engage_service_server_; + ros::ServiceServer shutdown_service_server_; + + geometry_msgs::TwistStamped command_; + geometry_msgs::WrenchStamped wrench_; + bool command_given_in_stabilized_frame_; + std::string base_link_frame_; + + struct { + struct { + PID x; + PID y; + PID z; + } linear, angular; + } pid_; + + geometry_msgs::Wrench limits_; + bool auto_engage_; + double load_factor_limit; + double mass_; + double inertia_[3]; + + bool motors_running_; + double linear_z_control_error_; + boost::mutex command_mutex_; + +}; + +} // namespace hector_quadrotor_controller + +#include +PLUGINLIB_EXPORT_CLASS(hector_quadrotor_controller::TwistController, controller_interface::ControllerBase) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/twist_controller.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/twist_controller.cpp new file mode 100644 index 0000000..ef9bc31 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller/src/twist_controller.cpp @@ -0,0 +1,372 @@ +//================================================================================================= +// Copyright (c) 2013, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include +#include + +#include + +#include +#include +#include + +#include +#include + +#include + +#include + +#include //add by zhangshuai, used to timing +#include + +namespace hector_quadrotor_controller +{ + +using namespace controller_interface; +// using namespace std; + +class TwistController : public controller_interface::Controller +{ + +public: + TwistController() + { + } + + ~TwistController() + { + } + + bool init(QuadrotorInterface *interface, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) + { + // get interface handles + pose_ = interface->getPose(); + twist_ = interface->getTwist(); + acceleration_ = interface->getAcceleration(); + twist_input_ = interface->addInput("twist"); + wrench_output_ = interface->addOutput("wrench"); + node_handle_ = root_nh; + + // subscribe to commanded twist (geometry_msgs/TwistStamped) and cmd_vel (geometry_msgs/Twist) + twist_subscriber_ = node_handle_.subscribe("command/twist", 1, boost::bind(&TwistController::twistCommandCallback, this, _1)); + cmd_vel_subscriber_ = node_handle_.subscribe("/cmd_vel", 1, boost::bind(&TwistController::cmd_velCommandCallback, this, _1)); + + // engage/shutdown service servers + engage_service_server_ = node_handle_.advertiseService("engage", boost::bind(&TwistController::engageCallback, this, _1, _2)); + shutdown_service_server_ = node_handle_.advertiseService("shutdown", boost::bind(&TwistController::shutdownCallback, this, _1, _2)); + + // initialize PID controllers + pid_.linear.x.init(ros::NodeHandle(controller_nh, "linear/xy")); + pid_.linear.y.init(ros::NodeHandle(controller_nh, "linear/xy")); + pid_.linear.z.init(ros::NodeHandle(controller_nh, "linear/z")); + pid_.angular.x.init(ros::NodeHandle(controller_nh, "angular/xy")); + pid_.angular.y.init(ros::NodeHandle(controller_nh, "angular/xy")); + pid_.angular.z.init(ros::NodeHandle(controller_nh, "angular/z")); + + // load other parameters + controller_nh.getParam("auto_engage", auto_engage_ = true); + controller_nh.getParam("limits/load_factor", load_factor_limit = 1.5); + controller_nh.getParam("limits/force/z", limits_.force.z); + controller_nh.getParam("limits/torque/xy", limits_.torque.x); + controller_nh.getParam("limits/torque/xy", limits_.torque.y); + controller_nh.getParam("limits/torque/z", limits_.torque.z); + root_nh.param("base_link_frame", base_link_frame_, "base_link"); + + // get mass and inertia from QuadrotorInterface + interface->getMassAndInertia(mass_, inertia_); + + command_given_in_stabilized_frame_ = false; + + return true; + } + + void reset() + { + pid_.linear.x.reset(); + pid_.linear.y.reset(); + pid_.linear.z.reset(); + pid_.angular.x.reset(); + pid_.angular.y.reset(); + pid_.angular.z.reset(); + + wrench_.wrench.force.x = 0.0; + wrench_.wrench.force.y = 0.0; + wrench_.wrench.force.z = 0.0; + wrench_.wrench.torque.x = 0.0; + wrench_.wrench.torque.y = 0.0; + wrench_.wrench.torque.z = 0.0; + + linear_z_control_error_ = 0.0; + motors_running_ = false; + } + + void twistCommandCallback(const geometry_msgs::TwistStampedConstPtr &command) + { + boost::mutex::scoped_lock lock(command_mutex_); + + command_ = *command; + if (command_.header.stamp.isZero()) + command_.header.stamp = ros::Time::now(); + command_given_in_stabilized_frame_ = false; + + // start controller if it not running + if (!isRunning()) + this->startRequest(command_.header.stamp); + } + + void cmd_velCommandCallback(const geometry_msgs::TwistConstPtr &command) + { + boost::mutex::scoped_lock lock(command_mutex_); + + command_.twist = *command; + command_.header.stamp = ros::Time::now(); + command_given_in_stabilized_frame_ = true; + + // start controller if it not running + if (!isRunning()) + this->startRequest(command_.header.stamp); + } + + bool engageCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &) + { + boost::mutex::scoped_lock lock(command_mutex_); + + ROS_INFO_NAMED("twist_controller", "Engaging motors!"); + motors_running_ = true; + return true; + } + + bool shutdownCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &) + { + boost::mutex::scoped_lock lock(command_mutex_); + + ROS_INFO_NAMED("twist_controller", "Shutting down motors!"); + motors_running_ = false; + return true; + } + + void starting(const ros::Time &time) + { + reset(); + wrench_output_->start(); + } + + void stopping(const ros::Time &time) + { + wrench_output_->stop(); + } + + void update(const ros::Time &time, const ros::Duration &period) + { + boost::mutex::scoped_lock lock(command_mutex_); + + // Get twist command input + if (twist_input_->connected() && twist_input_->enabled()) + { + command_.twist = twist_input_->getCommand(); + command_given_in_stabilized_frame_ = false; + } + + // Get current state and command + Twist command = command_.twist; + Twist twist = twist_->twist(); + Twist twist_body; + twist_body.linear = pose_->toBody(twist.linear); + twist_body.angular = pose_->toBody(twist.angular); + + // Transform to world coordinates if necessary (yaw only) + if (command_given_in_stabilized_frame_) + { + double yaw = pose_->getYaw(); + Twist transformed = command; + transformed.linear.x = cos(yaw) * command.linear.x - sin(yaw) * command.linear.y; + transformed.linear.y = sin(yaw) * command.linear.x + cos(yaw) * command.linear.y; + transformed.angular.x = cos(yaw) * command.angular.x - sin(yaw) * command.angular.y; + transformed.angular.y = sin(yaw) * command.angular.x + cos(yaw) * command.angular.y; + command = transformed; + } + + // Get gravity and load factor + const double gravity = 9.8065; + double load_factor = 1. / (pose_->pose().orientation.w * pose_->pose().orientation.w - pose_->pose().orientation.x * pose_->pose().orientation.x - pose_->pose().orientation.y * pose_->pose().orientation.y + pose_->pose().orientation.z * pose_->pose().orientation.z); + // Note: load_factor could be NaN or Inf...? + if (load_factor_limit > 0.0 && !(load_factor < load_factor_limit)) + load_factor = load_factor_limit; + + // Auto engage/shutdown + if (auto_engage_) + { + if (!motors_running_ && command.linear.z > 0.1 && load_factor > 0.0) + { + motors_running_ = true; + ROS_INFO_NAMED("twist_controller", "Engaging motors!"); + } + else if (motors_running_ && command.linear.z < -0.1 /* && (twist.linear.z > -0.1 && twist.linear.z < 0.1) */) + { + double shutdown_limit = 0.25 * std::min(command.linear.z, -0.5); + if (linear_z_control_error_ > 0.0) + linear_z_control_error_ = 0.0; // positive control errors should not affect shutdown + if (pid_.linear.z.getFilteredControlError(linear_z_control_error_, 5.0, period) < shutdown_limit) + { + motors_running_ = false; + ROS_INFO_NAMED("twist_controller", "Shutting down motors!"); + } + else + { + ROS_DEBUG_STREAM_NAMED("twist_controller", "z control error = " << linear_z_control_error_ << " >= " << shutdown_limit); + } + } + else + { + linear_z_control_error_ = 0.0; + } + + // flip over? + if (motors_running_ && load_factor < 0.0) + { + motors_running_ = false; + ROS_WARN_NAMED("twist_controller", "Shutting down motors due to flip over!"); + } + } + + // Update output + if (motors_running_) + { + Vector3 acceleration_command; + boost::timer t;//声明计时器对象并开始计时 add by zhangshuai + acceleration_command.x = pid_.linear.x.update(command.linear.x, twist.linear.x, acceleration_->acceleration().x, period); + // std::cout<<"è¿è¡Œæ—¶é—´ï¼š"<acceleration().y, period); + acceleration_command.z = pid_.linear.z.update(command.linear.z, twist.linear.z, acceleration_->acceleration().z, period) + gravity; + Vector3 acceleration_command_body = pose_->toBody(acceleration_command); + + ROS_DEBUG_STREAM_NAMED("twist_controller", "twist.linear: [" << twist.linear.x << " " << twist.linear.y << " " << twist.linear.z << "]"); + ROS_DEBUG_STREAM_NAMED("twist_controller", "twist_body.angular: [" << twist_body.angular.x << " " << twist_body.angular.y << " " << twist_body.angular.z << "]"); + ROS_DEBUG_STREAM_NAMED("twist_controller", "twist_command.linear: [" << command.linear.x << " " << command.linear.y << " " << command.linear.z << "]"); + ROS_DEBUG_STREAM_NAMED("twist_controller", "twist_command.angular: [" << command.angular.x << " " << command.angular.y << " " << command.angular.z << "]"); + ROS_DEBUG_STREAM_NAMED("twist_controller", "acceleration: [" << acceleration_->acceleration().x << " " << acceleration_->acceleration().y << " " << acceleration_->acceleration().z << "]"); + ROS_DEBUG_STREAM_NAMED("twist_controller", "acceleration_command_world: [" << acceleration_command.x << " " << acceleration_command.y << " " << acceleration_command.z << "]"); + ROS_DEBUG_STREAM_NAMED("twist_controller", "acceleration_command_body: [" << acceleration_command_body.x << " " << acceleration_command_body.y << " " << acceleration_command_body.z << "]"); + + wrench_.wrench.torque.x = inertia_[0] * pid_.angular.x.update(-acceleration_command_body.y / gravity, 0.0, twist_body.angular.x, period); + wrench_.wrench.torque.y = inertia_[1] * pid_.angular.y.update(acceleration_command_body.x / gravity, 0.0, twist_body.angular.y, period); + wrench_.wrench.torque.z = inertia_[2] * pid_.angular.z.update(command.angular.z, twist.angular.z, 0.0, period); + wrench_.wrench.force.x = 0.0; + wrench_.wrench.force.y = 0.0; + wrench_.wrench.force.z = mass_ * ((acceleration_command.z - gravity) * load_factor + gravity); + + if (limits_.force.z > 0.0 && wrench_.wrench.force.z > limits_.force.z) + wrench_.wrench.force.z = limits_.force.z; + if (wrench_.wrench.force.z <= std::numeric_limits::min()) + wrench_.wrench.force.z = std::numeric_limits::min(); + if (limits_.torque.x > 0.0) + { + if (wrench_.wrench.torque.x > limits_.torque.x) + wrench_.wrench.torque.x = limits_.torque.x; + if (wrench_.wrench.torque.x < -limits_.torque.x) + wrench_.wrench.torque.x = -limits_.torque.x; + } + if (limits_.torque.y > 0.0) + { + if (wrench_.wrench.torque.y > limits_.torque.y) + wrench_.wrench.torque.y = limits_.torque.y; + if (wrench_.wrench.torque.y < -limits_.torque.y) + wrench_.wrench.torque.y = -limits_.torque.y; + } + if (limits_.torque.z > 0.0) + { + if (wrench_.wrench.torque.z > limits_.torque.z) + wrench_.wrench.torque.z = limits_.torque.z; + if (wrench_.wrench.torque.z < -limits_.torque.z) + wrench_.wrench.torque.z = -limits_.torque.z; + } + + ROS_DEBUG_STREAM_NAMED("twist_controller", "wrench_command.force: [" << wrench_.wrench.force.x << " " << wrench_.wrench.force.y << " " << wrench_.wrench.force.z << "]"); + ROS_DEBUG_STREAM_NAMED("twist_controller", "wrench_command.torque: [" << wrench_.wrench.torque.x << " " << wrench_.wrench.torque.y << " " << wrench_.wrench.torque.z << "]"); + } + else + { + reset(); + } + + // set wrench output + wrench_.header.stamp = time; + wrench_.header.frame_id = base_link_frame_; + wrench_output_->setCommand(wrench_.wrench); + } + +private: + PoseHandlePtr pose_; + TwistHandlePtr twist_; + AccelerationHandlePtr acceleration_; + TwistCommandHandlePtr twist_input_; + WrenchCommandHandlePtr wrench_output_; + + ros::NodeHandle node_handle_; + ros::Subscriber twist_subscriber_; + ros::Subscriber cmd_vel_subscriber_; + ros::ServiceServer engage_service_server_; + ros::ServiceServer shutdown_service_server_; + + geometry_msgs::TwistStamped command_; + geometry_msgs::WrenchStamped wrench_; + bool command_given_in_stabilized_frame_; + std::string base_link_frame_; + + struct + { + struct + { + PID x; + PID y; + PID z; + } linear, angular; + } pid_; + + geometry_msgs::Wrench limits_; + bool auto_engage_; + double load_factor_limit; + double mass_; + double inertia_[3]; + + bool motors_running_; + double linear_z_control_error_; + boost::mutex command_mutex_; + + // std::ostream cout1; + // cout1<<"è¿è¡Œæ—¶é—´ï¼š"< +#include + +#include +#include +#include + +#include +#include + +namespace hector_quadrotor_controller_gazebo { + +using namespace hector_quadrotor_controller; +using namespace hardware_interface; +using namespace gazebo_ros_control; + +class QuadrotorHardwareSim : public RobotHWSim, public QuadrotorInterface +{ +public: + QuadrotorHardwareSim(); + virtual ~QuadrotorHardwareSim(); + + virtual const ros::Time &getTimestamp() { return header_.stamp; } + + virtual PoseHandlePtr getPose() { return PoseHandlePtr(new PoseHandle(this, &pose_)); } + virtual TwistHandlePtr getTwist() { return TwistHandlePtr(new TwistHandle(this, &twist_)); } + virtual AccelerationHandlePtr getAcceleration() { return AccelerationHandlePtr(new AccelerationHandle(this, &acceleration_)); } + virtual ImuHandlePtr getSensorImu() { return ImuHandlePtr(new ImuHandle(this, &imu_)); } + virtual MotorStatusHandlePtr getMotorStatus() { return MotorStatusHandlePtr(new MotorStatusHandle(this, &motor_status_)); } + + virtual bool getMassAndInertia(double &mass, double inertia[3]); + + virtual bool initSim( + const std::string& robot_namespace, + ros::NodeHandle model_nh, + gazebo::physics::ModelPtr parent_model, + const urdf::Model *const urdf_model, + std::vector transmissions); + + virtual void readSim(ros::Time time, ros::Duration period); + + virtual void writeSim(ros::Time time, ros::Duration period); + +private: + void stateCallback(const nav_msgs::OdometryConstPtr &state); + void imuCallback(const sensor_msgs::ImuConstPtr &imu); + void motorStatusCallback(const hector_uav_msgs::MotorStatusConstPtr &motor_status); + +protected: + std_msgs::Header header_; + Pose pose_; + Twist twist_; + Vector3 acceleration_; + Imu imu_; + MotorStatus motor_status_; + std::string base_link_frame_, world_frame_; + + WrenchCommandHandlePtr wrench_output_; + MotorCommandHandlePtr motor_output_; + + gazebo::physics::ModelPtr model_; + gazebo::physics::LinkPtr link_; + gazebo::physics::PhysicsEnginePtr physics_; + + gazebo::math::Pose gz_pose_; + gazebo::math::Vector3 gz_velocity_, gz_acceleration_, gz_angular_velocity_; + + ros::CallbackQueue callback_queue_; + ros::Subscriber subscriber_state_; + ros::Subscriber subscriber_imu_; + ros::Subscriber subscriber_motor_status_; + ros::Publisher publisher_wrench_command_; + ros::Publisher publisher_motor_command_; +}; + +} // namespace hector_quadrotor_controller_gazebo + +#endif // HECTOR_QUADROTOR_CONTROLLER_QUADROTOR_HARDWARE_GAZEBO_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller_gazebo/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller_gazebo/package.xml new file mode 100644 index 0000000..dbefdfb --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller_gazebo/package.xml @@ -0,0 +1,24 @@ + + + hector_quadrotor_controller_gazebo + 0.3.5 + The hector_quadrotor_controller_gazebo package implements the ros_control RobotHWSim interface for the quadrotor controller in package hector_quadrotor_controller. + Johannes Meyer + + BSD + + http://ros.org/wiki/hector_quadrotor_controller_gazebo + https://github.com/tu-darmstadt-ros-pkg/hector_quadrotor/issues + + Johannes Meyer + + catkin + gazebo_ros_control + hector_quadrotor_controller + gazebo_ros_control + hector_quadrotor_controller + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller_gazebo/quadrotor_controller_gazebo.xml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller_gazebo/quadrotor_controller_gazebo.xml new file mode 100644 index 0000000..b621e3c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller_gazebo/quadrotor_controller_gazebo.xml @@ -0,0 +1,7 @@ + + + + This class represents the quadrotor hardware in Gazebo for the gazebo_ros_control plugin. + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller_gazebo/src/quadrotor_hardware_gazebo.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller_gazebo/src/quadrotor_hardware_gazebo.cpp new file mode 100644 index 0000000..1ad4654 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_controller_gazebo/src/quadrotor_hardware_gazebo.cpp @@ -0,0 +1,223 @@ +//================================================================================================= +// Copyright (c) 2013, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include + +#include + +namespace hector_quadrotor_controller_gazebo { + +QuadrotorHardwareSim::QuadrotorHardwareSim() +{ + this->registerInterface(static_cast(this)); + + wrench_output_ = addInput("wrench"); + motor_output_ = addInput("motor"); +} + +QuadrotorHardwareSim::~QuadrotorHardwareSim() +{ + +} + +bool QuadrotorHardwareSim::initSim( + const std::string& robot_namespace, + ros::NodeHandle model_nh, + gazebo::physics::ModelPtr parent_model, + const urdf::Model *const urdf_model, + std::vector transmissions) +{ + ros::NodeHandle param_nh(model_nh, "controller"); + + // store parent model pointer + model_ = parent_model; + link_ = model_->GetLink(); + physics_ = model_->GetWorld()->GetPhysicsEngine(); + + model_nh.param("world_frame", world_frame_, "world"); + model_nh.param("base_link_frame", base_link_frame_, "base_link"); + + // subscribe state + std::string state_topic; + param_nh.getParam("state_topic", state_topic); + if (!state_topic.empty()) { + ros::SubscribeOptions ops = ros::SubscribeOptions::create(state_topic, 1, boost::bind(&QuadrotorHardwareSim::stateCallback, this, _1), ros::VoidConstPtr(), &callback_queue_); + subscriber_state_ = model_nh.subscribe(ops); + + gzlog << "[hector_quadrotor_controller_gazebo] Using topic '" << subscriber_state_.getTopic() << "' as state input for control" << std::endl; + } else { + gzlog << "[hector_quadrotor_controller_gazebo] Using ground truth from Gazebo as state input for control" << std::endl; + } + + // subscribe imu + std::string imu_topic; + param_nh.getParam("imu_topic", imu_topic); + if (!imu_topic.empty()) { + ros::SubscribeOptions ops = ros::SubscribeOptions::create(imu_topic, 1, boost::bind(&QuadrotorHardwareSim::imuCallback, this, _1), ros::VoidConstPtr(), &callback_queue_); + subscriber_imu_ = model_nh.subscribe(ops); + gzlog << "[hector_quadrotor_controller_gazebo] Using topic '" << subscriber_imu_.getTopic() << "' as imu input for control" << std::endl; + } else { + gzlog << "[hector_quadrotor_controller_gazebo] Using ground truth from Gazebo as imu input for control" << std::endl; + } + + // subscribe motor_status + { + ros::SubscribeOptions ops = ros::SubscribeOptions::create("motor_status", 1, boost::bind(&QuadrotorHardwareSim::motorStatusCallback, this, _1), ros::VoidConstPtr(), &callback_queue_); + subscriber_motor_status_ = model_nh.subscribe(ops); + } + + // publish wrench + { + ros::AdvertiseOptions ops = ros::AdvertiseOptions::create("command/wrench", 1, ros::SubscriberStatusCallback(), ros::SubscriberStatusCallback(), ros::VoidConstPtr(), &callback_queue_); + publisher_wrench_command_ = model_nh.advertise(ops); + } + + // publish motor command + { + ros::AdvertiseOptions ops = ros::AdvertiseOptions::create("command/motor", 1, ros::SubscriberStatusCallback(), ros::SubscriberStatusCallback(), ros::VoidConstPtr(), &callback_queue_); + publisher_motor_command_ = model_nh.advertise(ops); + } + + return true; +} + +bool QuadrotorHardwareSim::getMassAndInertia(double &mass, double inertia[3]) { + if (!link_) return false; + mass = link_->GetInertial()->GetMass(); + gazebo::math::Vector3 Inertia = link_->GetInertial()->GetPrincipalMoments(); + inertia[0] = Inertia.x; + inertia[1] = Inertia.y; + inertia[2] = Inertia.z; + return true; +} + +void QuadrotorHardwareSim::stateCallback(const nav_msgs::OdometryConstPtr &state) { + // calculate acceleration + if (!header_.stamp.isZero() && !state->header.stamp.isZero()) { + const double acceleration_time_constant = 0.1; + double dt((state->header.stamp - header_.stamp).toSec()); + if (dt > 0.0) { + acceleration_.x = ((state->twist.twist.linear.x - twist_.linear.x) + acceleration_time_constant * acceleration_.x) / (dt + acceleration_time_constant); + acceleration_.y = ((state->twist.twist.linear.y - twist_.linear.y) + acceleration_time_constant * acceleration_.y) / (dt + acceleration_time_constant); + acceleration_.z = ((state->twist.twist.linear.z - twist_.linear.z) + acceleration_time_constant * acceleration_.z) / (dt + acceleration_time_constant); + } + } + + header_ = state->header; + pose_ = state->pose.pose; + twist_ = state->twist.twist; +} + +void QuadrotorHardwareSim::imuCallback(const sensor_msgs::ImuConstPtr &imu) { + imu_ = *imu; +} + +void QuadrotorHardwareSim::motorStatusCallback(const hector_uav_msgs::MotorStatusConstPtr &motor_status) { + motor_status_ = *motor_status; +} + +void QuadrotorHardwareSim::readSim(ros::Time time, ros::Duration period) +{ + // call all available subscriber callbacks now + callback_queue_.callAvailable(); + + // read state from Gazebo + const double acceleration_time_constant = 0.1; + gz_pose_ = link_->GetWorldPose(); + gz_acceleration_ = ((link_->GetWorldLinearVel() - gz_velocity_) + acceleration_time_constant * gz_acceleration_) / (period.toSec() + acceleration_time_constant); + gz_velocity_ = link_->GetWorldLinearVel(); + gz_angular_velocity_ = link_->GetWorldAngularVel(); + + if (!subscriber_state_) { + header_.frame_id = world_frame_; + header_.stamp = time; + pose_.position.x = gz_pose_.pos.x; + pose_.position.y = gz_pose_.pos.y; + pose_.position.z = gz_pose_.pos.z; + pose_.orientation.w = gz_pose_.rot.w; + pose_.orientation.x = gz_pose_.rot.x; + pose_.orientation.y = gz_pose_.rot.y; + pose_.orientation.z = gz_pose_.rot.z; + twist_.linear.x = gz_velocity_.x; + twist_.linear.y = gz_velocity_.y; + twist_.linear.z = gz_velocity_.z; + twist_.angular.x = gz_angular_velocity_.x; + twist_.angular.y = gz_angular_velocity_.y; + twist_.angular.z = gz_angular_velocity_.z; + acceleration_.x = gz_acceleration_.x; + acceleration_.y = gz_acceleration_.y; + acceleration_.z = gz_acceleration_.z; + } + + if (!subscriber_imu_) { + imu_.orientation.w = gz_pose_.rot.w; + imu_.orientation.x = gz_pose_.rot.x; + imu_.orientation.y = gz_pose_.rot.y; + imu_.orientation.z = gz_pose_.rot.z; + + gazebo::math::Vector3 gz_angular_velocity_body = gz_pose_.rot.RotateVectorReverse(gz_angular_velocity_); + imu_.angular_velocity.x = gz_angular_velocity_body.x; + imu_.angular_velocity.y = gz_angular_velocity_body.y; + imu_.angular_velocity.z = gz_angular_velocity_body.z; + + gazebo::math::Vector3 gz_linear_acceleration_body = gz_pose_.rot.RotateVectorReverse(gz_acceleration_ - physics_->GetGravity()); + imu_.linear_acceleration.x = gz_linear_acceleration_body.x; + imu_.linear_acceleration.y = gz_linear_acceleration_body.y; + imu_.linear_acceleration.z = gz_linear_acceleration_body.z; + } +} + +void QuadrotorHardwareSim::writeSim(ros::Time time, ros::Duration period) +{ + bool result_written = false; + + if (motor_output_->connected() && motor_output_->enabled()) { + publisher_motor_command_.publish(motor_output_->getCommand()); + result_written = true; + } + + if (wrench_output_->connected() && wrench_output_->enabled()) { + geometry_msgs::WrenchStamped wrench; + wrench.header.stamp = time; + wrench.header.frame_id = base_link_frame_; + wrench.wrench = wrench_output_->getCommand(); + publisher_wrench_command_.publish(wrench); + + if (!result_written) { + gazebo::math::Vector3 force(wrench.wrench.force.x, wrench.wrench.force.y, wrench.wrench.force.z); + gazebo::math::Vector3 torque(wrench.wrench.torque.x, wrench.wrench.torque.y, wrench.wrench.torque.z); + link_->AddRelativeForce(force); + link_->AddRelativeTorque(torque - link_->GetInertial()->GetCoG().Cross(force)); + } + } +} + +} // namespace hector_quadrotor_controller_gazebo + +#include +PLUGINLIB_EXPORT_CLASS(hector_quadrotor_controller_gazebo::QuadrotorHardwareSim, gazebo_ros_control::RobotHWSim) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/CHANGELOG.rst b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/CHANGELOG.rst new file mode 100644 index 0000000..44dfe6c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/CHANGELOG.rst @@ -0,0 +1,25 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package hector_quadrotor_demo +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.5 (2015-03-28) +------------------ + +0.3.4 (2015-02-22) +------------------ + +0.3.3 (2014-09-01) +------------------ + +0.3.2 (2014-03-30) +------------------ + +0.3.1 (2013-12-26) +------------------ +* updated demo launch files +* updated rviz configs +* Contributors: Johannes Meyer + +0.3.0 (2013-09-11) +------------------ +* Catkinized stack hector_quadrotor and integrated hector_quadrotor_demo package from former hector_quadrotor_apps stack diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/CMakeLists.txt new file mode 100644 index 0000000..3923701 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/CMakeLists.txt @@ -0,0 +1,67 @@ +cmake_minimum_required(VERSION 2.8.3) +project(hector_quadrotor_demo) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package() + + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +# install(TARGETS @{name} @{name}_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) +install(DIRECTORY rviz_cfg DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/launch/indoor_slam_gazebo.launch b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/launch/indoor_slam_gazebo.launch new file mode 100644 index 0000000..283f1c6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/launch/indoor_slam_gazebo.launch @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/launch/outdoor_flight_gazebo.launch b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/launch/outdoor_flight_gazebo.launch new file mode 100644 index 0000000..157f8cb --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/launch/outdoor_flight_gazebo.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/package.xml new file mode 100644 index 0000000..3d1e9f8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/package.xml @@ -0,0 +1,28 @@ + + hector_quadrotor_demo + 0.3.5 + hector_quadrotor_demo contains various launch files and needed dependencies for demonstration of the hector_quadrotor stack (indoor/outdoor flight in gazebo etc.) + Johannes Meyer + + BSD + + http://ros.org/wiki/hector_quadrotor_demo + https://github.com/tu-darmstadt-ros-pkg/hector_quadrotor/issues + + Stefan Kohlbrecher + + + catkin + + + + + hector_quadrotor_gazebo + hector_gazebo_worlds + hector_mapping + hector_geotiff + hector_trajectory_server + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/rviz_cfg/indoor_slam.rviz b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/rviz_cfg/indoor_slam.rviz new file mode 100644 index 0000000..8d1d818 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/rviz_cfg/indoor_slam.rviz @@ -0,0 +1,207 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + Splitter Ratio: 0.5 + Tree Height: 460 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.588679 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_cam_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_cam_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + laser0_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sonar_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Alpha: 0.7 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 2 + Min Value: 0 + Value: false + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 255; 255; 255 + Color Transformer: AxisColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.01 + Style: Points + Topic: /scan + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Camera + Enabled: true + Image Rendering: background and overlay + Image Topic: /front_cam/camera/image + Name: Camera + Overlay Alpha: 0.5 + Queue Size: 2 + Transport Hint: raw + Value: true + Visibility: + Grid: false + LaserScan: false + Map: false + Path: true + RobotModel: false + Value: true + Zoom Factor: 1 + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 170; 0; 0 + Enabled: true + Name: Path + Topic: /trajectory + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: world + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 7.23194 + Focal Point: + X: 1.66903 + Y: -0.217464 + Z: -0.674569 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.625399 + Target Frame: base_stabilized + Value: Orbit (rviz) + Yaw: 2.89041 + Saved: ~ +Window Geometry: + Camera: + collapsed: false + Displays: + collapsed: false + Height: 1026 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd00000004000000000000012e0000035ffc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000410000025b000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000002a2000000fe0000001600fffffffb0000000a0049006d00610067006501000002d9000000c70000000000000000000000010000010f0000035ffc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000410000035f000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000065f0000003efc0100000002fb0000000800540069006d006501000000000000065f000002f600fffffffb0000000800540069006d006501000000000000045000000000000000000000052b0000035f00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1631 + X: 49 + Y: 24 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/rviz_cfg/outdoor_flight.rviz b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/rviz_cfg/outdoor_flight.rviz new file mode 100644 index 0000000..4d25080 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_demo/rviz_cfg/outdoor_flight.rviz @@ -0,0 +1,192 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /LaserScan1/Autocompute Value Bounds1 + - /Camera1/Visibility1 + Splitter Ratio: 0.5 + Tree Height: 408 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.588679 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_cam_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_cam_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + laser0_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sonar_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 2 + Min Value: 0 + Value: false + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 255; 255; 255 + Color Transformer: AxisColor + Decay Time: 10 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.01 + Style: Points + Topic: /scan + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Camera + Enabled: true + Image Rendering: background and overlay + Image Topic: /front_cam/camera/image + Name: Camera + Overlay Alpha: 0.5 + Queue Size: 2 + Transport Hint: raw + Value: true + Visibility: + Grid: false + LaserScan: true + RobotModel: false + Value: true + Zoom Factor: 1 + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: world + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 28.8231 + Focal Point: + X: 0 + Y: 0 + Z: 0 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.630398 + Target Frame: + Value: Orbit (rviz) + Yaw: 1.16541 + Saved: ~ +Window Geometry: + Camera: + collapsed: false + Displays: + collapsed: false + Height: 1026 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd00000004000000000000012e0000035ffc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000004100000227000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d006500720061010000026e000001320000001600ffffff000000010000010f000002abfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000041000002ab000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000065f0000003efc0100000002fb0000000800540069006d006501000000000000065f000002f600fffffffb0000000800540069006d006501000000000000045000000000000000000000052b0000035f00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1631 + X: 49 + Y: 24 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/CHANGELOG.rst b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/CHANGELOG.rst new file mode 100644 index 0000000..eef8dd4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/CHANGELOG.rst @@ -0,0 +1,22 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package hector_quadrotor_description +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.5 (2015-03-28) +------------------ + +0.3.4 (2015-02-22) +------------------ + +0.3.3 (2014-09-01) +------------------ + +0.3.2 (2014-03-30) +------------------ + +0.3.1 (2013-12-26) +------------------ + +0.3.0 (2013-09-11) +------------------ +* Catkinized stack hector_quadrotor and integrated hector_quadrotor_demo package from former hector_quadrotor_apps stack diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/CMakeLists.txt new file mode 100644 index 0000000..a40f4f5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/CMakeLists.txt @@ -0,0 +1,68 @@ +cmake_minimum_required(VERSION 2.8.3) +project(hector_quadrotor_description) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package() + + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +# install(TARGETS @{name} @{name}_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) +install(DIRECTORY meshes DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) +install(DIRECTORY urdf DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/launch/xacrodisplay_quadrotor_base.launch b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/launch/xacrodisplay_quadrotor_base.launch new file mode 100644 index 0000000..3da01aa --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/launch/xacrodisplay_quadrotor_base.launch @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/box.gazebo.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/box.gazebo.xacro new file mode 100644 index 0000000..a69a4eb --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/box.gazebo.xacro @@ -0,0 +1,6 @@ + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/box.urdf.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/box.urdf.xacro new file mode 100644 index 0000000..284b929 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/box.urdf.xacro @@ -0,0 +1,12 @@ + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/box_base.urdf.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/box_base.urdf.xacro new file mode 100644 index 0000000..6b67ab7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/box_base.urdf.xacro @@ -0,0 +1,61 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/blender/quadrotor_base.blend b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/blender/quadrotor_base.blend new file mode 100644 index 0000000..af035a6 Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/blender/quadrotor_base.blend differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/blender/quadrotor_base_red_none.blend b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/blender/quadrotor_base_red_none.blend new file mode 100644 index 0000000..7bfe1f8 Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/blender/quadrotor_base_red_none.blend differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/blender/quadrotor_base_red_none.dae b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/blender/quadrotor_base_red_none.dae new file mode 100644 index 0000000..af9131f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/blender/quadrotor_base_red_none.dae @@ -0,0 +1,229 @@ + + + + + Blender User + Blender 2.79.0 + + 2018-10-19T14:54:03 + 2018-10-19T14:54:03 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 1 0 0.0106101 1 + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 0.2 0.2 0.2 1 + + + 0 0 0 1 + + + 0.4575223 0.4575223 0.4575223 1 + + + 1 1 1 1 + + + 33 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.05496641 0.05496641 0.05496641 1 + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.5925679 0.5925679 0.5925679 1 + + + 0.5 0.5 0.5 1 + + + 20 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + + + + + + + + + + + + + + + 0.8236175 0.673869 -1.366201 -0.8236175 0.6738689 -1.366201 -0.8236175 0.6852639 -1.361481 0.8236175 0.6852641 -1.361481 -0.8236175 0.6899839 -1.350086 0.8236175 0.689984 -1.350086 -0.8236175 0.6852639 -1.338691 0.8236175 0.685264 -1.338691 -0.8236175 0.6738689 -1.333971 0.8236175 0.673869 -1.333971 -0.8236175 0.6624739 -1.338691 0.8236175 0.662474 -1.338691 -0.8236175 0.657754 -1.350086 0.8236175 0.6577541 -1.350086 -0.8236175 0.6624739 -1.361481 0.8236175 0.6624741 -1.361481 0.8236175 0.673869 -1.350086 -0.8236175 0.6738689 -1.350086 0.8236174 -0.6738691 -1.350086 0.8236174 -0.662474 -1.361481 0.8236174 -0.6738691 -1.366201 -0.8236175 -0.6738691 -1.350086 -0.8236175 -0.6738691 -1.366201 -0.8236175 -0.6624742 -1.361481 0.8236174 -0.6577541 -1.350086 -0.8236175 -0.6577541 -1.350086 0.8236174 -0.662474 -1.338691 -0.8236175 -0.662474 -1.338691 0.8236174 -0.6738691 -1.333971 -0.8236175 -0.6738691 -1.333971 0.8236174 -0.6852641 -1.338691 -0.8236175 -0.6852641 -1.338691 0.8236174 -0.689984 -1.350086 -0.8236175 -0.689984 -1.350086 0.8236174 -0.6852641 -1.361481 -0.8236175 -0.6852641 -1.361481 0.5614412 0.08138328 0 0.5614412 0.07047998 -0.04069161 0.5614412 0.04069161 -0.07047998 0.5614412 0 -0.08138328 0.5614412 -0.04069161 -0.07047998 0.5614413 -0.07047998 -0.04069161 0.5614413 -0.08138328 0 0.5614413 -0.07047998 0.04069155 0.5614412 -0.04069167 0.07047992 0.560442 -0.001217126 0.08256208 0.560442 0.03947442 0.07165879 0.5614412 0.07047992 0.04069167 2.084521 0.08138328 0 2.084521 0.07048004 -0.04069155 2.084521 0.04069167 -0.07047986 2.084521 0 -0.08138328 2.084521 -0.04069155 -0.07047998 2.084521 -0.07047986 -0.04069167 2.084521 -0.08138328 0 2.084521 -0.07048004 0.04069155 2.084521 -0.04069173 0.07047992 2.084521 0 0.08138328 2.083522 0.03947442 0.07165884 2.084521 0.07047992 0.04069173 0.5614412 0 0 2.084521 0 0 0.6738689 0.6899839 -1.332763 0.6852639 0.6852639 -1.332763 0.6899839 0.6738689 -1.332763 0.6852639 0.6624739 -1.332763 0.6738689 0.657754 -1.332763 0.6624739 0.6624739 -1.332763 0.657754 0.6738689 -1.332763 0.6624739 0.6852639 -1.332763 0.2994973 0.3156122 -0.303241 0.3108922 0.3108922 -0.303241 0.3156122 0.2994973 -0.303241 0.3108922 0.2881023 -0.303241 0.2994973 0.2833823 -0.303241 0.2881022 0.2881023 -0.303241 0.2833823 0.2994973 -0.303241 0.2881023 0.3108922 -0.303241 0.6738689 0.6738689 -1.332763 0.2994973 0.2994973 -0.303241 0.3156121 -0.2994973 -0.303241 0.6899838 -0.673869 -1.332763 0.6852638 -0.6624739 -1.332763 0.3108922 -0.2881023 -0.303241 0.6738688 -0.657754 -1.332763 0.2994972 -0.2833823 -0.303241 0.6624738 -0.6624739 -1.332763 0.2881022 -0.2881023 -0.303241 0.6577539 -0.673869 -1.332763 0.2833822 -0.2994973 -0.303241 0.6624738 -0.6852639 -1.332763 0.2881022 -0.3108923 -0.303241 0.6738688 -0.6899839 -1.332763 0.2994972 -0.3156122 -0.303241 0.6852638 -0.6852639 -1.332763 0.3108922 -0.3108922 -0.303241 0.2994972 -0.2994973 -0.303241 0.6738688 -0.673869 -1.332763 -0.673869 -0.6738688 -1.332763 -0.685264 -0.6852638 -1.332763 -0.6738691 -0.6899837 -1.332763 -0.2994973 -0.2994972 -0.303241 -0.2994973 -0.3156121 -0.303241 -0.3108923 -0.3108922 -0.303241 -0.689984 -0.6738687 -1.332763 -0.3156123 -0.2994972 -0.303241 -0.685264 -0.6624737 -1.332763 -0.3108923 -0.2881022 -0.303241 -0.673869 -0.6577538 -1.332763 -0.2994973 -0.2833822 -0.303241 -0.662474 -0.6624737 -1.332763 -0.2881023 -0.2881022 -0.303241 -0.6577541 -0.6738688 -1.332763 -0.2833824 -0.2994972 -0.303241 -0.662474 -0.6852638 -1.332763 -0.2881023 -0.3108922 -0.303241 -0.3156121 0.2994973 -0.303241 -0.6899837 0.6738693 -1.332763 -0.6852637 0.662474 -1.332763 -0.3108922 0.2881023 -0.303241 -0.6738687 0.6577541 -1.332763 -0.2994971 0.2833824 -0.303241 -0.6624737 0.662474 -1.332763 -0.2881022 0.2881023 -0.303241 -0.6577537 0.6738691 -1.332763 -0.2833822 0.2994973 -0.303241 -0.6624737 0.6852641 -1.332763 -0.2881022 0.3108924 -0.303241 -0.6738685 0.689984 -1.332763 -0.2994971 0.3156123 -0.303241 -0.6852637 0.6852641 -1.332763 -0.3108922 0.3108923 -0.303241 -0.2994971 0.2994973 -0.303241 -0.6738687 0.6738691 -1.332763 1.969194 0 0.1871857 2.886225 -0.3798463 0.2218515 2.671059 -0.7018645 0.2218514 1.969194 0 0.2620601 2.349041 -0.9170302 0.2218514 1.969195 -0.9925863 0.2218514 1.589348 -0.9170302 0.2218514 1.26733 -0.7018646 0.2218514 1.052164 -0.3798465 0.2218515 0.9766083 -2.36674e-7 0.2218515 1.052164 0.379846 0.2218516 1.26733 0.7018642 0.2218517 1.589348 0.9170299 0.2218517 1.969194 0.992586 0.2218518 2.34904 0.91703 0.2218517 2.671058 0.7018645 0.2218517 2.886224 0.3798464 0.2218516 2.96178 3.25924e-7 0.2218515 0 -0.5614412 0 0.08138316 -0.5614412 0 0.07047986 -0.5614412 -0.04069161 -2.69139e-7 -2.084521 0 0.07047975 -2.084521 -0.04069155 0.08138298 -2.084521 0 0.04069155 -0.5614412 -0.07047998 0.04069143 -2.084521 -0.07047992 0 -0.5614412 -0.08138328 -1.69274e-7 -2.084521 -0.08138328 -0.04069167 -0.5614412 -0.07047998 -0.04069179 -2.084521 -0.07047998 -0.07048004 -0.5614413 -0.04069167 -0.07048016 -2.084521 -0.04069167 -0.08138334 -0.5614413 0 -0.08138352 -2.084521 0 -0.07048004 -0.5614413 0.04069161 -0.07048028 -2.084521 0.04069155 -0.04069173 -0.5614412 0.07047998 -0.04069197 -2.084521 0.07047992 -1.3514e-7 -0.5614412 0.08138328 -3.81294e-7 -2.084521 0.08138328 0.04069143 -0.5614412 0.07047998 0.04069125 -2.084521 0.07048004 0.07047986 -0.5614412 0.04069167 0.07047963 -2.084521 0.04069173 0.379846 -2.886224 0.2218516 -2.61752e-7 -1.969194 0.1871857 0 -2.96178 0.2218515 -3.25223e-7 -1.969194 0.2620601 0.7018641 -2.671058 0.2218517 0.9170297 -2.34904 0.2218517 0.9925858 -1.969194 0.2218517 0.9170296 -1.589348 0.2218517 0.701864 -1.26733 0.2218517 0.3798459 -1.052164 0.2218516 -3.6789e-7 -0.9766083 0.2218515 -0.3798466 -1.052164 0.2218514 -0.7018647 -1.26733 0.2218514 -0.9170304 -1.589348 0.2218513 -0.9925865 -1.969194 0.2218513 -0.9170305 -2.34904 0.2218513 -0.7018648 -2.671059 0.2218514 -0.3798467 -2.886225 0.2218514 -2.96178 4.69959e-7 0.2218515 -2.886225 0.3798471 0.2218514 -1.969194 5.26331e-7 0.1871857 -1.969194 5.89802e-7 0.2620601 -2.671059 0.7018652 0.2218514 -2.34904 0.9170308 0.2218513 -1.969194 0.9925867 0.2218513 -1.589348 0.9170306 0.2218513 -1.26733 0.7018649 0.2218514 -1.052164 0.3798468 0.2218514 -0.9766083 4.99106e-7 0.2218515 -1.052164 -0.3798457 0.2218516 -1.26733 -0.7018638 0.2218517 -1.589348 -0.9170294 0.2218517 -1.969194 -0.9925855 0.2218517 -2.349041 -0.9170294 0.2218517 -2.671058 -0.7018638 0.2218517 -2.886224 -0.3798456 0.2218516 -0.5614412 -0.07047981 0.04069167 -0.5614412 -0.0813831 0 -2.084521 -0.08138269 0 -2.084521 -0.07047933 0.04069173 -0.5614412 -0.04069137 0.07047998 -2.084521 -0.04069095 0.07048004 -0.5614412 2.10574e-7 0.08138328 -2.084521 6.61367e-7 0.08138328 -0.5614412 0.04069179 0.07047998 -2.084521 0.04069226 0.07047992 -0.5614413 0.0704801 0.04069161 -2.084521 0.07048058 0.04069155 -0.5614413 0.0813834 0 -2.084521 0.08138382 0 -0.5614413 0.0704801 -0.04069167 -2.084521 0.07048046 -0.04069167 -0.5614412 0.04069179 -0.07047998 -2.084521 0.04069209 -0.07047998 -0.5614412 1.54427e-7 -0.08138328 -2.084521 4.49347e-7 -0.08138328 -0.5614412 -0.04069149 -0.07047998 -2.084521 -0.04069113 -0.07047992 -0.5614412 -0.07047981 -0.04069161 -2.084521 -0.07047945 -0.04069155 -2.084521 5.49213e-7 0 -0.5614412 1.61804e-7 0 2.37238e-7 0.5614412 0 -0.08138304 0.5614412 0 -0.07047975 0.5614412 -0.04069161 8.29287e-7 2.084521 0 -0.07047921 2.084521 -0.04069155 -0.08138245 2.084521 0 -0.04069137 0.5614412 -0.07047998 -0.04069083 2.084521 -0.07047992 2.29861e-7 0.5614412 -0.08138328 7.29421e-7 2.084521 -0.08138328 0.04069185 0.5614412 -0.07047998 0.04069238 2.084521 -0.07047998 0.07048016 0.5614413 -0.04069167 0.07048076 2.084521 -0.04069167 0.08138352 0.5614413 0 0.08138412 2.084521 0 0.07048022 0.5614413 0.04069161 0.07048088 2.084521 0.04069155 0.04069191 0.5614412 0.07047998 0.04069256 2.084521 0.07047992 2.86009e-7 0.5614412 0.08138328 9.41441e-7 2.084521 0.08138328 -0.04069131 0.5614412 0.07047998 -0.04069072 2.084521 0.07048004 -0.07047975 0.5614412 0.04069167 -0.07047903 2.084521 0.04069173 -0.3798453 2.886224 0.2218516 7.9091e-7 1.969194 0.1871857 8.67901e-7 2.96178 0.2218515 8.54381e-7 1.969194 0.2620601 -0.7018634 2.671058 0.2218517 -0.9170291 2.349041 0.2218517 -0.9925853 1.969195 0.2218517 -0.9170292 1.589348 0.2218517 -0.7018637 1.26733 0.2218517 -0.3798456 1.052164 0.2218516 6.30322e-7 0.9766083 0.2218515 0.3798469 1.052164 0.2218514 0.7018651 1.26733 0.2218514 0.9170309 1.589348 0.2218513 0.992587 1.969194 0.2218513 0.9170311 2.34904 0.2218513 0.7018656 2.671059 0.2218514 0.3798475 2.886225 0.2218514 0.3369342 0.5615574 -0.2994973 0.3369344 -0.5615572 -0.2994973 -0.3369344 -0.5615574 -0.2994973 -0.3369344 0.5615576 -0.2994973 0.3369346 0.5615574 0.2994973 0.3369344 -0.5615576 0.2994973 -0.3369344 -0.5615574 0.2994973 -0.3369344 0.5615572 0.2994973 0.5615572 0.3369344 -0.2994973 -0.5615572 0.3369347 -0.2994973 0.5615576 0.3369343 0.2994973 -0.5615572 0.3369344 0.2994973 0.5615572 -0.3369344 -0.2994973 -0.5615575 -0.3369343 -0.2994973 0.5615574 -0.3369347 0.2994973 -0.5615575 -0.3369344 0.2994973 + + + + + + + + + + 1 0 0 0.6302583 0 -0.7763856 0.6302602 0.5489864 -0.5489864 -0.6302602 0.5489864 -0.5489864 -0.6302583 0 -0.7763856 -1 0 0 0.6302583 0.7763856 0 -0.6302583 0.7763856 0 0.6302602 0.5489864 0.5489864 -0.6302602 0.5489864 0.5489864 0.6302583 0 0.7763856 -0.6302583 0 0.7763856 0.6302602 -0.5489864 0.5489864 -0.6302602 -0.5489864 0.5489864 0.6302583 -0.7763856 0 -0.6302583 -0.7763856 0 0.6302602 -0.5489864 -0.5489864 -0.6302602 -0.5489864 -0.5489864 1 -2.24983e-6 0 -1 2.81229e-7 0 1 -3.37475e-6 0 1 7.8744e-6 0 -1 -3.37475e-6 1.46479e-6 1 -4.49967e-6 0 -1 -1.12492e-6 -3.92489e-7 -1 -1.12492e-6 3.92489e-7 -1 -2.24983e-6 -1.46479e-6 -0.9996916 -0.02150607 -0.01241582 1 2.24983e-6 0 -0.9999209 -0.003253757 -0.01214957 0.9996798 0.02530705 0 -0.9997215 0.01180022 -0.02044135 0.9997214 -0.01180779 0.02044135 -1 5.52928e-7 0 0 0 -1 0.06228959 0.8715052 -0.4864144 0.6329994 0.6329994 -0.4456723 0 0 1 0.4264737 0.4264737 0.7976468 -0.06045901 0.6646835 0.744675 0.8715052 0.06228959 -0.4864144 0.6646835 -0.06045901 0.744675 0.6226522 -0.494197 -0.6066907 0.494197 -0.6226522 0.6066907 0.06045901 -0.6646835 -0.744675 -0.06228959 -0.8715052 0.4864144 -0.4264737 -0.4264737 -0.7976468 -0.6329994 -0.6329994 0.4456723 -0.6646835 0.06045901 -0.744675 -0.8715052 -0.06228959 0.4864144 -0.494197 0.6226522 -0.6066907 -0.6226522 0.494197 0.6066907 0.6646835 0.06045901 0.744675 0.494197 0.6226522 0.6066907 0.6226522 0.494197 -0.6066907 0.871518 -0.06229048 -0.486391 -0.06228959 0.8715052 0.4864144 0.06045901 0.6646835 -0.744675 -0.6329994 0.6329994 0.4456723 -0.4264737 0.4264737 -0.7976468 -0.8715052 0.06228959 0.4864144 -0.6646835 -0.06045901 -0.744675 -0.6226522 -0.494197 0.6066907 -0.494197 -0.6226522 -0.6066907 -0.06045901 -0.6646835 0.744675 0.06228959 -0.8715052 -0.4864144 0.4264737 -0.4264737 0.7976468 0.6329994 -0.6329994 -0.4456723 -0.06229048 -0.871518 -0.486391 -0.6329994 -0.6329994 -0.4456723 -0.4264737 -0.4264737 0.7976468 0.06045901 -0.6646835 0.744675 -0.871518 -0.06229048 -0.486391 -0.6646835 0.06045901 0.744675 -0.6226522 0.494197 -0.6066907 -0.494197 0.6226522 0.6066907 -0.06045901 0.6646835 -0.744675 0.06228959 0.8715052 0.4864144 0.4264737 0.4264737 -0.7976468 0.6329994 0.6329994 0.4456723 0.6646835 -0.06045901 -0.744675 0.8715052 0.06228959 0.4864144 0.494197 -0.6226522 -0.6066907 0.6226522 -0.494197 0.6066907 -0.6646835 -0.06045901 0.744675 -0.494197 -0.6226522 0.6066907 -0.6226522 -0.494197 -0.6066907 -0.8715052 0.06228959 -0.4864144 0.06228959 -0.8715052 0.4864144 -0.06045901 -0.6646835 -0.744675 0.6329994 -0.6329994 0.4456723 0.4264737 -0.4264737 -0.7976468 0.871518 -0.06229048 0.486391 0.6646835 0.06045901 -0.744675 0.6226522 0.494197 0.6066907 0.494197 0.6226522 -0.6066907 0.06045901 0.6646835 0.744675 -0.06228959 0.8715052 -0.4864144 -0.4264737 0.4264737 0.7976468 -0.6329994 0.6329994 -0.4456723 0.03490263 -0.006942212 -0.9993667 0.04047435 -0.008050978 0.9991483 0.03431254 -0.0229271 0.9991481 0.02958899 -0.01977056 -0.9993667 0.01977074 -0.02958875 -0.9993667 0.0229268 -0.0343126 0.9991483 0.008050799 -0.04047453 0.9991482 0.00694257 -0.03490233 -0.9993667 -0.00694257 -0.03490239 -0.9993667 -0.008050799 -0.04047447 0.9991481 -0.02292686 -0.03431266 0.9991482 -0.01977074 -0.02958875 -0.9993667 -0.02958893 -0.01977056 -0.9993667 -0.03431242 -0.02292704 0.9991483 -0.04047429 -0.008051037 0.9991483 -0.03490263 -0.006942272 -0.9993666 -0.03490257 0.006942689 -0.9993666 -0.04047429 0.00805062 0.9991483 -0.03431254 0.02292662 0.9991483 -0.02958899 0.01977092 -0.9993666 -0.01977074 0.02958923 -0.9993667 -0.0229268 0.03431224 0.9991482 -0.008050799 0.04047405 0.9991483 -0.00694257 0.03490281 -0.9993667 0.00694257 0.03490275 -0.9993667 0.008050799 0.04047405 0.9991483 0.02292686 0.0343123 0.9991482 0.01977068 0.02958923 -0.9993667 0.02958899 0.01977097 -0.9993666 0.03431248 0.02292656 0.9991482 0.04047429 0.00805068 0.9991483 0.03490263 0.006942689 -0.9993667 0 1 2.81229e-7 0 -1 4.49966e-6 0 1 1.12492e-6 0 -1 -2.24983e-6 0 1 0 0 -1 0 -2.53709e-6 1 0 0 -1 2.24983e-6 -1.46479e-6 1 -1.12492e-6 0 -1 2.24983e-6 -1.46479e-6 1 5.62457e-7 0 -1 -4.49966e-6 -2.53709e-6 1 0 0 1 1.12491e-6 0 -1 4.49966e-6 0 1 -1.12492e-6 0 -1 -4.49966e-6 0 1 -1.12491e-6 0 1 2.81229e-7 0 -1 -2.24983e-6 0.006942749 -0.03490263 -0.9993666 0.00805068 -0.04047423 0.9991482 0.02292668 -0.03431242 0.9991481 0.01977086 -0.02958899 -0.9993667 0.02958923 -0.01977074 -0.9993667 0.03431218 -0.02292686 0.9991483 0.04047405 -0.008050799 0.9991483 0.03490281 -0.00694257 -0.9993666 0.03490281 0.00694257 -0.9993666 0.04047405 0.008050799 0.9991483 0.03431218 0.02292686 0.9991483 0.02958923 0.01977068 -0.9993667 0.01977092 0.02958899 -0.9993666 0.02292668 0.03431242 0.9991483 0.00805062 0.04047423 0.9991482 0.006942689 0.03490263 -0.9993667 -0.006942272 0.03490263 -0.9993667 -0.008051097 0.04047423 0.9991482 -0.02292704 0.03431242 0.9991482 -0.0197705 0.02958893 -0.9993667 -0.02958875 0.01977074 -0.9993667 -0.03431266 0.0229268 0.9991482 -0.04047447 0.008050858 0.9991481 -0.03490233 0.006942451 -0.9993667 -0.03490233 -0.00694251 -0.9993667 -0.04047453 -0.008050858 0.9991481 -0.03431266 -0.0229268 0.9991482 -0.02958869 -0.01977074 -0.9993667 -0.01977056 -0.02958893 -0.9993667 -0.02292704 -0.03431242 0.9991482 -0.008051037 -0.04047423 0.9991482 -0.006942212 -0.03490263 -0.9993667 -0.03490257 0.006942093 -0.9993667 -0.04047429 0.008051097 0.9991483 -0.03431242 0.02292704 0.9991482 -0.02958899 0.01977056 -0.9993667 -0.01977068 0.02958875 -0.9993667 -0.0229268 0.03431272 0.9991481 -0.008050799 0.04047447 0.9991482 -0.00694251 0.03490233 -0.9993667 0.00694251 0.03490233 -0.9993667 0.008050799 0.04047453 0.9991481 0.0229268 0.03431266 0.9991481 0.01977074 0.02958875 -0.9993667 0.02958899 0.0197705 -0.9993667 0.03431242 0.02292698 0.9991482 0.04047423 0.008051156 0.9991482 0.03490263 0.006942212 -0.9993667 0.03490263 -0.006942689 -0.9993667 0.04047423 -0.00805062 0.9991482 0.03431242 -0.02292668 0.9991482 0.02958899 -0.01977092 -0.9993667 0.01977068 -0.02958917 -0.9993666 0.02292686 -0.03431218 0.9991483 0.008050739 -0.04047411 0.9991483 0.00694257 -0.03490281 -0.9993667 -0.00694257 -0.03490275 -0.9993667 -0.008050739 -0.04047411 0.9991483 -0.02292692 -0.03431218 0.9991482 -0.01977068 -0.02958923 -0.9993667 -0.02958893 -0.01977092 -0.9993666 -0.03431242 -0.02292656 0.9991483 -0.04047423 -0.008050739 0.9991482 -0.03490263 -0.006942689 -0.9993667 -1 5.62457e-6 0 -1 -2.24983e-6 0 1 2.24983e-6 -1.46479e-6 1 2.24983e-6 3.92489e-7 1 2.24983e-6 -3.92489e-7 -1 4.49966e-6 0 1 2.24983e-6 1.46479e-6 -1 -7.8744e-6 0 -1 2.24983e-6 0 0 -1 2.81229e-7 0 1 4.49966e-6 0 1 2.24983e-6 0 -1 -1.12492e-6 2.53709e-6 -1 2.24983e-6 1.46479e-6 -1 -1.12492e-6 0 1 -6.74949e-6 1.46479e-6 -1 5.62457e-7 0 1 4.49966e-6 2.53709e-6 -1 -1.12492e-6 0 1 2.24983e-6 0 -1 1.12491e-6 0 1 4.49966e-6 0 -1 -1.12492e-6 0 1 -4.49966e-6 0 1 -4.49966e-6 0 -1 2.81229e-7 0 1 -2.24983e-6 -0.006942749 0.03490263 -0.9993667 -0.00805068 0.04047423 0.9991482 -0.02292662 0.03431242 0.9991482 -0.01977092 0.02958899 -0.9993666 -0.02958917 0.01977074 -0.9993667 -0.03431218 0.02292692 0.9991481 -0.04047405 0.008050799 0.9991482 -0.03490281 0.00694257 -0.9993666 -0.03490281 -0.00694257 -0.9993666 -0.04047405 -0.008050799 0.9991483 -0.03431212 -0.02292686 0.9991482 -0.02958923 -0.01977068 -0.9993667 -0.01977092 -0.02958899 -0.9993666 -0.02292668 -0.03431242 0.9991482 -0.00805062 -0.04047423 0.9991482 -0.006942689 -0.03490263 -0.9993667 0.006942272 -0.03490263 -0.9993667 0.008051037 -0.04047423 0.9991482 0.02292704 -0.03431248 0.9991481 0.0197705 -0.02958899 -0.9993667 0.02958869 -0.01977074 -0.9993667 0.03431266 -0.0229268 0.9991482 0.04047447 -0.008050858 0.9991481 0.03490239 -0.00694251 -0.9993667 0.03490233 0.006942451 -0.9993667 0.04047453 0.008050858 0.9991481 0.03431272 0.02292674 0.9991481 0.02958875 0.01977068 -0.9993667 0.01977056 0.02958893 -0.9993667 0.02292704 0.03431242 0.9991482 0.008051037 0.04047423 0.9991482 0.006942212 0.03490257 -0.9993667 -1 4.42999e-7 0 -1 2.95333e-7 0 -0.7071066 -0.7071071 0 -0.707107 -0.7071067 0 0.7071068 -0.7071068 -4.69872e-7 0.7071068 -0.7071068 -5.48184e-7 1 -4.42999e-7 -1.99016e-7 1 0 -5.97047e-7 0 0 1 0 0 -1 0 0 -1 -0.7071068 0.7071068 3.9156e-7 -0.7071069 0.7071067 5.48184e-7 0.7071068 0.7071068 -5.24176e-7 0.7071069 0.7071067 -2.34936e-7 0 0 -1 0 0 -1 -2.65354e-7 1 0 3.53806e-7 1 5.90666e-7 -3.53806e-7 -1 -5.90666e-7 2.65354e-7 -1 0 -0.6557323 -0.6532297 0.3785583 -0.7571544 0.653236 0 -0.7571544 -0.653236 0 -0.6557323 0.6532297 0.3785583 -0.3785582 -0.6532296 0.6557322 -0.3785658 0.6532427 0.6557148 0 -0.653236 0.7571544 0 0.653236 0.7571544 0.3785582 -0.6532296 0.6557322 0.3785582 0.6532296 0.6557322 0.6557323 -0.6532297 0.3785583 0.6557247 0.6532222 0.3785844 0.7571544 -0.653236 0 0.7571544 0.653236 0 0.6557323 -0.6532297 -0.3785583 0.6557072 0.6532351 -0.378592 0.3785582 -0.6532296 -0.6557322 0.3785582 0.6532296 -0.6557322 0 -0.653236 -0.7571544 0 0.653236 -0.7571544 -0.3785582 -0.6532296 -0.6557322 -0.3785582 0.6532296 -0.6557322 -0.6557323 -0.6532297 -0.3785583 -0.6557323 0.6532297 -0.3785583 0.653236 -0.7571544 0 -0.653236 -0.7571544 0 -0.6532297 -0.6557323 -0.3785583 0.6532297 -0.6557323 -0.3785583 -0.6532296 -0.3785582 -0.6557322 0.6532296 -0.3785582 -0.6557322 -0.653236 0 -0.7571544 0.653236 0 -0.7571544 -0.6532296 0.3785582 -0.6557322 0.6532296 0.3785582 -0.6557322 -0.6532297 0.6557323 -0.3785583 0.6532297 0.6557323 -0.3785583 -0.653236 0.7571544 0 0.653236 0.7571544 0 -0.6532297 0.6557323 0.3785583 0.6532297 0.6557323 0.3785583 -0.6532296 0.3785582 0.6557322 0.6532296 0.3785582 0.6557322 -0.653236 0 0.7571544 0.653236 0 0.7571544 -0.6532296 -0.3785582 0.6557322 0.6532296 -0.3785582 0.6557322 -0.6532297 -0.6557323 0.3785583 0.6532297 -0.6557323 0.3785583 0.6557323 0.6532297 0.3785583 -0.3785582 0.6532296 0.6557322 0.6557323 0.6532297 -0.3785583 -0.6503974 0.6608045 0.3745942 0.6558382 0.6504973 0.383053 -0.6598159 0.3809048 0.6477304 0.6418532 0.3770365 0.6677336 -0.6564947 -0.020051 0.7540641 0.658137 -8.85044e-4 0.7528977 -0.6533265 -0.3956215 0.645483 + + + + + + + + + + + + + + +

60 5 36 5 37 5 60 5 37 5 38 5 60 19 38 19 39 19 60 19 39 19 40 19 60 22 40 22 41 22 60 24 41 24 42 24 60 25 42 25 43 25 60 26 43 26 44 26 60 27 44 27 45 27 60 29 45 29 46 29 60 31 46 31 47 31 47 33 36 33 60 33

+
+ + + +

151 100 135 100 134 100 137 101 135 101 151 101 136 104 138 104 134 104 137 105 138 105 136 105 139 108 140 108 134 108 137 109 140 109 139 109 141 112 142 112 134 112 137 113 142 113 141 113 143 116 144 116 134 116 137 117 144 117 143 117 145 120 146 120 134 120 137 121 146 121 145 121 147 124 148 124 134 124 137 125 148 125 147 125 149 128 150 128 134 128 137 129 150 129 149 129 181 154 178 154 182 154 182 155 178 155 179 155 181 158 183 158 184 158 184 159 183 159 179 159 181 162 185 162 186 162 186 163 185 163 179 163 181 166 187 166 188 166 188 167 187 167 179 167 181 170 189 170 190 170 190 171 189 171 179 171 181 174 191 174 192 174 192 175 191 175 179 175 181 178 193 178 194 178 194 179 193 179 179 179 181 182 195 182 180 182 180 183 195 183 179 183 196 184 197 184 198 184 199 185 197 185 196 185 200 188 201 188 198 188 199 189 201 189 200 189 202 192 203 192 198 192 199 193 203 193 202 193 204 196 205 196 198 196 199 197 205 197 204 197 206 200 207 200 198 200 199 201 207 201 206 201 208 204 209 204 198 204 199 205 209 205 208 205 210 208 211 208 198 208 199 209 211 209 210 209 212 212 213 212 198 212 199 213 213 213 212 213 269 245 266 245 270 245 270 246 266 246 267 246 269 249 271 249 272 249 272 250 271 250 267 250 269 253 273 253 274 253 274 254 273 254 267 254 269 257 275 257 276 257 276 258 275 258 267 258 269 261 277 261 278 261 278 262 277 262 267 262 269 265 279 265 280 265 280 266 279 266 267 266 269 269 281 269 282 269 282 270 281 270 267 270 269 273 283 273 268 273 268 274 283 274 267 274

+
+ + + +

16 0 0 1 3 2 2 3 1 4 17 5 16 0 3 2 5 6 17 5 4 7 2 3 16 0 5 6 7 8 17 5 6 9 4 7 16 0 7 8 9 10 17 5 8 11 6 9 16 0 9 10 11 12 17 5 10 13 8 11 16 0 11 12 13 14 17 5 12 15 10 13 16 0 13 14 15 16 17 5 14 17 12 15 15 16 0 1 16 0 17 5 1 4 14 17 18 0 20 1 19 2 21 5 23 3 22 4 18 0 19 2 24 6 21 5 25 7 23 3 18 0 24 6 26 8 21 5 27 9 25 7 18 0 26 8 28 10 21 5 29 11 27 9 18 0 28 10 30 12 21 5 31 13 29 11 18 0 30 12 32 14 21 5 33 15 31 13 18 0 32 14 34 16 21 5 35 17 33 15 34 16 20 1 18 0 35 17 21 5 22 4 61 0 49 0 48 0 61 18 50 18 49 18 61 20 51 20 50 20 61 21 52 21 51 21 61 23 53 23 52 23 61 0 54 0 53 0 61 0 55 0 54 0 61 0 56 0 55 0 61 28 57 28 56 28 61 30 58 30 57 30 61 32 59 32 58 32 61 0 48 0 59 0 78 34 62 35 63 36 79 37 71 38 70 39 78 34 63 36 64 40 79 37 72 41 71 38 78 34 64 40 65 42 79 37 73 43 72 41 78 34 65 42 66 44 79 37 74 45 73 43 78 34 66 44 67 46 79 37 75 47 74 45 78 34 67 46 68 48 79 37 76 49 75 47 78 34 68 48 69 50 79 37 77 51 76 49 69 50 62 35 78 34 79 37 70 39 77 51 96 37 80 52 83 53 82 54 81 55 97 34 96 37 83 53 85 56 97 34 84 57 82 54 96 37 85 56 87 58 97 34 86 59 84 57 96 37 87 58 89 60 97 34 88 61 86 59 96 37 89 60 91 62 97 34 90 63 88 61 96 37 91 62 93 64 97 34 92 65 90 63 96 37 93 64 95 66 97 34 94 67 92 65 96 37 95 66 80 52 97 34 81 55 94 67 98 34 100 68 99 69 101 37 103 70 102 71 98 34 99 69 104 72 101 37 105 73 103 70 98 34 104 72 106 74 101 37 107 75 105 73 98 34 106 74 108 76 101 37 109 77 107 75 98 34 108 76 110 78 101 37 111 79 109 77 98 34 110 78 112 80 101 37 113 81 111 79 98 34 112 80 114 82 101 37 115 83 113 81 114 82 100 68 98 34 101 37 102 71 115 83 132 37 116 84 119 85 118 86 117 87 133 34 132 37 119 85 121 88 133 34 120 89 118 86 132 37 121 88 123 90 133 34 122 91 120 89 132 37 123 90 125 92 133 34 124 93 122 91 132 37 125 92 127 94 133 34 126 95 124 93 132 37 127 94 129 96 133 34 128 97 126 95 132 37 129 96 131 98 133 34 130 99 128 97 132 37 131 98 116 84 133 34 117 87 130 99 152 132 153 132 154 132 155 133 156 133 157 133 152 134 154 134 158 134 155 135 159 135 156 135 152 136 158 136 160 136 155 137 161 137 159 137 152 136 160 136 162 136 155 137 163 137 161 137 152 138 162 138 164 138 155 139 165 139 163 139 152 140 164 140 166 140 155 141 167 141 165 141 152 142 166 142 168 142 155 143 169 143 167 143 152 144 168 144 170 144 155 135 171 135 169 135 152 145 170 145 172 145 155 146 173 146 171 146 152 147 172 147 174 147 155 148 175 148 173 148 152 149 174 149 176 149 155 137 177 137 175 137 152 150 176 150 153 150 155 151 157 151 177 151 238 5 216 5 217 5 239 0 214 0 215 0 238 5 217 5 219 5 239 0 218 0 214 0 238 216 219 216 221 216 239 0 220 0 218 0 238 217 221 217 223 217 239 0 222 0 220 0 238 5 223 5 225 5 239 218 224 218 222 218 238 5 225 5 227 5 239 219 226 219 224 219 238 5 227 5 229 5 239 220 228 220 226 220 238 221 229 221 231 221 239 222 230 222 228 222 238 223 231 223 233 223 239 0 232 0 230 0 238 224 233 224 235 224 239 0 234 0 232 0 238 5 235 5 237 5 239 0 236 0 234 0 238 5 237 5 216 5 239 0 215 0 236 0 240 225 241 225 242 225 243 226 244 226 245 226 240 137 242 137 246 137 243 227 247 227 244 227 240 137 246 137 248 137 243 136 249 136 247 136 240 228 248 228 250 228 243 136 251 136 249 136 240 229 250 229 252 229 243 136 253 136 251 136 240 230 252 230 254 230 243 231 255 231 253 231 240 232 254 232 256 232 243 233 257 233 255 233 240 234 256 234 258 234 243 235 259 235 257 235 240 236 258 236 260 236 243 237 261 237 259 237 240 238 260 238 262 238 243 239 263 239 261 239 240 137 262 137 264 137 243 240 265 240 263 240 240 241 264 241 241 241 243 242 245 242 265 242 299 275 295 275 297 275 295 276 293 276 297 276 290 277 299 277 297 277 290 278 297 278 286 278 298 279 289 279 285 279 298 280 285 280 296 280 294 281 298 281 296 281 294 282 296 282 292 282 299 37 290 37 298 37 290 37 289 37 298 37 295 283 299 283 298 283 295 37 298 37 294 37 296 284 285 284 286 284 296 34 286 34 297 34 292 285 296 285 297 285 292 34 297 34 293 34 295 286 291 286 293 286 291 287 287 287 293 287 292 288 284 288 288 288 292 289 288 289 294 289 291 37 295 37 288 37 295 37 294 37 288 37 284 290 292 290 293 290 284 291 293 291 287 291 288 292 284 292 291 292 284 293 287 293 291 293 285 294 289 294 290 294 285 295 290 295 286 295 264 296 245 297 241 298 264 296 265 299 245 297 262 300 265 299 264 296 262 300 263 301 265 299 260 302 263 301 262 300 260 302 261 303 263 301 258 304 261 303 260 302 258 304 259 305 261 303 256 306 259 305 258 304 256 306 257 307 259 305 254 308 257 307 256 306 254 308 255 309 257 307 252 310 255 309 254 308 252 310 253 311 255 309 250 312 253 311 252 310 250 312 251 313 253 311 248 314 251 313 250 312 248 314 249 315 251 313 246 316 249 315 248 314 246 316 247 317 249 315 242 318 247 317 246 316 242 318 244 319 247 317 241 298 244 319 242 318 241 298 245 297 244 319 215 320 216 321 237 322 215 320 237 322 236 323 236 323 237 322 235 324 236 323 235 324 234 325 234 325 235 324 233 326 234 325 233 326 232 327 232 327 233 326 231 328 232 327 231 328 230 329 230 329 231 328 229 330 230 329 229 330 228 331 228 331 229 330 227 332 228 331 227 332 226 333 226 333 227 332 225 334 226 333 225 334 224 335 224 335 225 334 223 336 224 335 223 336 222 337 222 337 223 336 221 338 222 337 221 338 220 339 220 339 221 338 219 340 220 339 219 340 218 341 218 341 219 340 217 342 218 341 217 342 214 343 214 343 217 342 216 321 214 343 216 321 215 320 176 344 157 308 153 309 176 344 177 306 157 308 174 305 177 306 176 344 174 305 175 304 177 306 172 303 175 304 174 305 172 303 173 302 175 304 170 345 173 302 172 303 170 345 171 300 173 302 168 299 171 300 170 345 168 299 169 296 171 300 166 297 169 296 168 299 166 297 167 298 169 296 164 319 167 298 166 297 164 319 165 318 167 298 162 317 165 318 164 319 162 317 163 316 165 318 160 315 163 316 162 317 160 315 161 314 163 316 158 313 161 314 160 315 158 313 159 312 161 314 154 346 159 312 158 313 154 346 156 310 159 312 153 309 156 310 154 346 153 309 157 308 156 310 117 87 131 98 130 99 117 87 116 84 131 98 130 99 131 98 128 97 128 97 131 98 129 96 128 97 129 96 126 95 126 95 129 96 127 94 126 95 127 94 124 93 124 93 127 94 125 92 124 93 125 92 122 91 122 91 125 92 123 90 122 91 121 88 120 89 122 91 123 90 121 88 120 89 119 85 118 86 120 89 121 88 119 85 116 84 118 86 119 85 116 84 117 87 118 86 102 71 100 68 114 82 102 71 114 82 115 83 112 80 113 81 115 83 112 80 115 83 114 82 110 78 111 79 113 81 110 78 113 81 112 80 108 76 109 77 110 78 109 77 111 79 110 78 106 74 107 75 108 76 107 75 109 77 108 76 104 72 105 73 106 74 105 73 107 75 106 74 99 69 103 70 104 72 103 70 105 73 104 72 100 68 102 71 103 70 100 68 103 70 99 69 81 55 95 66 94 67 81 55 80 52 95 66 94 67 95 66 92 65 92 65 95 66 93 64 92 65 93 64 90 63 90 63 93 64 91 62 90 63 91 62 88 61 88 61 91 62 89 60 88 61 89 60 86 59 86 59 89 60 87 58 86 59 85 56 84 57 86 59 87 58 85 56 84 57 83 53 82 54 84 57 85 56 83 53 80 52 82 54 83 53 80 52 81 55 82 54 70 39 62 35 69 50 70 39 69 50 77 51 68 48 76 49 77 51 68 48 77 51 69 50 67 46 75 47 76 49 67 46 76 49 68 48 66 44 74 45 67 46 74 45 75 47 67 46 65 42 73 43 66 44 73 43 74 45 66 44 64 40 72 41 65 42 72 41 73 43 65 42 63 36 71 38 64 40 71 38 72 41 64 40 62 35 70 39 71 38 62 35 71 38 63 36 48 333 36 332 47 347 48 333 47 347 59 348 46 349 58 350 59 348 46 349 59 348 47 347 45 351 57 352 58 350 45 351 58 350 46 349 44 353 56 341 57 352 44 353 57 352 45 351 43 342 55 343 56 341 43 342 56 341 44 353 42 321 54 320 55 343 42 321 55 343 43 342 41 322 53 323 54 320 41 322 54 320 42 321 40 324 52 325 53 323 40 324 53 323 41 322 39 326 51 327 52 325 39 326 52 325 40 324 38 328 50 329 51 327 38 328 51 327 39 326 37 330 49 331 50 329 37 330 50 329 38 328 36 332 48 333 49 331 36 332 49 331 37 330 22 4 20 1 34 16 22 4 34 16 35 17 32 14 33 15 35 17 32 14 35 17 34 16 30 12 31 13 33 15 30 12 33 15 32 14 28 10 29 11 31 13 28 10 31 13 30 12 26 8 27 9 29 11 26 8 29 11 28 10 24 6 25 7 27 9 24 6 27 9 26 8 19 2 23 3 25 7 19 2 25 7 24 6 23 3 19 2 20 1 23 3 20 1 22 4 1 4 0 1 15 16 15 16 14 17 1 4 14 17 13 14 12 15 14 17 15 16 13 14 12 15 11 12 10 13 12 15 13 14 11 12 10 13 9 10 8 11 10 13 11 12 9 10 8 11 7 8 6 9 8 11 9 10 7 8 6 9 5 6 4 7 6 9 7 8 5 6 4 7 3 2 2 3 4 7 5 6 3 2 0 1 2 3 3 2 0 1 1 4 2 3

+
+ + + +

137 102 136 102 135 102 135 103 136 103 134 103 137 106 139 106 138 106 138 107 139 107 134 107 137 110 141 110 140 110 140 111 141 111 134 111 137 114 143 114 142 114 142 115 143 115 134 115 137 118 145 118 144 118 144 119 145 119 134 119 137 122 147 122 146 122 146 123 147 123 134 123 137 126 149 126 148 126 148 127 149 127 134 127 137 130 151 130 150 130 150 131 151 131 134 131 178 152 180 152 179 152 181 153 180 153 178 153 183 156 182 156 179 156 181 157 182 157 183 157 185 160 184 160 179 160 181 161 184 161 185 161 187 164 186 164 179 164 181 165 186 165 187 165 189 168 188 168 179 168 181 169 188 169 189 169 191 172 190 172 179 172 181 173 190 173 191 173 193 176 192 176 179 176 181 177 192 177 193 177 195 180 194 180 179 180 181 181 194 181 195 181 199 186 200 186 197 186 197 187 200 187 198 187 199 190 202 190 201 190 201 191 202 191 198 191 199 194 204 194 203 194 203 195 204 195 198 195 199 198 206 198 205 198 205 199 206 199 198 199 199 202 208 202 207 202 207 203 208 203 198 203 199 206 210 206 209 206 209 207 210 207 198 207 199 210 212 210 211 210 211 211 212 211 198 211 199 214 196 214 213 214 213 215 196 215 198 215 266 243 268 243 267 243 269 244 268 244 266 244 271 247 270 247 267 247 269 248 270 248 271 248 273 251 272 251 267 251 269 252 272 252 273 252 275 255 274 255 267 255 269 256 274 256 275 256 277 259 276 259 267 259 269 260 276 260 277 260 279 263 278 263 267 263 269 264 278 264 279 264 281 267 280 267 267 267 269 268 280 268 281 268 283 271 282 271 267 271 269 272 282 272 283 272

+
+
+ 1 +
+
+ + + + + 0.1335572 0 0 0 0 0.1335572 0 0 0 0 0.1335572 0 0 0 0 1 + + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/quadrotor_base (原始).dae b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/quadrotor_base (原始).dae new file mode 100644 index 0000000..5bc4e16 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/quadrotor_base (原始).dae @@ -0,0 +1,238 @@ + + + + + Stefan Kohlbrecher + Blender 2.61.4 r43829 + + 2012-02-03T14:20:49 + 2012-02-03T14:20:49 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.1 0.1 0.1 1 + + + 1 0 0.0106101 1 + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 1 1 1 1 + + + + 1 1 1 1 + + + + 1 1 1 1 + + + + 1 1 1 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 0 0 0 1 + + + 0.1 0.1 0.1 1 + + + 0.05496641 0.05496641 0.05496641 1 + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 0.15 0.15 0.15 1 + + + 0.23 0.23 0.23 1 + + + 0.5 0.5 0.5 1 + + + 1 1 1 1 + + + 20 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + + + + + + + + + + + + + + + 0.8236175 0.673869 -1.366201 -0.8236175 0.6738689 -1.366201 -0.8236175 0.6852639 -1.361481 0.8236175 0.6852641 -1.361481 -0.8236175 0.6899839 -1.350086 0.8236175 0.689984 -1.350086 -0.8236175 0.6852639 -1.338691 0.8236175 0.685264 -1.338691 -0.8236175 0.6738689 -1.333971 0.8236175 0.673869 -1.333971 -0.8236175 0.6624739 -1.338691 0.8236175 0.662474 -1.338691 -0.8236175 0.657754 -1.350086 0.8236175 0.6577541 -1.350086 -0.8236175 0.6624739 -1.361481 0.8236175 0.6624741 -1.361481 0.8236175 0.673869 -1.350086 -0.8236175 0.6738689 -1.350086 0.8236174 -0.6738691 -1.350086 0.8236174 -0.662474 -1.361481 0.8236174 -0.6738691 -1.366201 -0.8236175 -0.6738691 -1.350086 -0.8236175 -0.6738691 -1.366201 -0.8236175 -0.6624742 -1.361481 0.8236174 -0.6577541 -1.350086 -0.8236175 -0.6577541 -1.350086 0.8236174 -0.662474 -1.338691 -0.8236175 -0.662474 -1.338691 0.8236174 -0.6738691 -1.333971 -0.8236175 -0.6738691 -1.333971 0.8236174 -0.6852641 -1.338691 -0.8236175 -0.6852641 -1.338691 0.8236174 -0.689984 -1.350086 -0.8236175 -0.689984 -1.350086 0.8236174 -0.6852641 -1.361481 -0.8236175 -0.6852641 -1.361481 0.5614412 0.08138328 0 0.5614412 0.07047998 -0.04069161 0.5614412 0.04069161 -0.07047998 0.5614412 0 -0.08138328 0.5614412 -0.04069161 -0.07047998 0.5614413 -0.07047998 -0.04069161 0.5614413 -0.08138328 0 0.5614413 -0.07047998 0.04069155 0.5614412 -0.04069167 0.07047992 0.5614412 0 0.08138328 0.5614412 0.04069155 0.07047998 0.5614412 0.07047992 0.04069167 2.084521 0.08138328 0 2.084521 0.07048004 -0.04069155 2.084521 0.04069167 -0.07047986 2.084521 0 -0.08138328 2.084521 -0.04069155 -0.07047998 2.084521 -0.07047986 -0.04069167 2.084521 -0.08138328 0 2.084521 -0.07048004 0.04069155 2.084521 -0.04069173 0.07047992 2.084521 0 0.08138328 2.084521 0.04069155 0.07048004 2.084521 0.07047992 0.04069173 0.5614412 0 0 2.084521 0 0 0.6738689 0.6899839 -1.332763 0.6852639 0.6852639 -1.332763 0.6899839 0.6738689 -1.332763 0.6852639 0.6624739 -1.332763 0.6738689 0.657754 -1.332763 0.6624739 0.6624739 -1.332763 0.657754 0.6738689 -1.332763 0.6624739 0.6852639 -1.332763 0.2994973 0.3156122 -0.303241 0.3108922 0.3108922 -0.303241 0.3156122 0.2994973 -0.303241 0.3108922 0.2881023 -0.303241 0.2994973 0.2833823 -0.303241 0.2881022 0.2881023 -0.303241 0.2833823 0.2994973 -0.303241 0.2881023 0.3108922 -0.303241 0.6738689 0.6738689 -1.332763 0.2994973 0.2994973 -0.303241 0.3156121 -0.2994973 -0.303241 0.6899838 -0.673869 -1.332763 0.6852638 -0.6624739 -1.332763 0.3108922 -0.2881023 -0.303241 0.6738688 -0.657754 -1.332763 0.2994972 -0.2833823 -0.303241 0.6624738 -0.6624739 -1.332763 0.2881022 -0.2881023 -0.303241 0.6577539 -0.673869 -1.332763 0.2833822 -0.2994973 -0.303241 0.6624738 -0.6852639 -1.332763 0.2881022 -0.3108923 -0.303241 0.6738688 -0.6899839 -1.332763 0.2994972 -0.3156122 -0.303241 0.6852638 -0.6852639 -1.332763 0.3108922 -0.3108922 -0.303241 0.2994972 -0.2994973 -0.303241 0.6738688 -0.673869 -1.332763 -0.673869 -0.6738688 -1.332763 -0.685264 -0.6852638 -1.332763 -0.6738691 -0.6899837 -1.332763 -0.2994973 -0.2994972 -0.303241 -0.2994973 -0.3156121 -0.303241 -0.3108923 -0.3108922 -0.303241 -0.689984 -0.6738687 -1.332763 -0.3156123 -0.2994972 -0.303241 -0.685264 -0.6624737 -1.332763 -0.3108923 -0.2881022 -0.303241 -0.673869 -0.6577538 -1.332763 -0.2994973 -0.2833822 -0.303241 -0.662474 -0.6624737 -1.332763 -0.2881023 -0.2881022 -0.303241 -0.6577541 -0.6738688 -1.332763 -0.2833824 -0.2994972 -0.303241 -0.662474 -0.6852638 -1.332763 -0.2881023 -0.3108922 -0.303241 -0.3156121 0.2994973 -0.303241 -0.6899837 0.6738693 -1.332763 -0.6852637 0.662474 -1.332763 -0.3108922 0.2881023 -0.303241 -0.6738687 0.6577541 -1.332763 -0.2994971 0.2833824 -0.303241 -0.6624737 0.662474 -1.332763 -0.2881022 0.2881023 -0.303241 -0.6577537 0.6738691 -1.332763 -0.2833822 0.2994973 -0.303241 -0.6624737 0.6852641 -1.332763 -0.2881022 0.3108924 -0.303241 -0.6738685 0.689984 -1.332763 -0.2994971 0.3156123 -0.303241 -0.6852637 0.6852641 -1.332763 -0.3108922 0.3108923 -0.303241 -0.2994971 0.2994973 -0.303241 -0.6738687 0.6738691 -1.332763 1.969194 0 0.1871857 2.886225 -0.3798463 0.2218515 2.671059 -0.7018645 0.2218514 1.969194 0 0.2620601 2.349041 -0.9170302 0.2218514 1.969195 -0.9925863 0.2218514 1.589348 -0.9170302 0.2218514 1.26733 -0.7018646 0.2218514 1.052164 -0.3798465 0.2218515 0.9766083 -2.36674e-7 0.2218515 1.052164 0.379846 0.2218516 1.26733 0.7018642 0.2218517 1.589348 0.9170299 0.2218517 1.969194 0.992586 0.2218518 2.34904 0.91703 0.2218517 2.671058 0.7018645 0.2218517 2.886224 0.3798464 0.2218516 2.96178 3.25924e-7 0.2218515 0 -0.5614412 0 0.08138316 -0.5614412 0 0.07047986 -0.5614412 -0.04069161 -2.69139e-7 -2.084521 0 0.07047975 -2.084521 -0.04069155 0.08138298 -2.084521 0 0.04069155 -0.5614412 -0.07047998 0.04069143 -2.084521 -0.07047992 0 -0.5614412 -0.08138328 -1.69274e-7 -2.084521 -0.08138328 -0.04069167 -0.5614412 -0.07047998 -0.04069179 -2.084521 -0.07047998 -0.07048004 -0.5614413 -0.04069167 -0.07048016 -2.084521 -0.04069167 -0.08138334 -0.5614413 0 -0.08138352 -2.084521 0 -0.07048004 -0.5614413 0.04069161 -0.07048028 -2.084521 0.04069155 -0.04069173 -0.5614412 0.07047998 -0.04069197 -2.084521 0.07047992 -1.3514e-7 -0.5614412 0.08138328 -3.81294e-7 -2.084521 0.08138328 0.04069143 -0.5614412 0.07047998 0.04069125 -2.084521 0.07048004 0.07047986 -0.5614412 0.04069167 0.07047963 -2.084521 0.04069173 0.379846 -2.886224 0.2218516 -2.61752e-7 -1.969194 0.1871857 0 -2.96178 0.2218515 -3.25223e-7 -1.969194 0.2620601 0.7018641 -2.671058 0.2218517 0.9170297 -2.34904 0.2218517 0.9925858 -1.969194 0.2218517 0.9170296 -1.589348 0.2218517 0.701864 -1.26733 0.2218517 0.3798459 -1.052164 0.2218516 -3.6789e-7 -0.9766083 0.2218515 -0.3798466 -1.052164 0.2218514 -0.7018647 -1.26733 0.2218514 -0.9170304 -1.589348 0.2218513 -0.9925865 -1.969194 0.2218513 -0.9170305 -2.34904 0.2218513 -0.7018648 -2.671059 0.2218514 -0.3798467 -2.886225 0.2218514 -2.96178 4.69959e-7 0.2218515 -2.886225 0.3798471 0.2218514 -1.969194 5.26331e-7 0.1871857 -1.969194 5.89802e-7 0.2620601 -2.671059 0.7018652 0.2218514 -2.34904 0.9170308 0.2218513 -1.969194 0.9925867 0.2218513 -1.589348 0.9170306 0.2218513 -1.26733 0.7018649 0.2218514 -1.052164 0.3798468 0.2218514 -0.9766083 4.99106e-7 0.2218515 -1.052164 -0.3798457 0.2218516 -1.26733 -0.7018638 0.2218517 -1.589348 -0.9170294 0.2218517 -1.969194 -0.9925855 0.2218517 -2.349041 -0.9170294 0.2218517 -2.671058 -0.7018638 0.2218517 -2.886224 -0.3798456 0.2218516 -0.5614412 -0.07047981 0.04069167 -0.5614412 -0.0813831 0 -2.084521 -0.08138269 0 -2.084521 -0.07047933 0.04069173 -0.5614412 -0.04069137 0.07047998 -2.084521 -0.04069095 0.07048004 -0.5614412 2.10574e-7 0.08138328 -2.084521 6.61367e-7 0.08138328 -0.5614412 0.04069179 0.07047998 -2.084521 0.04069226 0.07047992 -0.5614413 0.0704801 0.04069161 -2.084521 0.07048058 0.04069155 -0.5614413 0.0813834 0 -2.084521 0.08138382 0 -0.5614413 0.0704801 -0.04069167 -2.084521 0.07048046 -0.04069167 -0.5614412 0.04069179 -0.07047998 -2.084521 0.04069209 -0.07047998 -0.5614412 1.54427e-7 -0.08138328 -2.084521 4.49347e-7 -0.08138328 -0.5614412 -0.04069149 -0.07047998 -2.084521 -0.04069113 -0.07047992 -0.5614412 -0.07047981 -0.04069161 -2.084521 -0.07047945 -0.04069155 -2.084521 5.49213e-7 0 -0.5614412 1.61804e-7 0 2.37238e-7 0.5614412 0 -0.08138304 0.5614412 0 -0.07047975 0.5614412 -0.04069161 8.29287e-7 2.084521 0 -0.07047921 2.084521 -0.04069155 -0.08138245 2.084521 0 -0.04069137 0.5614412 -0.07047998 -0.04069083 2.084521 -0.07047992 2.29861e-7 0.5614412 -0.08138328 7.29421e-7 2.084521 -0.08138328 0.04069185 0.5614412 -0.07047998 0.04069238 2.084521 -0.07047998 0.07048016 0.5614413 -0.04069167 0.07048076 2.084521 -0.04069167 0.08138352 0.5614413 0 0.08138412 2.084521 0 0.07048022 0.5614413 0.04069161 0.07048088 2.084521 0.04069155 0.04069191 0.5614412 0.07047998 0.04069256 2.084521 0.07047992 2.86009e-7 0.5614412 0.08138328 9.41441e-7 2.084521 0.08138328 -0.04069131 0.5614412 0.07047998 -0.04069072 2.084521 0.07048004 -0.07047975 0.5614412 0.04069167 -0.07047903 2.084521 0.04069173 -0.3798453 2.886224 0.2218516 7.9091e-7 1.969194 0.1871857 8.67901e-7 2.96178 0.2218515 8.54381e-7 1.969194 0.2620601 -0.7018634 2.671058 0.2218517 -0.9170291 2.349041 0.2218517 -0.9925853 1.969195 0.2218517 -0.9170292 1.589348 0.2218517 -0.7018637 1.26733 0.2218517 -0.3798456 1.052164 0.2218516 6.30322e-7 0.9766083 0.2218515 0.3798469 1.052164 0.2218514 0.7018651 1.26733 0.2218514 0.9170309 1.589348 0.2218513 0.992587 1.969194 0.2218513 0.9170311 2.34904 0.2218513 0.7018656 2.671059 0.2218514 0.3798475 2.886225 0.2218514 0.3369342 0.5615574 -0.2994973 0.3369344 -0.5615572 -0.2994973 -0.3369344 -0.5615574 -0.2994973 -0.3369344 0.5615576 -0.2994973 0.3369346 0.5615574 0.2994973 0.3369344 -0.5615576 0.2994973 -0.3369344 -0.5615574 0.2994973 -0.3369344 0.5615572 0.2994973 0.5615572 0.3369344 -0.2994973 -0.5615572 0.3369347 -0.2994973 0.5615576 0.3369343 0.2994973 -0.5615572 0.3369344 0.2994973 0.5615572 -0.3369344 -0.2994973 -0.5615575 -0.3369343 -0.2994973 0.5615574 -0.3369347 0.2994973 -0.5615575 -0.3369344 0.2994973 + + + + + + + + + + 1 0 0 0.6302378 0 -0.7763603 0.6302378 0.548967 -0.548967 -0.6302378 0.548967 -0.548967 -0.6302378 0 -0.7763603 -1 0 0 0.6302378 0.7763603 0 -0.6302378 0.7763603 0 0.6302378 0.548967 0.548967 -0.6302378 0.548967 0.548967 0.6302378 0 0.7763603 -0.6302378 0 0.7763603 0.6302378 -0.548967 0.548967 -0.6302378 -0.548967 0.548967 0.6302378 -0.7763603 0 -0.6302378 -0.7763603 0 0.6302378 -0.548967 -0.548967 -0.6302378 -0.548967 -0.548967 1 0 0 0.6302378 0 -0.7763603 0.6302378 0.548967 -0.548967 -1 0 0 -0.6302378 0.548967 -0.548967 -0.6302378 0 -0.7763603 0.6302378 0.7763603 0 -0.6302378 0.7763603 0 0.6302378 0.548967 0.548967 -0.6302378 0.548967 0.548967 0.6302378 0 0.7763603 -0.6302378 0 0.7763603 0.6302378 -0.548967 0.548967 -0.6302378 -0.548967 0.548967 0.6302378 -0.7763603 0 -0.6302378 -0.7763603 0 0.6302378 -0.548967 -0.548967 -0.6302378 -0.548967 -0.548967 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 -2.53709e-6 1.46479e-6 1 0 0 -1 -1.46479e-6 -3.92489e-7 1 0 0 -1 -1.46479e-6 3.92489e-7 1 0 0 -1 -2.53709e-6 -1.46479e-6 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 0 0 -1 0.06228822 0.8714866 -0.486404 0.6329844 0.6329844 -0.4456618 0 0 1 0.4264656 0.4264656 0.7976318 -0.06045717 0.6646626 0.7446516 0.8714866 0.06228822 -0.486404 0.6646626 -0.06045717 0.7446516 0.6226387 -0.4941862 -0.6066775 0.4941862 -0.6226387 0.6066775 0.06045717 -0.6646626 -0.7446516 -0.06228822 -0.8714866 0.486404 -0.4264656 -0.4264656 -0.7976318 -0.6329844 -0.6329844 0.4456618 -0.6646626 0.06045717 -0.7446516 -0.8714866 -0.06228822 0.486404 -0.4941862 0.6226387 -0.6066775 -0.6226387 0.4941862 0.6066775 0 0 1 0.6646626 0.06045717 0.7446516 0.4941862 0.6226387 0.6066775 0.6226387 0.4941862 -0.6066775 0.8714866 -0.06228822 -0.486404 0 0 -1 -0.06228822 0.8714866 0.486404 0.06045717 0.6646626 -0.7446516 -0.6329844 0.6329844 0.4456618 -0.4264656 0.4264656 -0.7976318 -0.8714866 0.06228822 0.486404 -0.6646626 -0.06045717 -0.7446516 -0.6226387 -0.4941862 0.6066775 -0.4941862 -0.6226387 -0.6066775 -0.06045717 -0.6646626 0.7446516 0.06228822 -0.8714866 -0.486404 0.4264656 -0.4264656 0.7976318 0.6329844 -0.6329844 -0.4456618 0 0 -1 -0.06228822 -0.8714866 -0.486404 -0.6329844 -0.6329844 -0.4456618 0 0 1 -0.4264656 -0.4264656 0.7976318 0.06045717 -0.6646626 0.7446516 -0.8714866 -0.06228822 -0.486404 -0.6646626 0.06045717 0.7446516 -0.6226387 0.4941862 -0.6066775 -0.4941862 0.6226387 0.6066775 -0.06045717 0.6646626 -0.7446516 0.06228822 0.8714866 0.486404 0.4264656 0.4264656 -0.7976318 0.6329844 0.6329844 0.4456618 0.6646626 -0.06045717 -0.7446516 0.8714866 0.06228822 0.486404 0.4941862 -0.6226387 -0.6066775 0.6226387 -0.4941862 0.6066775 0 0 1 -0.6646626 -0.06045717 0.7446516 -0.4941862 -0.6226387 0.6066775 -0.6226387 -0.4941862 -0.6066775 -0.8714866 0.06228822 -0.486404 0 0 -1 0.06228822 -0.8714866 0.486404 -0.06045717 -0.6646626 -0.7446516 0.6329844 -0.6329844 0.4456618 0.4264656 -0.4264656 -0.7976318 0.8714866 -0.06228822 0.486404 0.6646626 0.06045717 -0.7446516 0.6226387 0.4941862 0.6066775 0.4941862 0.6226387 -0.6066775 0.06045717 0.6646626 0.7446516 -0.06228822 0.8714866 -0.486404 -0.4264656 0.4264656 0.7976318 -0.6329844 0.6329844 -0.4456618 0.03490257 -0.006942212 -0.9993667 0.04047429 -0.008050978 0.9991481 0.03431242 -0.02292704 0.9991481 0.02958893 -0.0197705 -0.9993667 0.01977074 -0.02958875 -0.9993666 0.02292686 -0.03431266 0.9991481 0.008050799 -0.04047453 0.9991481 0.00694251 -0.03490239 -0.9993667 -0.00694251 -0.03490239 -0.9993667 -0.008050799 -0.04047447 0.9991481 -0.02292686 -0.03431266 0.9991481 -0.01977074 -0.02958875 -0.9993666 -0.02958893 -0.01977056 -0.9993666 -0.03431248 -0.02292704 0.9991481 -0.04047429 -0.008051037 0.9991481 -0.03490257 -0.006942331 -0.9993666 -0.03490257 0.006942749 -0.9993666 -0.04047429 0.00805062 0.9991481 -0.03431248 0.02292662 0.999148 -0.02958899 0.01977092 -0.9993666 -0.01977074 0.02958917 -0.9993667 -0.02292686 0.03431224 0.9991482 -0.008050799 0.04047405 0.9991481 -0.00694251 0.03490281 -0.9993667 0.00694251 0.03490281 -0.9993667 0.008050799 0.04047411 0.9991481 0.0229268 0.03431224 0.9991482 0.01977074 0.02958923 -0.9993667 0.02958899 0.01977092 -0.9993667 0.03431248 0.02292662 0.9991481 0.04047429 0.00805062 0.9991481 0.03490257 0.006942749 -0.9993667 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 -2.53709e-6 1 1.46479e-6 0 -1 0 -1.46479e-6 1 -3.92489e-7 0 -1 0 -1.46479e-6 1 3.92489e-7 0 -1 0 -2.53709e-6 1 -1.46479e-6 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0.006942689 -0.03490263 -0.9993667 0.00805068 -0.04047423 0.9991481 0.02292662 -0.03431242 0.9991482 0.01977092 -0.02958899 -0.9993667 0.02958923 -0.01977068 -0.9993667 0.03431218 -0.02292686 0.9991481 0.04047405 -0.008050739 0.9991482 0.03490281 -0.00694257 -0.9993666 0.03490281 0.00694257 -0.9993667 0.04047405 0.008050799 0.9991481 0.03431218 0.02292686 0.9991481 0.02958923 0.01977068 -0.9993667 0.01977092 0.02958899 -0.9993666 0.02292662 0.03431242 0.9991481 0.00805062 0.04047423 0.9991481 0.006942689 0.03490263 -0.9993666 -0.006942212 0.03490263 -0.9993666 -0.008051097 0.04047423 0.9991481 -0.02292704 0.03431242 0.9991481 -0.0197705 0.02958893 -0.9993666 -0.02958869 0.01977074 -0.9993666 -0.03431266 0.0229268 0.9991481 -0.04047447 0.008050858 0.9991481 -0.03490233 0.00694251 -0.9993667 -0.03490233 -0.00694251 -0.9993667 -0.04047447 -0.008050858 0.9991481 -0.03431266 -0.0229268 0.9991481 -0.02958875 -0.01977074 -0.9993667 -0.0197705 -0.02958893 -0.9993667 -0.02292704 -0.03431242 0.9991481 -0.008051037 -0.04047423 0.999148 -0.006942152 -0.03490263 -0.9993667 -0.03490263 0.006942152 -0.9993667 -0.04047423 0.008051037 0.9991481 -0.03431242 0.02292704 0.9991481 -0.02958893 0.0197705 -0.9993667 -0.01977068 0.02958875 -0.9993666 -0.02292674 0.03431272 0.9991482 -0.008050858 0.04047447 0.9991481 -0.006942451 0.03490233 -0.9993666 0.00694251 0.03490239 -0.9993667 0.008050858 0.04047447 0.9991481 0.0229268 0.03431266 0.9991481 0.01977074 0.02958869 -0.9993666 0.02958893 0.0197705 -0.9993666 0.03431248 0.02292698 0.9991481 0.04047423 0.008051097 0.9991481 0.03490263 0.006942212 -0.9993666 0.03490263 -0.006942689 -0.9993666 0.04047423 -0.00805062 0.9991481 0.03431242 -0.02292662 0.9991482 0.02958899 -0.01977092 -0.9993667 0.01977068 -0.02958923 -0.9993667 0.02292686 -0.03431218 0.9991481 0.008050799 -0.04047405 0.9991481 0.00694257 -0.03490281 -0.9993667 -0.00694257 -0.03490281 -0.9993667 -0.008050799 -0.04047405 0.9991481 -0.02292686 -0.03431218 0.9991482 -0.01977068 -0.02958917 -0.9993667 -0.02958899 -0.01977092 -0.9993667 -0.03431242 -0.02292662 0.9991482 -0.04047423 -0.00805068 0.9991481 -0.03490263 -0.006942689 -0.9993667 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 2.53709e-6 -1.46479e-6 -1 0 0 1 1.46479e-6 3.92489e-7 -1 0 0 1 1.46479e-6 -3.92489e-7 -1 0 0 1 2.53709e-6 1.46479e-6 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 2.53709e-6 -1 1.46479e-6 0 1 0 1.46479e-6 -1 -3.92489e-7 0 1 0 1.46479e-6 -1 3.92489e-7 0 1 0 2.53709e-6 -1 -1.46479e-6 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 -0.006942689 0.03490263 -0.9993667 -0.00805068 0.04047423 0.9991481 -0.02292662 0.03431242 0.9991482 -0.01977092 0.02958899 -0.9993667 -0.02958917 0.01977074 -0.9993666 -0.03431218 0.02292692 0.9991483 -0.04047405 0.008050799 0.9991482 -0.03490281 0.00694257 -0.9993666 -0.03490281 -0.00694257 -0.9993667 -0.04047405 -0.008050799 0.9991481 -0.03431218 -0.02292686 0.9991481 -0.02958923 -0.01977068 -0.9993666 -0.01977092 -0.02958899 -0.9993667 -0.02292662 -0.03431242 0.9991481 -0.00805062 -0.04047423 0.9991481 -0.006942689 -0.03490263 -0.9993666 0.006942212 -0.03490263 -0.9993666 0.008051097 -0.04047423 0.9991481 0.02292698 -0.03431248 0.9991482 0.0197705 -0.02958899 -0.9993667 0.02958869 -0.01977074 -0.9993667 0.03431266 -0.0229268 0.999148 0.04047447 -0.008050858 0.9991481 0.03490233 -0.00694251 -0.9993667 0.03490239 0.006942451 -0.9993667 0.04047447 0.008050858 0.9991481 0.03431272 0.02292674 0.9991481 0.02958875 0.01977068 -0.9993667 0.0197705 0.02958893 -0.9993667 0.02292704 0.03431242 0.9991481 0.008051037 0.04047423 0.9991481 0.006942152 0.03490263 -0.9993667 -1 3.53806e-7 0 -1 3.53806e-7 0 -0.7071067 -0.707107 -1.40725e-7 -0.7071068 -0.7071068 0 0.7071068 -0.7071069 -4.92539e-7 0.7071067 -0.7071068 -4.8945e-7 1 -3.53806e-7 -1.99016e-7 1 0 -5.97047e-7 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.7071067 0.7071068 3.9156e-7 -0.7071068 0.7071067 4.92539e-7 0.7071067 0.7071068 -5.2772e-7 0.707107 0.7071065 -3.13248e-7 0 0 1 0 0 1 0 0 -1 0 0 -1 -2.65354e-7 1 0 3.53806e-7 1 6.96555e-7 -3.53806e-7 -1 -6.96555e-7 2.65354e-7 -1 0 -0.6557207 -0.6532182 0.3785516 -0.7571337 0.6532182 0 -0.7571337 -0.6532182 0 -0.6557207 0.6532182 0.3785516 -0.3785516 -0.6532182 0.6557207 -0.3785516 0.6532182 0.6557207 0 -0.6532182 0.7571337 0 0.6532182 0.7571337 0.3785516 -0.6532182 0.6557207 0.3785821 0.6532182 0.6557207 0.6557207 -0.6532182 0.3785516 0.6557207 0.6532182 0.3785516 0.7571337 -0.6532182 0 0.7571337 0.6532182 0 0.6557207 -0.6532182 -0.3785516 0.6557207 0.6532182 -0.3785516 0.3785516 -0.6532182 -0.6557207 0.3785516 0.6532182 -0.6557207 0 -0.6532182 -0.7571337 0 0.6532182 -0.7571337 -0.3785516 -0.6532182 -0.6557207 -0.3785516 0.6532182 -0.6557207 -0.6557207 -0.6532182 -0.3785516 -0.6557207 0.6532182 -0.3785516 0.6532182 -0.7571337 0 -0.6532182 -0.7571337 0 -0.6532182 -0.6557207 -0.3785516 0.6532182 -0.6557207 -0.3785516 -0.6532182 -0.3785516 -0.6557207 0.6532182 -0.3785516 -0.6557207 -0.6532182 0 -0.7571337 0.6532182 0 -0.7571337 -0.6532182 0.3785516 -0.6557207 0.6532182 0.3785516 -0.6557207 -0.6532182 0.6557207 -0.3785516 0.6532182 0.6557207 -0.3785516 -0.6532182 0.7571337 0 0.6532182 0.7571337 0 -0.6532182 0.6557207 0.3785516 0.6532182 0.6557207 0.3785516 -0.6532182 0.3785821 0.6557207 0.6532182 0.3785821 0.6557207 -0.6532182 0 0.7571337 0.6532182 0 0.7571337 -0.6532182 -0.3785516 0.6557207 0.6532182 -0.3785516 0.6557207 -0.6532182 -0.6557207 0.3785516 0.6532182 -0.6557207 0.3785516 0.6557207 0.6532182 0.3785516 0.7571337 -0.6532182 0 0.7571337 0.6532182 0 0.6557207 -0.6532182 0.3785516 0.3785516 0.6532182 0.6557207 0.3785516 -0.6532182 0.6557207 0 0.6532182 0.7571337 0 -0.6532182 0.7571337 -0.3785821 0.6532182 0.6557207 -0.3785821 -0.6532182 0.6557207 -0.6557207 0.6532182 0.3785516 -0.6557207 -0.6532182 0.3785516 -0.7571337 0.6532182 0 -0.7571337 -0.6532182 0 -0.6557207 0.6532182 -0.3785516 -0.6557207 -0.6532182 -0.3785516 -0.3785516 0.6532182 -0.6557207 -0.3785516 -0.6532182 -0.6557207 0 0.6532182 -0.7571337 0 -0.6532182 -0.7571337 0.3785516 0.6532182 -0.6557207 0.3785516 -0.6532182 -0.6557207 0.6557207 0.6532182 -0.3785516 0.6557207 -0.6532182 -0.3785516 0.6532182 0.7571337 0 -0.6532182 0.7571337 0 -0.6532182 0.6557207 0.3785516 0.6532182 0.6557207 0.3785516 -0.6532182 0.3785516 0.6557207 0.6532182 0.3785516 0.6557207 -0.6532182 0 0.7571337 0.6532182 0 0.7571337 -0.6532182 -0.3785821 0.6556902 0.6532182 -0.3785821 0.6557207 -0.6532182 -0.6557207 0.3785516 0.6532182 -0.6557207 0.3785516 -0.6532182 -0.7571337 0 0.6532182 -0.7571337 0 -0.6532182 -0.6557207 -0.3785516 0.6532182 -0.6557207 -0.3785516 -0.6532182 -0.3785516 -0.6557207 0.6532182 -0.3785516 -0.6557207 -0.6532182 0 -0.7571337 0.6532182 0 -0.7571337 -0.6532182 0.3785516 -0.6557207 0.6532182 0.3785516 -0.6557207 -0.6532182 0.6557207 -0.3785516 0.6532182 0.6557207 -0.3785516 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

60 36 36 36 37 36 61 37 49 37 48 37 60 38 37 38 38 38 61 39 50 39 49 39 60 40 38 40 39 40 61 41 51 41 50 41 60 42 39 42 40 42 61 43 52 43 51 43 60 44 40 44 41 44 61 45 53 45 52 45 60 46 41 46 42 46 61 47 54 47 53 47 60 48 42 48 43 48 61 49 55 49 54 49 60 50 43 50 44 50 61 51 56 51 55 51 60 52 44 52 45 52 61 53 57 53 56 53 60 54 45 54 46 54 61 55 58 55 57 55 60 56 46 56 47 56 61 57 59 57 58 57 47 58 36 58 60 58 61 59 48 59 59 59 48 432 36 433 47 434 48 432 47 434 59 435 46 436 58 437 59 435 46 436 59 435 47 434 45 438 57 439 58 437 45 438 58 437 46 436 44 440 56 441 57 439 44 440 57 439 45 438 43 442 55 443 56 441 43 442 56 441 44 440 42 444 54 445 55 443 42 444 55 443 43 442 41 446 53 447 54 445 41 446 54 445 42 444 40 448 52 449 53 447 40 448 53 447 41 446 39 450 51 451 52 449 39 450 52 449 40 448 38 452 50 453 51 451 38 452 51 451 39 450 37 454 49 455 50 453 37 454 50 453 38 452 36 433 48 432 49 455 36 433 49 455 37 454

+
+ + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

151 132 135 132 134 132 137 133 135 133 151 133 136 136 138 136 134 136 137 137 138 137 136 137 139 140 140 140 134 140 137 141 140 141 139 141 141 144 142 144 134 144 137 145 142 145 141 145 143 148 144 148 134 148 137 149 144 149 143 149 145 152 146 152 134 152 137 153 146 153 145 153 147 156 148 156 134 156 137 157 148 157 147 157 149 160 150 160 134 160 137 161 150 161 149 161 181 190 178 190 182 190 182 191 178 191 179 191 181 194 183 194 184 194 184 195 183 195 179 195 181 198 185 198 186 198 186 199 185 199 179 199 181 202 187 202 188 202 188 203 187 203 179 203 181 206 189 206 190 206 190 207 189 207 179 207 181 210 191 210 192 210 192 211 191 211 179 211 181 214 193 214 194 214 194 215 193 215 179 215 181 218 195 218 180 218 180 219 195 219 179 219 196 220 197 220 198 220 199 221 197 221 196 221 200 224 201 224 198 224 199 225 201 225 200 225 202 228 203 228 198 228 199 229 203 229 202 229 204 232 205 232 198 232 199 233 205 233 204 233 206 236 207 236 198 236 199 237 207 237 206 237 208 240 209 240 198 240 199 241 209 241 208 241 210 244 211 244 198 244 199 245 211 245 210 245 212 248 213 248 198 248 199 249 213 249 212 249 269 302 266 302 270 302 270 303 266 303 267 303 269 306 271 306 272 306 272 307 271 307 267 307 269 310 273 310 274 310 274 311 273 311 267 311 269 314 275 314 276 314 276 315 275 315 267 315 269 318 277 318 278 318 278 319 277 319 267 319 269 322 279 322 280 322 280 323 279 323 267 323 269 326 281 326 282 326 282 327 281 327 267 327 269 330 283 330 268 330 268 331 283 331 267 331

+
+ + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

16 0 0 1 3 2 2 3 1 4 17 5 16 0 3 2 5 6 17 5 4 7 2 3 16 0 5 6 7 8 17 5 6 9 4 7 16 0 7 8 9 10 17 5 8 11 6 9 16 0 9 10 11 12 17 5 10 13 8 11 16 0 11 12 13 14 17 5 12 15 10 13 16 0 13 14 15 16 17 5 14 17 12 15 15 16 0 1 16 0 17 5 1 4 14 17 18 18 20 19 19 20 21 21 23 22 22 23 18 18 19 20 24 24 21 21 25 25 23 22 18 18 24 24 26 26 21 21 27 27 25 25 18 18 26 26 28 28 21 21 29 29 27 27 18 18 28 28 30 30 21 21 31 31 29 29 18 18 30 30 32 32 21 21 33 33 31 31 18 18 32 32 34 34 21 21 35 35 33 33 34 34 20 19 18 18 35 35 21 21 22 23 78 60 62 61 63 62 79 63 71 64 70 65 78 60 63 62 64 66 79 63 72 67 71 64 78 60 64 66 65 68 79 63 73 69 72 67 78 60 65 68 66 70 79 63 74 71 73 69 78 60 66 70 67 72 79 63 75 73 74 71 78 60 67 72 68 74 79 63 76 75 75 73 78 60 68 74 69 76 79 63 77 77 76 75 69 76 62 61 78 60 79 63 70 65 77 77 96 78 80 79 83 80 82 81 81 82 97 83 96 78 83 80 85 84 97 83 84 85 82 81 96 78 85 84 87 86 97 83 86 87 84 85 96 78 87 86 89 88 97 83 88 89 86 87 96 78 89 88 91 90 97 83 90 91 88 89 96 78 91 90 93 92 97 83 92 93 90 91 96 78 93 92 95 94 97 83 94 95 92 93 96 78 95 94 80 79 97 83 81 82 94 95 98 96 100 97 99 98 101 99 103 100 102 101 98 96 99 98 104 102 101 99 105 103 103 100 98 96 104 102 106 104 101 99 107 105 105 103 98 96 106 104 108 106 101 99 109 107 107 105 98 96 108 106 110 108 101 99 111 109 109 107 98 96 110 108 112 110 101 99 113 111 111 109 98 96 112 110 114 112 101 99 115 113 113 111 114 112 100 97 98 96 101 99 102 101 115 113 132 114 116 115 119 116 118 117 117 118 133 119 132 114 119 116 121 120 133 119 120 121 118 117 132 114 121 120 123 122 133 119 122 123 120 121 132 114 123 122 125 124 133 119 124 125 122 123 132 114 125 124 127 126 133 119 126 127 124 125 132 114 127 126 129 128 133 119 128 129 126 127 132 114 129 128 131 130 133 119 130 131 128 129 132 114 131 130 116 115 133 119 117 118 130 131 152 164 153 164 154 164 155 165 156 165 157 165 152 166 154 166 158 166 155 167 159 167 156 167 152 168 158 168 160 168 155 169 161 169 159 169 152 170 160 170 162 170 155 171 163 171 161 171 152 172 162 172 164 172 155 173 165 173 163 173 152 174 164 174 166 174 155 175 167 175 165 175 152 176 166 176 168 176 155 177 169 177 167 177 152 178 168 178 170 178 155 179 171 179 169 179 152 180 170 180 172 180 155 181 173 181 171 181 152 182 172 182 174 182 155 183 175 183 173 183 152 184 174 184 176 184 155 185 177 185 175 185 152 186 176 186 153 186 155 187 157 187 177 187 238 252 216 252 217 252 239 253 214 253 215 253 238 254 217 254 219 254 239 255 218 255 214 255 238 256 219 256 221 256 239 257 220 257 218 257 238 258 221 258 223 258 239 259 222 259 220 259 238 260 223 260 225 260 239 261 224 261 222 261 238 262 225 262 227 262 239 263 226 263 224 263 238 264 227 264 229 264 239 265 228 265 226 265 238 266 229 266 231 266 239 267 230 267 228 267 238 268 231 268 233 268 239 269 232 269 230 269 238 270 233 270 235 270 239 271 234 271 232 271 238 272 235 272 237 272 239 273 236 273 234 273 238 274 237 274 216 274 239 275 215 275 236 275 240 276 241 276 242 276 243 277 244 277 245 277 240 278 242 278 246 278 243 279 247 279 244 279 240 280 246 280 248 280 243 281 249 281 247 281 240 282 248 282 250 282 243 283 251 283 249 283 240 284 250 284 252 284 243 285 253 285 251 285 240 286 252 286 254 286 243 287 255 287 253 287 240 288 254 288 256 288 243 289 257 289 255 289 240 290 256 290 258 290 243 291 259 291 257 291 240 292 258 292 260 292 243 293 261 293 259 293 240 294 260 294 262 294 243 295 263 295 261 295 240 296 262 296 264 296 243 297 265 297 263 297 240 298 264 298 241 298 243 299 245 299 265 299 299 332 295 332 297 332 295 333 293 333 297 333 290 334 299 334 297 334 290 335 297 335 286 335 298 336 289 336 285 336 298 337 285 337 296 337 294 338 298 338 296 338 294 339 296 339 292 339 299 340 290 340 298 340 290 341 289 341 298 341 295 342 299 342 298 342 295 343 298 343 294 343 296 344 285 344 286 344 296 345 286 345 297 345 292 346 296 346 297 346 292 347 297 347 293 347 295 348 291 348 293 348 291 349 287 349 293 349 292 350 284 350 288 350 292 351 288 351 294 351 291 352 295 352 288 352 295 353 294 353 288 353 284 354 292 354 293 354 284 355 293 355 287 355 288 356 284 356 291 356 284 357 287 357 291 357 285 358 289 358 290 358 285 359 290 359 286 359 264 360 245 361 241 362 264 360 265 363 245 361 262 364 265 363 264 360 262 364 263 365 265 363 260 366 263 365 262 364 260 366 261 367 263 365 258 368 261 367 260 366 258 368 259 369 261 367 256 370 259 369 258 368 256 370 257 371 259 369 254 372 257 371 256 370 254 372 255 373 257 371 252 374 255 373 254 372 252 374 253 375 255 373 250 376 253 375 252 374 250 376 251 377 253 375 248 378 251 377 250 376 248 378 249 379 251 377 246 380 249 379 248 378 246 380 247 381 249 379 242 382 247 381 246 380 242 382 244 383 247 381 241 362 244 383 242 382 241 362 245 361 244 383 215 384 216 385 237 386 215 384 237 386 236 387 236 387 237 386 235 388 236 387 235 388 234 389 234 389 235 388 233 390 234 389 233 390 232 391 232 391 233 390 231 392 232 391 231 392 230 393 230 393 231 392 229 394 230 393 229 394 228 395 228 395 229 394 227 396 228 395 227 396 226 397 226 397 227 396 225 398 226 397 225 398 224 399 224 399 225 398 223 400 224 399 223 400 222 401 222 401 223 400 221 402 222 401 221 402 220 403 220 403 221 402 219 404 220 403 219 404 218 405 218 405 219 404 217 406 218 405 217 406 214 407 214 407 217 406 216 385 214 407 216 385 215 384 176 408 157 409 153 410 176 408 177 411 157 409 174 412 177 411 176 408 174 412 175 413 177 411 172 414 175 413 174 412 172 414 173 415 175 413 170 416 173 415 172 414 170 416 171 417 173 415 168 418 171 417 170 416 168 418 169 419 171 417 166 420 169 419 168 418 166 420 167 421 169 419 164 422 167 421 166 420 164 422 165 423 167 421 162 424 165 423 164 422 162 424 163 425 165 423 160 426 163 425 162 424 160 426 161 427 163 425 158 428 161 427 160 426 158 428 159 429 161 427 154 430 159 429 158 428 154 430 156 431 159 429 153 410 156 431 154 430 153 410 157 409 156 431 117 118 131 130 130 131 117 118 116 115 131 130 130 131 131 130 128 129 128 129 131 130 129 128 128 129 129 128 126 127 126 127 129 128 127 126 126 127 127 126 124 125 124 125 127 126 125 124 124 125 125 124 122 123 122 123 125 124 123 122 122 123 121 120 120 121 122 123 123 122 121 120 120 121 119 116 118 117 120 121 121 120 119 116 116 115 118 117 119 116 116 115 117 118 118 117 102 101 100 97 114 112 102 101 114 112 115 113 112 110 113 111 115 113 112 110 115 113 114 112 110 108 111 109 113 111 110 108 113 111 112 110 108 106 109 107 110 108 109 107 111 109 110 108 106 104 107 105 108 106 107 105 109 107 108 106 104 102 105 103 106 104 105 103 107 105 106 104 99 98 103 100 104 102 103 100 105 103 104 102 100 97 102 101 103 100 100 97 103 100 99 98 81 82 95 94 94 95 81 82 80 79 95 94 94 95 95 94 92 93 92 93 95 94 93 92 92 93 93 92 90 91 90 91 93 92 91 90 90 91 91 90 88 89 88 89 91 90 89 88 88 89 89 88 86 87 86 87 89 88 87 86 86 87 85 84 84 85 86 87 87 86 85 84 84 85 83 80 82 81 84 85 85 84 83 80 80 79 82 81 83 80 80 79 81 82 82 81 70 65 62 61 69 76 70 65 69 76 77 77 68 74 76 75 77 77 68 74 77 77 69 76 67 72 75 73 76 75 67 72 76 75 68 74 66 70 74 71 67 72 74 71 75 73 67 72 65 68 73 69 66 70 73 69 74 71 66 70 64 66 72 67 65 68 72 67 73 69 65 68 63 62 71 64 64 66 71 64 72 67 64 66 62 61 70 65 71 64 62 61 71 64 63 62 22 23 20 19 34 34 22 23 34 34 35 35 32 32 33 33 35 35 32 32 35 35 34 34 30 30 31 31 33 33 30 30 33 33 32 32 28 28 29 29 31 31 28 28 31 31 30 30 26 26 27 27 29 29 26 26 29 29 28 28 24 24 25 25 27 27 24 24 27 27 26 26 19 20 23 22 25 25 19 20 25 25 24 24 23 22 19 20 20 19 23 22 20 19 22 23 1 4 0 1 15 16 15 16 14 17 1 4 14 17 13 14 12 15 14 17 15 16 13 14 12 15 11 12 10 13 12 15 13 14 11 12 10 13 9 10 8 11 10 13 11 12 9 10 8 11 7 8 6 9 8 11 9 10 7 8 6 9 5 6 4 7 6 9 7 8 5 6 4 7 3 2 2 3 4 7 5 6 3 2 0 1 2 3 3 2 0 1 1 4 2 3

+
+ + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

137 134 136 134 135 134 135 135 136 135 134 135 137 138 139 138 138 138 138 139 139 139 134 139 137 142 141 142 140 142 140 143 141 143 134 143 137 146 143 146 142 146 142 147 143 147 134 147 137 150 145 150 144 150 144 151 145 151 134 151 137 154 147 154 146 154 146 155 147 155 134 155 137 158 149 158 148 158 148 159 149 159 134 159 137 162 151 162 150 162 150 163 151 163 134 163 178 188 180 188 179 188 181 189 180 189 178 189 183 192 182 192 179 192 181 193 182 193 183 193 185 196 184 196 179 196 181 197 184 197 185 197 187 200 186 200 179 200 181 201 186 201 187 201 189 204 188 204 179 204 181 205 188 205 189 205 191 208 190 208 179 208 181 209 190 209 191 209 193 212 192 212 179 212 181 213 192 213 193 213 195 216 194 216 179 216 181 217 194 217 195 217 199 222 200 222 197 222 197 223 200 223 198 223 199 226 202 226 201 226 201 227 202 227 198 227 199 230 204 230 203 230 203 231 204 231 198 231 199 234 206 234 205 234 205 235 206 235 198 235 199 238 208 238 207 238 207 239 208 239 198 239 199 242 210 242 209 242 209 243 210 243 198 243 199 246 212 246 211 246 211 247 212 247 198 247 199 250 196 250 213 250 213 251 196 251 198 251 266 300 268 300 267 300 269 301 268 301 266 301 271 304 270 304 267 304 269 305 270 305 271 305 273 308 272 308 267 308 269 309 272 309 273 309 275 312 274 312 267 312 269 313 274 313 275 313 277 316 276 316 267 316 269 317 276 317 277 317 279 320 278 320 267 320 269 321 278 321 279 321 281 324 280 324 267 324 269 325 280 325 281 325 283 328 282 328 267 328 269 329 282 329 283 329

+
+
+ 1 +
+
+ + + + 0 0 0 + 0 0 1 0 + 0 1 0 0 + 1 0 0 0 + 0.1335572 0.1335572 0.1335572 + + + + + + + + + + + + + + + + +
diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/quadrotor_base (å¤ä»¶).dae b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/quadrotor_base (å¤ä»¶).dae new file mode 100644 index 0000000..5bc4e16 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/quadrotor_base (å¤ä»¶).dae @@ -0,0 +1,238 @@ + + + + + Stefan Kohlbrecher + Blender 2.61.4 r43829 + + 2012-02-03T14:20:49 + 2012-02-03T14:20:49 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.1 0.1 0.1 1 + + + 1 0 0.0106101 1 + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 1 1 1 1 + + + + 1 1 1 1 + + + + 1 1 1 1 + + + + 1 1 1 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 0 0 0 1 + + + 0.1 0.1 0.1 1 + + + 0.05496641 0.05496641 0.05496641 1 + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 0.15 0.15 0.15 1 + + + 0.23 0.23 0.23 1 + + + 0.5 0.5 0.5 1 + + + 1 1 1 1 + + + 20 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + + + + + + + + + + + + + + + 0.8236175 0.673869 -1.366201 -0.8236175 0.6738689 -1.366201 -0.8236175 0.6852639 -1.361481 0.8236175 0.6852641 -1.361481 -0.8236175 0.6899839 -1.350086 0.8236175 0.689984 -1.350086 -0.8236175 0.6852639 -1.338691 0.8236175 0.685264 -1.338691 -0.8236175 0.6738689 -1.333971 0.8236175 0.673869 -1.333971 -0.8236175 0.6624739 -1.338691 0.8236175 0.662474 -1.338691 -0.8236175 0.657754 -1.350086 0.8236175 0.6577541 -1.350086 -0.8236175 0.6624739 -1.361481 0.8236175 0.6624741 -1.361481 0.8236175 0.673869 -1.350086 -0.8236175 0.6738689 -1.350086 0.8236174 -0.6738691 -1.350086 0.8236174 -0.662474 -1.361481 0.8236174 -0.6738691 -1.366201 -0.8236175 -0.6738691 -1.350086 -0.8236175 -0.6738691 -1.366201 -0.8236175 -0.6624742 -1.361481 0.8236174 -0.6577541 -1.350086 -0.8236175 -0.6577541 -1.350086 0.8236174 -0.662474 -1.338691 -0.8236175 -0.662474 -1.338691 0.8236174 -0.6738691 -1.333971 -0.8236175 -0.6738691 -1.333971 0.8236174 -0.6852641 -1.338691 -0.8236175 -0.6852641 -1.338691 0.8236174 -0.689984 -1.350086 -0.8236175 -0.689984 -1.350086 0.8236174 -0.6852641 -1.361481 -0.8236175 -0.6852641 -1.361481 0.5614412 0.08138328 0 0.5614412 0.07047998 -0.04069161 0.5614412 0.04069161 -0.07047998 0.5614412 0 -0.08138328 0.5614412 -0.04069161 -0.07047998 0.5614413 -0.07047998 -0.04069161 0.5614413 -0.08138328 0 0.5614413 -0.07047998 0.04069155 0.5614412 -0.04069167 0.07047992 0.5614412 0 0.08138328 0.5614412 0.04069155 0.07047998 0.5614412 0.07047992 0.04069167 2.084521 0.08138328 0 2.084521 0.07048004 -0.04069155 2.084521 0.04069167 -0.07047986 2.084521 0 -0.08138328 2.084521 -0.04069155 -0.07047998 2.084521 -0.07047986 -0.04069167 2.084521 -0.08138328 0 2.084521 -0.07048004 0.04069155 2.084521 -0.04069173 0.07047992 2.084521 0 0.08138328 2.084521 0.04069155 0.07048004 2.084521 0.07047992 0.04069173 0.5614412 0 0 2.084521 0 0 0.6738689 0.6899839 -1.332763 0.6852639 0.6852639 -1.332763 0.6899839 0.6738689 -1.332763 0.6852639 0.6624739 -1.332763 0.6738689 0.657754 -1.332763 0.6624739 0.6624739 -1.332763 0.657754 0.6738689 -1.332763 0.6624739 0.6852639 -1.332763 0.2994973 0.3156122 -0.303241 0.3108922 0.3108922 -0.303241 0.3156122 0.2994973 -0.303241 0.3108922 0.2881023 -0.303241 0.2994973 0.2833823 -0.303241 0.2881022 0.2881023 -0.303241 0.2833823 0.2994973 -0.303241 0.2881023 0.3108922 -0.303241 0.6738689 0.6738689 -1.332763 0.2994973 0.2994973 -0.303241 0.3156121 -0.2994973 -0.303241 0.6899838 -0.673869 -1.332763 0.6852638 -0.6624739 -1.332763 0.3108922 -0.2881023 -0.303241 0.6738688 -0.657754 -1.332763 0.2994972 -0.2833823 -0.303241 0.6624738 -0.6624739 -1.332763 0.2881022 -0.2881023 -0.303241 0.6577539 -0.673869 -1.332763 0.2833822 -0.2994973 -0.303241 0.6624738 -0.6852639 -1.332763 0.2881022 -0.3108923 -0.303241 0.6738688 -0.6899839 -1.332763 0.2994972 -0.3156122 -0.303241 0.6852638 -0.6852639 -1.332763 0.3108922 -0.3108922 -0.303241 0.2994972 -0.2994973 -0.303241 0.6738688 -0.673869 -1.332763 -0.673869 -0.6738688 -1.332763 -0.685264 -0.6852638 -1.332763 -0.6738691 -0.6899837 -1.332763 -0.2994973 -0.2994972 -0.303241 -0.2994973 -0.3156121 -0.303241 -0.3108923 -0.3108922 -0.303241 -0.689984 -0.6738687 -1.332763 -0.3156123 -0.2994972 -0.303241 -0.685264 -0.6624737 -1.332763 -0.3108923 -0.2881022 -0.303241 -0.673869 -0.6577538 -1.332763 -0.2994973 -0.2833822 -0.303241 -0.662474 -0.6624737 -1.332763 -0.2881023 -0.2881022 -0.303241 -0.6577541 -0.6738688 -1.332763 -0.2833824 -0.2994972 -0.303241 -0.662474 -0.6852638 -1.332763 -0.2881023 -0.3108922 -0.303241 -0.3156121 0.2994973 -0.303241 -0.6899837 0.6738693 -1.332763 -0.6852637 0.662474 -1.332763 -0.3108922 0.2881023 -0.303241 -0.6738687 0.6577541 -1.332763 -0.2994971 0.2833824 -0.303241 -0.6624737 0.662474 -1.332763 -0.2881022 0.2881023 -0.303241 -0.6577537 0.6738691 -1.332763 -0.2833822 0.2994973 -0.303241 -0.6624737 0.6852641 -1.332763 -0.2881022 0.3108924 -0.303241 -0.6738685 0.689984 -1.332763 -0.2994971 0.3156123 -0.303241 -0.6852637 0.6852641 -1.332763 -0.3108922 0.3108923 -0.303241 -0.2994971 0.2994973 -0.303241 -0.6738687 0.6738691 -1.332763 1.969194 0 0.1871857 2.886225 -0.3798463 0.2218515 2.671059 -0.7018645 0.2218514 1.969194 0 0.2620601 2.349041 -0.9170302 0.2218514 1.969195 -0.9925863 0.2218514 1.589348 -0.9170302 0.2218514 1.26733 -0.7018646 0.2218514 1.052164 -0.3798465 0.2218515 0.9766083 -2.36674e-7 0.2218515 1.052164 0.379846 0.2218516 1.26733 0.7018642 0.2218517 1.589348 0.9170299 0.2218517 1.969194 0.992586 0.2218518 2.34904 0.91703 0.2218517 2.671058 0.7018645 0.2218517 2.886224 0.3798464 0.2218516 2.96178 3.25924e-7 0.2218515 0 -0.5614412 0 0.08138316 -0.5614412 0 0.07047986 -0.5614412 -0.04069161 -2.69139e-7 -2.084521 0 0.07047975 -2.084521 -0.04069155 0.08138298 -2.084521 0 0.04069155 -0.5614412 -0.07047998 0.04069143 -2.084521 -0.07047992 0 -0.5614412 -0.08138328 -1.69274e-7 -2.084521 -0.08138328 -0.04069167 -0.5614412 -0.07047998 -0.04069179 -2.084521 -0.07047998 -0.07048004 -0.5614413 -0.04069167 -0.07048016 -2.084521 -0.04069167 -0.08138334 -0.5614413 0 -0.08138352 -2.084521 0 -0.07048004 -0.5614413 0.04069161 -0.07048028 -2.084521 0.04069155 -0.04069173 -0.5614412 0.07047998 -0.04069197 -2.084521 0.07047992 -1.3514e-7 -0.5614412 0.08138328 -3.81294e-7 -2.084521 0.08138328 0.04069143 -0.5614412 0.07047998 0.04069125 -2.084521 0.07048004 0.07047986 -0.5614412 0.04069167 0.07047963 -2.084521 0.04069173 0.379846 -2.886224 0.2218516 -2.61752e-7 -1.969194 0.1871857 0 -2.96178 0.2218515 -3.25223e-7 -1.969194 0.2620601 0.7018641 -2.671058 0.2218517 0.9170297 -2.34904 0.2218517 0.9925858 -1.969194 0.2218517 0.9170296 -1.589348 0.2218517 0.701864 -1.26733 0.2218517 0.3798459 -1.052164 0.2218516 -3.6789e-7 -0.9766083 0.2218515 -0.3798466 -1.052164 0.2218514 -0.7018647 -1.26733 0.2218514 -0.9170304 -1.589348 0.2218513 -0.9925865 -1.969194 0.2218513 -0.9170305 -2.34904 0.2218513 -0.7018648 -2.671059 0.2218514 -0.3798467 -2.886225 0.2218514 -2.96178 4.69959e-7 0.2218515 -2.886225 0.3798471 0.2218514 -1.969194 5.26331e-7 0.1871857 -1.969194 5.89802e-7 0.2620601 -2.671059 0.7018652 0.2218514 -2.34904 0.9170308 0.2218513 -1.969194 0.9925867 0.2218513 -1.589348 0.9170306 0.2218513 -1.26733 0.7018649 0.2218514 -1.052164 0.3798468 0.2218514 -0.9766083 4.99106e-7 0.2218515 -1.052164 -0.3798457 0.2218516 -1.26733 -0.7018638 0.2218517 -1.589348 -0.9170294 0.2218517 -1.969194 -0.9925855 0.2218517 -2.349041 -0.9170294 0.2218517 -2.671058 -0.7018638 0.2218517 -2.886224 -0.3798456 0.2218516 -0.5614412 -0.07047981 0.04069167 -0.5614412 -0.0813831 0 -2.084521 -0.08138269 0 -2.084521 -0.07047933 0.04069173 -0.5614412 -0.04069137 0.07047998 -2.084521 -0.04069095 0.07048004 -0.5614412 2.10574e-7 0.08138328 -2.084521 6.61367e-7 0.08138328 -0.5614412 0.04069179 0.07047998 -2.084521 0.04069226 0.07047992 -0.5614413 0.0704801 0.04069161 -2.084521 0.07048058 0.04069155 -0.5614413 0.0813834 0 -2.084521 0.08138382 0 -0.5614413 0.0704801 -0.04069167 -2.084521 0.07048046 -0.04069167 -0.5614412 0.04069179 -0.07047998 -2.084521 0.04069209 -0.07047998 -0.5614412 1.54427e-7 -0.08138328 -2.084521 4.49347e-7 -0.08138328 -0.5614412 -0.04069149 -0.07047998 -2.084521 -0.04069113 -0.07047992 -0.5614412 -0.07047981 -0.04069161 -2.084521 -0.07047945 -0.04069155 -2.084521 5.49213e-7 0 -0.5614412 1.61804e-7 0 2.37238e-7 0.5614412 0 -0.08138304 0.5614412 0 -0.07047975 0.5614412 -0.04069161 8.29287e-7 2.084521 0 -0.07047921 2.084521 -0.04069155 -0.08138245 2.084521 0 -0.04069137 0.5614412 -0.07047998 -0.04069083 2.084521 -0.07047992 2.29861e-7 0.5614412 -0.08138328 7.29421e-7 2.084521 -0.08138328 0.04069185 0.5614412 -0.07047998 0.04069238 2.084521 -0.07047998 0.07048016 0.5614413 -0.04069167 0.07048076 2.084521 -0.04069167 0.08138352 0.5614413 0 0.08138412 2.084521 0 0.07048022 0.5614413 0.04069161 0.07048088 2.084521 0.04069155 0.04069191 0.5614412 0.07047998 0.04069256 2.084521 0.07047992 2.86009e-7 0.5614412 0.08138328 9.41441e-7 2.084521 0.08138328 -0.04069131 0.5614412 0.07047998 -0.04069072 2.084521 0.07048004 -0.07047975 0.5614412 0.04069167 -0.07047903 2.084521 0.04069173 -0.3798453 2.886224 0.2218516 7.9091e-7 1.969194 0.1871857 8.67901e-7 2.96178 0.2218515 8.54381e-7 1.969194 0.2620601 -0.7018634 2.671058 0.2218517 -0.9170291 2.349041 0.2218517 -0.9925853 1.969195 0.2218517 -0.9170292 1.589348 0.2218517 -0.7018637 1.26733 0.2218517 -0.3798456 1.052164 0.2218516 6.30322e-7 0.9766083 0.2218515 0.3798469 1.052164 0.2218514 0.7018651 1.26733 0.2218514 0.9170309 1.589348 0.2218513 0.992587 1.969194 0.2218513 0.9170311 2.34904 0.2218513 0.7018656 2.671059 0.2218514 0.3798475 2.886225 0.2218514 0.3369342 0.5615574 -0.2994973 0.3369344 -0.5615572 -0.2994973 -0.3369344 -0.5615574 -0.2994973 -0.3369344 0.5615576 -0.2994973 0.3369346 0.5615574 0.2994973 0.3369344 -0.5615576 0.2994973 -0.3369344 -0.5615574 0.2994973 -0.3369344 0.5615572 0.2994973 0.5615572 0.3369344 -0.2994973 -0.5615572 0.3369347 -0.2994973 0.5615576 0.3369343 0.2994973 -0.5615572 0.3369344 0.2994973 0.5615572 -0.3369344 -0.2994973 -0.5615575 -0.3369343 -0.2994973 0.5615574 -0.3369347 0.2994973 -0.5615575 -0.3369344 0.2994973 + + + + + + + + + + 1 0 0 0.6302378 0 -0.7763603 0.6302378 0.548967 -0.548967 -0.6302378 0.548967 -0.548967 -0.6302378 0 -0.7763603 -1 0 0 0.6302378 0.7763603 0 -0.6302378 0.7763603 0 0.6302378 0.548967 0.548967 -0.6302378 0.548967 0.548967 0.6302378 0 0.7763603 -0.6302378 0 0.7763603 0.6302378 -0.548967 0.548967 -0.6302378 -0.548967 0.548967 0.6302378 -0.7763603 0 -0.6302378 -0.7763603 0 0.6302378 -0.548967 -0.548967 -0.6302378 -0.548967 -0.548967 1 0 0 0.6302378 0 -0.7763603 0.6302378 0.548967 -0.548967 -1 0 0 -0.6302378 0.548967 -0.548967 -0.6302378 0 -0.7763603 0.6302378 0.7763603 0 -0.6302378 0.7763603 0 0.6302378 0.548967 0.548967 -0.6302378 0.548967 0.548967 0.6302378 0 0.7763603 -0.6302378 0 0.7763603 0.6302378 -0.548967 0.548967 -0.6302378 -0.548967 0.548967 0.6302378 -0.7763603 0 -0.6302378 -0.7763603 0 0.6302378 -0.548967 -0.548967 -0.6302378 -0.548967 -0.548967 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 -2.53709e-6 1.46479e-6 1 0 0 -1 -1.46479e-6 -3.92489e-7 1 0 0 -1 -1.46479e-6 3.92489e-7 1 0 0 -1 -2.53709e-6 -1.46479e-6 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 0 0 -1 0.06228822 0.8714866 -0.486404 0.6329844 0.6329844 -0.4456618 0 0 1 0.4264656 0.4264656 0.7976318 -0.06045717 0.6646626 0.7446516 0.8714866 0.06228822 -0.486404 0.6646626 -0.06045717 0.7446516 0.6226387 -0.4941862 -0.6066775 0.4941862 -0.6226387 0.6066775 0.06045717 -0.6646626 -0.7446516 -0.06228822 -0.8714866 0.486404 -0.4264656 -0.4264656 -0.7976318 -0.6329844 -0.6329844 0.4456618 -0.6646626 0.06045717 -0.7446516 -0.8714866 -0.06228822 0.486404 -0.4941862 0.6226387 -0.6066775 -0.6226387 0.4941862 0.6066775 0 0 1 0.6646626 0.06045717 0.7446516 0.4941862 0.6226387 0.6066775 0.6226387 0.4941862 -0.6066775 0.8714866 -0.06228822 -0.486404 0 0 -1 -0.06228822 0.8714866 0.486404 0.06045717 0.6646626 -0.7446516 -0.6329844 0.6329844 0.4456618 -0.4264656 0.4264656 -0.7976318 -0.8714866 0.06228822 0.486404 -0.6646626 -0.06045717 -0.7446516 -0.6226387 -0.4941862 0.6066775 -0.4941862 -0.6226387 -0.6066775 -0.06045717 -0.6646626 0.7446516 0.06228822 -0.8714866 -0.486404 0.4264656 -0.4264656 0.7976318 0.6329844 -0.6329844 -0.4456618 0 0 -1 -0.06228822 -0.8714866 -0.486404 -0.6329844 -0.6329844 -0.4456618 0 0 1 -0.4264656 -0.4264656 0.7976318 0.06045717 -0.6646626 0.7446516 -0.8714866 -0.06228822 -0.486404 -0.6646626 0.06045717 0.7446516 -0.6226387 0.4941862 -0.6066775 -0.4941862 0.6226387 0.6066775 -0.06045717 0.6646626 -0.7446516 0.06228822 0.8714866 0.486404 0.4264656 0.4264656 -0.7976318 0.6329844 0.6329844 0.4456618 0.6646626 -0.06045717 -0.7446516 0.8714866 0.06228822 0.486404 0.4941862 -0.6226387 -0.6066775 0.6226387 -0.4941862 0.6066775 0 0 1 -0.6646626 -0.06045717 0.7446516 -0.4941862 -0.6226387 0.6066775 -0.6226387 -0.4941862 -0.6066775 -0.8714866 0.06228822 -0.486404 0 0 -1 0.06228822 -0.8714866 0.486404 -0.06045717 -0.6646626 -0.7446516 0.6329844 -0.6329844 0.4456618 0.4264656 -0.4264656 -0.7976318 0.8714866 -0.06228822 0.486404 0.6646626 0.06045717 -0.7446516 0.6226387 0.4941862 0.6066775 0.4941862 0.6226387 -0.6066775 0.06045717 0.6646626 0.7446516 -0.06228822 0.8714866 -0.486404 -0.4264656 0.4264656 0.7976318 -0.6329844 0.6329844 -0.4456618 0.03490257 -0.006942212 -0.9993667 0.04047429 -0.008050978 0.9991481 0.03431242 -0.02292704 0.9991481 0.02958893 -0.0197705 -0.9993667 0.01977074 -0.02958875 -0.9993666 0.02292686 -0.03431266 0.9991481 0.008050799 -0.04047453 0.9991481 0.00694251 -0.03490239 -0.9993667 -0.00694251 -0.03490239 -0.9993667 -0.008050799 -0.04047447 0.9991481 -0.02292686 -0.03431266 0.9991481 -0.01977074 -0.02958875 -0.9993666 -0.02958893 -0.01977056 -0.9993666 -0.03431248 -0.02292704 0.9991481 -0.04047429 -0.008051037 0.9991481 -0.03490257 -0.006942331 -0.9993666 -0.03490257 0.006942749 -0.9993666 -0.04047429 0.00805062 0.9991481 -0.03431248 0.02292662 0.999148 -0.02958899 0.01977092 -0.9993666 -0.01977074 0.02958917 -0.9993667 -0.02292686 0.03431224 0.9991482 -0.008050799 0.04047405 0.9991481 -0.00694251 0.03490281 -0.9993667 0.00694251 0.03490281 -0.9993667 0.008050799 0.04047411 0.9991481 0.0229268 0.03431224 0.9991482 0.01977074 0.02958923 -0.9993667 0.02958899 0.01977092 -0.9993667 0.03431248 0.02292662 0.9991481 0.04047429 0.00805062 0.9991481 0.03490257 0.006942749 -0.9993667 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 -2.53709e-6 1 1.46479e-6 0 -1 0 -1.46479e-6 1 -3.92489e-7 0 -1 0 -1.46479e-6 1 3.92489e-7 0 -1 0 -2.53709e-6 1 -1.46479e-6 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0.006942689 -0.03490263 -0.9993667 0.00805068 -0.04047423 0.9991481 0.02292662 -0.03431242 0.9991482 0.01977092 -0.02958899 -0.9993667 0.02958923 -0.01977068 -0.9993667 0.03431218 -0.02292686 0.9991481 0.04047405 -0.008050739 0.9991482 0.03490281 -0.00694257 -0.9993666 0.03490281 0.00694257 -0.9993667 0.04047405 0.008050799 0.9991481 0.03431218 0.02292686 0.9991481 0.02958923 0.01977068 -0.9993667 0.01977092 0.02958899 -0.9993666 0.02292662 0.03431242 0.9991481 0.00805062 0.04047423 0.9991481 0.006942689 0.03490263 -0.9993666 -0.006942212 0.03490263 -0.9993666 -0.008051097 0.04047423 0.9991481 -0.02292704 0.03431242 0.9991481 -0.0197705 0.02958893 -0.9993666 -0.02958869 0.01977074 -0.9993666 -0.03431266 0.0229268 0.9991481 -0.04047447 0.008050858 0.9991481 -0.03490233 0.00694251 -0.9993667 -0.03490233 -0.00694251 -0.9993667 -0.04047447 -0.008050858 0.9991481 -0.03431266 -0.0229268 0.9991481 -0.02958875 -0.01977074 -0.9993667 -0.0197705 -0.02958893 -0.9993667 -0.02292704 -0.03431242 0.9991481 -0.008051037 -0.04047423 0.999148 -0.006942152 -0.03490263 -0.9993667 -0.03490263 0.006942152 -0.9993667 -0.04047423 0.008051037 0.9991481 -0.03431242 0.02292704 0.9991481 -0.02958893 0.0197705 -0.9993667 -0.01977068 0.02958875 -0.9993666 -0.02292674 0.03431272 0.9991482 -0.008050858 0.04047447 0.9991481 -0.006942451 0.03490233 -0.9993666 0.00694251 0.03490239 -0.9993667 0.008050858 0.04047447 0.9991481 0.0229268 0.03431266 0.9991481 0.01977074 0.02958869 -0.9993666 0.02958893 0.0197705 -0.9993666 0.03431248 0.02292698 0.9991481 0.04047423 0.008051097 0.9991481 0.03490263 0.006942212 -0.9993666 0.03490263 -0.006942689 -0.9993666 0.04047423 -0.00805062 0.9991481 0.03431242 -0.02292662 0.9991482 0.02958899 -0.01977092 -0.9993667 0.01977068 -0.02958923 -0.9993667 0.02292686 -0.03431218 0.9991481 0.008050799 -0.04047405 0.9991481 0.00694257 -0.03490281 -0.9993667 -0.00694257 -0.03490281 -0.9993667 -0.008050799 -0.04047405 0.9991481 -0.02292686 -0.03431218 0.9991482 -0.01977068 -0.02958917 -0.9993667 -0.02958899 -0.01977092 -0.9993667 -0.03431242 -0.02292662 0.9991482 -0.04047423 -0.00805068 0.9991481 -0.03490263 -0.006942689 -0.9993667 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 2.53709e-6 -1.46479e-6 -1 0 0 1 1.46479e-6 3.92489e-7 -1 0 0 1 1.46479e-6 -3.92489e-7 -1 0 0 1 2.53709e-6 1.46479e-6 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 2.53709e-6 -1 1.46479e-6 0 1 0 1.46479e-6 -1 -3.92489e-7 0 1 0 1.46479e-6 -1 3.92489e-7 0 1 0 2.53709e-6 -1 -1.46479e-6 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 -0.006942689 0.03490263 -0.9993667 -0.00805068 0.04047423 0.9991481 -0.02292662 0.03431242 0.9991482 -0.01977092 0.02958899 -0.9993667 -0.02958917 0.01977074 -0.9993666 -0.03431218 0.02292692 0.9991483 -0.04047405 0.008050799 0.9991482 -0.03490281 0.00694257 -0.9993666 -0.03490281 -0.00694257 -0.9993667 -0.04047405 -0.008050799 0.9991481 -0.03431218 -0.02292686 0.9991481 -0.02958923 -0.01977068 -0.9993666 -0.01977092 -0.02958899 -0.9993667 -0.02292662 -0.03431242 0.9991481 -0.00805062 -0.04047423 0.9991481 -0.006942689 -0.03490263 -0.9993666 0.006942212 -0.03490263 -0.9993666 0.008051097 -0.04047423 0.9991481 0.02292698 -0.03431248 0.9991482 0.0197705 -0.02958899 -0.9993667 0.02958869 -0.01977074 -0.9993667 0.03431266 -0.0229268 0.999148 0.04047447 -0.008050858 0.9991481 0.03490233 -0.00694251 -0.9993667 0.03490239 0.006942451 -0.9993667 0.04047447 0.008050858 0.9991481 0.03431272 0.02292674 0.9991481 0.02958875 0.01977068 -0.9993667 0.0197705 0.02958893 -0.9993667 0.02292704 0.03431242 0.9991481 0.008051037 0.04047423 0.9991481 0.006942152 0.03490263 -0.9993667 -1 3.53806e-7 0 -1 3.53806e-7 0 -0.7071067 -0.707107 -1.40725e-7 -0.7071068 -0.7071068 0 0.7071068 -0.7071069 -4.92539e-7 0.7071067 -0.7071068 -4.8945e-7 1 -3.53806e-7 -1.99016e-7 1 0 -5.97047e-7 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.7071067 0.7071068 3.9156e-7 -0.7071068 0.7071067 4.92539e-7 0.7071067 0.7071068 -5.2772e-7 0.707107 0.7071065 -3.13248e-7 0 0 1 0 0 1 0 0 -1 0 0 -1 -2.65354e-7 1 0 3.53806e-7 1 6.96555e-7 -3.53806e-7 -1 -6.96555e-7 2.65354e-7 -1 0 -0.6557207 -0.6532182 0.3785516 -0.7571337 0.6532182 0 -0.7571337 -0.6532182 0 -0.6557207 0.6532182 0.3785516 -0.3785516 -0.6532182 0.6557207 -0.3785516 0.6532182 0.6557207 0 -0.6532182 0.7571337 0 0.6532182 0.7571337 0.3785516 -0.6532182 0.6557207 0.3785821 0.6532182 0.6557207 0.6557207 -0.6532182 0.3785516 0.6557207 0.6532182 0.3785516 0.7571337 -0.6532182 0 0.7571337 0.6532182 0 0.6557207 -0.6532182 -0.3785516 0.6557207 0.6532182 -0.3785516 0.3785516 -0.6532182 -0.6557207 0.3785516 0.6532182 -0.6557207 0 -0.6532182 -0.7571337 0 0.6532182 -0.7571337 -0.3785516 -0.6532182 -0.6557207 -0.3785516 0.6532182 -0.6557207 -0.6557207 -0.6532182 -0.3785516 -0.6557207 0.6532182 -0.3785516 0.6532182 -0.7571337 0 -0.6532182 -0.7571337 0 -0.6532182 -0.6557207 -0.3785516 0.6532182 -0.6557207 -0.3785516 -0.6532182 -0.3785516 -0.6557207 0.6532182 -0.3785516 -0.6557207 -0.6532182 0 -0.7571337 0.6532182 0 -0.7571337 -0.6532182 0.3785516 -0.6557207 0.6532182 0.3785516 -0.6557207 -0.6532182 0.6557207 -0.3785516 0.6532182 0.6557207 -0.3785516 -0.6532182 0.7571337 0 0.6532182 0.7571337 0 -0.6532182 0.6557207 0.3785516 0.6532182 0.6557207 0.3785516 -0.6532182 0.3785821 0.6557207 0.6532182 0.3785821 0.6557207 -0.6532182 0 0.7571337 0.6532182 0 0.7571337 -0.6532182 -0.3785516 0.6557207 0.6532182 -0.3785516 0.6557207 -0.6532182 -0.6557207 0.3785516 0.6532182 -0.6557207 0.3785516 0.6557207 0.6532182 0.3785516 0.7571337 -0.6532182 0 0.7571337 0.6532182 0 0.6557207 -0.6532182 0.3785516 0.3785516 0.6532182 0.6557207 0.3785516 -0.6532182 0.6557207 0 0.6532182 0.7571337 0 -0.6532182 0.7571337 -0.3785821 0.6532182 0.6557207 -0.3785821 -0.6532182 0.6557207 -0.6557207 0.6532182 0.3785516 -0.6557207 -0.6532182 0.3785516 -0.7571337 0.6532182 0 -0.7571337 -0.6532182 0 -0.6557207 0.6532182 -0.3785516 -0.6557207 -0.6532182 -0.3785516 -0.3785516 0.6532182 -0.6557207 -0.3785516 -0.6532182 -0.6557207 0 0.6532182 -0.7571337 0 -0.6532182 -0.7571337 0.3785516 0.6532182 -0.6557207 0.3785516 -0.6532182 -0.6557207 0.6557207 0.6532182 -0.3785516 0.6557207 -0.6532182 -0.3785516 0.6532182 0.7571337 0 -0.6532182 0.7571337 0 -0.6532182 0.6557207 0.3785516 0.6532182 0.6557207 0.3785516 -0.6532182 0.3785516 0.6557207 0.6532182 0.3785516 0.6557207 -0.6532182 0 0.7571337 0.6532182 0 0.7571337 -0.6532182 -0.3785821 0.6556902 0.6532182 -0.3785821 0.6557207 -0.6532182 -0.6557207 0.3785516 0.6532182 -0.6557207 0.3785516 -0.6532182 -0.7571337 0 0.6532182 -0.7571337 0 -0.6532182 -0.6557207 -0.3785516 0.6532182 -0.6557207 -0.3785516 -0.6532182 -0.3785516 -0.6557207 0.6532182 -0.3785516 -0.6557207 -0.6532182 0 -0.7571337 0.6532182 0 -0.7571337 -0.6532182 0.3785516 -0.6557207 0.6532182 0.3785516 -0.6557207 -0.6532182 0.6557207 -0.3785516 0.6532182 0.6557207 -0.3785516 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

60 36 36 36 37 36 61 37 49 37 48 37 60 38 37 38 38 38 61 39 50 39 49 39 60 40 38 40 39 40 61 41 51 41 50 41 60 42 39 42 40 42 61 43 52 43 51 43 60 44 40 44 41 44 61 45 53 45 52 45 60 46 41 46 42 46 61 47 54 47 53 47 60 48 42 48 43 48 61 49 55 49 54 49 60 50 43 50 44 50 61 51 56 51 55 51 60 52 44 52 45 52 61 53 57 53 56 53 60 54 45 54 46 54 61 55 58 55 57 55 60 56 46 56 47 56 61 57 59 57 58 57 47 58 36 58 60 58 61 59 48 59 59 59 48 432 36 433 47 434 48 432 47 434 59 435 46 436 58 437 59 435 46 436 59 435 47 434 45 438 57 439 58 437 45 438 58 437 46 436 44 440 56 441 57 439 44 440 57 439 45 438 43 442 55 443 56 441 43 442 56 441 44 440 42 444 54 445 55 443 42 444 55 443 43 442 41 446 53 447 54 445 41 446 54 445 42 444 40 448 52 449 53 447 40 448 53 447 41 446 39 450 51 451 52 449 39 450 52 449 40 448 38 452 50 453 51 451 38 452 51 451 39 450 37 454 49 455 50 453 37 454 50 453 38 452 36 433 48 432 49 455 36 433 49 455 37 454

+
+ + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

151 132 135 132 134 132 137 133 135 133 151 133 136 136 138 136 134 136 137 137 138 137 136 137 139 140 140 140 134 140 137 141 140 141 139 141 141 144 142 144 134 144 137 145 142 145 141 145 143 148 144 148 134 148 137 149 144 149 143 149 145 152 146 152 134 152 137 153 146 153 145 153 147 156 148 156 134 156 137 157 148 157 147 157 149 160 150 160 134 160 137 161 150 161 149 161 181 190 178 190 182 190 182 191 178 191 179 191 181 194 183 194 184 194 184 195 183 195 179 195 181 198 185 198 186 198 186 199 185 199 179 199 181 202 187 202 188 202 188 203 187 203 179 203 181 206 189 206 190 206 190 207 189 207 179 207 181 210 191 210 192 210 192 211 191 211 179 211 181 214 193 214 194 214 194 215 193 215 179 215 181 218 195 218 180 218 180 219 195 219 179 219 196 220 197 220 198 220 199 221 197 221 196 221 200 224 201 224 198 224 199 225 201 225 200 225 202 228 203 228 198 228 199 229 203 229 202 229 204 232 205 232 198 232 199 233 205 233 204 233 206 236 207 236 198 236 199 237 207 237 206 237 208 240 209 240 198 240 199 241 209 241 208 241 210 244 211 244 198 244 199 245 211 245 210 245 212 248 213 248 198 248 199 249 213 249 212 249 269 302 266 302 270 302 270 303 266 303 267 303 269 306 271 306 272 306 272 307 271 307 267 307 269 310 273 310 274 310 274 311 273 311 267 311 269 314 275 314 276 314 276 315 275 315 267 315 269 318 277 318 278 318 278 319 277 319 267 319 269 322 279 322 280 322 280 323 279 323 267 323 269 326 281 326 282 326 282 327 281 327 267 327 269 330 283 330 268 330 268 331 283 331 267 331

+
+ + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

16 0 0 1 3 2 2 3 1 4 17 5 16 0 3 2 5 6 17 5 4 7 2 3 16 0 5 6 7 8 17 5 6 9 4 7 16 0 7 8 9 10 17 5 8 11 6 9 16 0 9 10 11 12 17 5 10 13 8 11 16 0 11 12 13 14 17 5 12 15 10 13 16 0 13 14 15 16 17 5 14 17 12 15 15 16 0 1 16 0 17 5 1 4 14 17 18 18 20 19 19 20 21 21 23 22 22 23 18 18 19 20 24 24 21 21 25 25 23 22 18 18 24 24 26 26 21 21 27 27 25 25 18 18 26 26 28 28 21 21 29 29 27 27 18 18 28 28 30 30 21 21 31 31 29 29 18 18 30 30 32 32 21 21 33 33 31 31 18 18 32 32 34 34 21 21 35 35 33 33 34 34 20 19 18 18 35 35 21 21 22 23 78 60 62 61 63 62 79 63 71 64 70 65 78 60 63 62 64 66 79 63 72 67 71 64 78 60 64 66 65 68 79 63 73 69 72 67 78 60 65 68 66 70 79 63 74 71 73 69 78 60 66 70 67 72 79 63 75 73 74 71 78 60 67 72 68 74 79 63 76 75 75 73 78 60 68 74 69 76 79 63 77 77 76 75 69 76 62 61 78 60 79 63 70 65 77 77 96 78 80 79 83 80 82 81 81 82 97 83 96 78 83 80 85 84 97 83 84 85 82 81 96 78 85 84 87 86 97 83 86 87 84 85 96 78 87 86 89 88 97 83 88 89 86 87 96 78 89 88 91 90 97 83 90 91 88 89 96 78 91 90 93 92 97 83 92 93 90 91 96 78 93 92 95 94 97 83 94 95 92 93 96 78 95 94 80 79 97 83 81 82 94 95 98 96 100 97 99 98 101 99 103 100 102 101 98 96 99 98 104 102 101 99 105 103 103 100 98 96 104 102 106 104 101 99 107 105 105 103 98 96 106 104 108 106 101 99 109 107 107 105 98 96 108 106 110 108 101 99 111 109 109 107 98 96 110 108 112 110 101 99 113 111 111 109 98 96 112 110 114 112 101 99 115 113 113 111 114 112 100 97 98 96 101 99 102 101 115 113 132 114 116 115 119 116 118 117 117 118 133 119 132 114 119 116 121 120 133 119 120 121 118 117 132 114 121 120 123 122 133 119 122 123 120 121 132 114 123 122 125 124 133 119 124 125 122 123 132 114 125 124 127 126 133 119 126 127 124 125 132 114 127 126 129 128 133 119 128 129 126 127 132 114 129 128 131 130 133 119 130 131 128 129 132 114 131 130 116 115 133 119 117 118 130 131 152 164 153 164 154 164 155 165 156 165 157 165 152 166 154 166 158 166 155 167 159 167 156 167 152 168 158 168 160 168 155 169 161 169 159 169 152 170 160 170 162 170 155 171 163 171 161 171 152 172 162 172 164 172 155 173 165 173 163 173 152 174 164 174 166 174 155 175 167 175 165 175 152 176 166 176 168 176 155 177 169 177 167 177 152 178 168 178 170 178 155 179 171 179 169 179 152 180 170 180 172 180 155 181 173 181 171 181 152 182 172 182 174 182 155 183 175 183 173 183 152 184 174 184 176 184 155 185 177 185 175 185 152 186 176 186 153 186 155 187 157 187 177 187 238 252 216 252 217 252 239 253 214 253 215 253 238 254 217 254 219 254 239 255 218 255 214 255 238 256 219 256 221 256 239 257 220 257 218 257 238 258 221 258 223 258 239 259 222 259 220 259 238 260 223 260 225 260 239 261 224 261 222 261 238 262 225 262 227 262 239 263 226 263 224 263 238 264 227 264 229 264 239 265 228 265 226 265 238 266 229 266 231 266 239 267 230 267 228 267 238 268 231 268 233 268 239 269 232 269 230 269 238 270 233 270 235 270 239 271 234 271 232 271 238 272 235 272 237 272 239 273 236 273 234 273 238 274 237 274 216 274 239 275 215 275 236 275 240 276 241 276 242 276 243 277 244 277 245 277 240 278 242 278 246 278 243 279 247 279 244 279 240 280 246 280 248 280 243 281 249 281 247 281 240 282 248 282 250 282 243 283 251 283 249 283 240 284 250 284 252 284 243 285 253 285 251 285 240 286 252 286 254 286 243 287 255 287 253 287 240 288 254 288 256 288 243 289 257 289 255 289 240 290 256 290 258 290 243 291 259 291 257 291 240 292 258 292 260 292 243 293 261 293 259 293 240 294 260 294 262 294 243 295 263 295 261 295 240 296 262 296 264 296 243 297 265 297 263 297 240 298 264 298 241 298 243 299 245 299 265 299 299 332 295 332 297 332 295 333 293 333 297 333 290 334 299 334 297 334 290 335 297 335 286 335 298 336 289 336 285 336 298 337 285 337 296 337 294 338 298 338 296 338 294 339 296 339 292 339 299 340 290 340 298 340 290 341 289 341 298 341 295 342 299 342 298 342 295 343 298 343 294 343 296 344 285 344 286 344 296 345 286 345 297 345 292 346 296 346 297 346 292 347 297 347 293 347 295 348 291 348 293 348 291 349 287 349 293 349 292 350 284 350 288 350 292 351 288 351 294 351 291 352 295 352 288 352 295 353 294 353 288 353 284 354 292 354 293 354 284 355 293 355 287 355 288 356 284 356 291 356 284 357 287 357 291 357 285 358 289 358 290 358 285 359 290 359 286 359 264 360 245 361 241 362 264 360 265 363 245 361 262 364 265 363 264 360 262 364 263 365 265 363 260 366 263 365 262 364 260 366 261 367 263 365 258 368 261 367 260 366 258 368 259 369 261 367 256 370 259 369 258 368 256 370 257 371 259 369 254 372 257 371 256 370 254 372 255 373 257 371 252 374 255 373 254 372 252 374 253 375 255 373 250 376 253 375 252 374 250 376 251 377 253 375 248 378 251 377 250 376 248 378 249 379 251 377 246 380 249 379 248 378 246 380 247 381 249 379 242 382 247 381 246 380 242 382 244 383 247 381 241 362 244 383 242 382 241 362 245 361 244 383 215 384 216 385 237 386 215 384 237 386 236 387 236 387 237 386 235 388 236 387 235 388 234 389 234 389 235 388 233 390 234 389 233 390 232 391 232 391 233 390 231 392 232 391 231 392 230 393 230 393 231 392 229 394 230 393 229 394 228 395 228 395 229 394 227 396 228 395 227 396 226 397 226 397 227 396 225 398 226 397 225 398 224 399 224 399 225 398 223 400 224 399 223 400 222 401 222 401 223 400 221 402 222 401 221 402 220 403 220 403 221 402 219 404 220 403 219 404 218 405 218 405 219 404 217 406 218 405 217 406 214 407 214 407 217 406 216 385 214 407 216 385 215 384 176 408 157 409 153 410 176 408 177 411 157 409 174 412 177 411 176 408 174 412 175 413 177 411 172 414 175 413 174 412 172 414 173 415 175 413 170 416 173 415 172 414 170 416 171 417 173 415 168 418 171 417 170 416 168 418 169 419 171 417 166 420 169 419 168 418 166 420 167 421 169 419 164 422 167 421 166 420 164 422 165 423 167 421 162 424 165 423 164 422 162 424 163 425 165 423 160 426 163 425 162 424 160 426 161 427 163 425 158 428 161 427 160 426 158 428 159 429 161 427 154 430 159 429 158 428 154 430 156 431 159 429 153 410 156 431 154 430 153 410 157 409 156 431 117 118 131 130 130 131 117 118 116 115 131 130 130 131 131 130 128 129 128 129 131 130 129 128 128 129 129 128 126 127 126 127 129 128 127 126 126 127 127 126 124 125 124 125 127 126 125 124 124 125 125 124 122 123 122 123 125 124 123 122 122 123 121 120 120 121 122 123 123 122 121 120 120 121 119 116 118 117 120 121 121 120 119 116 116 115 118 117 119 116 116 115 117 118 118 117 102 101 100 97 114 112 102 101 114 112 115 113 112 110 113 111 115 113 112 110 115 113 114 112 110 108 111 109 113 111 110 108 113 111 112 110 108 106 109 107 110 108 109 107 111 109 110 108 106 104 107 105 108 106 107 105 109 107 108 106 104 102 105 103 106 104 105 103 107 105 106 104 99 98 103 100 104 102 103 100 105 103 104 102 100 97 102 101 103 100 100 97 103 100 99 98 81 82 95 94 94 95 81 82 80 79 95 94 94 95 95 94 92 93 92 93 95 94 93 92 92 93 93 92 90 91 90 91 93 92 91 90 90 91 91 90 88 89 88 89 91 90 89 88 88 89 89 88 86 87 86 87 89 88 87 86 86 87 85 84 84 85 86 87 87 86 85 84 84 85 83 80 82 81 84 85 85 84 83 80 80 79 82 81 83 80 80 79 81 82 82 81 70 65 62 61 69 76 70 65 69 76 77 77 68 74 76 75 77 77 68 74 77 77 69 76 67 72 75 73 76 75 67 72 76 75 68 74 66 70 74 71 67 72 74 71 75 73 67 72 65 68 73 69 66 70 73 69 74 71 66 70 64 66 72 67 65 68 72 67 73 69 65 68 63 62 71 64 64 66 71 64 72 67 64 66 62 61 70 65 71 64 62 61 71 64 63 62 22 23 20 19 34 34 22 23 34 34 35 35 32 32 33 33 35 35 32 32 35 35 34 34 30 30 31 31 33 33 30 30 33 33 32 32 28 28 29 29 31 31 28 28 31 31 30 30 26 26 27 27 29 29 26 26 29 29 28 28 24 24 25 25 27 27 24 24 27 27 26 26 19 20 23 22 25 25 19 20 25 25 24 24 23 22 19 20 20 19 23 22 20 19 22 23 1 4 0 1 15 16 15 16 14 17 1 4 14 17 13 14 12 15 14 17 15 16 13 14 12 15 11 12 10 13 12 15 13 14 11 12 10 13 9 10 8 11 10 13 11 12 9 10 8 11 7 8 6 9 8 11 9 10 7 8 6 9 5 6 4 7 6 9 7 8 5 6 4 7 3 2 2 3 4 7 5 6 3 2 0 1 2 3 3 2 0 1 1 4 2 3

+
+ + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

137 134 136 134 135 134 135 135 136 135 134 135 137 138 139 138 138 138 138 139 139 139 134 139 137 142 141 142 140 142 140 143 141 143 134 143 137 146 143 146 142 146 142 147 143 147 134 147 137 150 145 150 144 150 144 151 145 151 134 151 137 154 147 154 146 154 146 155 147 155 134 155 137 158 149 158 148 158 148 159 149 159 134 159 137 162 151 162 150 162 150 163 151 163 134 163 178 188 180 188 179 188 181 189 180 189 178 189 183 192 182 192 179 192 181 193 182 193 183 193 185 196 184 196 179 196 181 197 184 197 185 197 187 200 186 200 179 200 181 201 186 201 187 201 189 204 188 204 179 204 181 205 188 205 189 205 191 208 190 208 179 208 181 209 190 209 191 209 193 212 192 212 179 212 181 213 192 213 193 213 195 216 194 216 179 216 181 217 194 217 195 217 199 222 200 222 197 222 197 223 200 223 198 223 199 226 202 226 201 226 201 227 202 227 198 227 199 230 204 230 203 230 203 231 204 231 198 231 199 234 206 234 205 234 205 235 206 235 198 235 199 238 208 238 207 238 207 239 208 239 198 239 199 242 210 242 209 242 209 243 210 243 198 243 199 246 212 246 211 246 211 247 212 247 198 247 199 250 196 250 213 250 213 251 196 251 198 251 266 300 268 300 267 300 269 301 268 301 266 301 271 304 270 304 267 304 269 305 270 305 271 305 273 308 272 308 267 308 269 309 272 309 273 309 275 312 274 312 267 312 269 313 274 313 275 313 277 316 276 316 267 316 269 317 276 317 277 317 279 320 278 320 267 320 269 321 278 321 279 321 281 324 280 324 267 324 269 325 280 325 281 325 283 328 282 328 267 328 269 329 282 329 283 329

+
+
+ 1 +
+
+ + + + 0 0 0 + 0 0 1 0 + 0 1 0 0 + 1 0 0 0 + 0.1335572 0.1335572 0.1335572 + + + + + + + + + + + + + + + + +
diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/quadrotor_base.dae b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/quadrotor_base.dae new file mode 100644 index 0000000..0f138bf --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/quadrotor_base.dae @@ -0,0 +1,238 @@ + + + + + Stefan Kohlbrecher + Blender 2.61.4 r43829 + + 2012-02-03T14:20:49 + 2012-02-03T14:20:49 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.1 0.1 0.1 1 + + + 1 0 0.0106101 1 + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 1 1 1 1 + + + + 1 1 1 1 + + + + 1 1 1 1 + + + + 1 1 1 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 0 0 0 1 + + + 0.1 0.1 0.1 1 + + + 0.05496641 0.05496641 0.05496641 1 + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 0.15 0.15 0.15 1 + + + 0.23 0.23 0.23 1 + + + 0.5 0.5 0.5 1 + + + 1 1 1 1 + + + 20 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + + + + + + + + + + + + + + + 0.8236175 0.673869 -1.366201 -0.8236175 0.6738689 -1.366201 -0.8236175 0.6852639 -1.361481 0.8236175 0.6852641 -1.361481 -0.8236175 0.6899839 -1.350086 0.8236175 0.689984 -1.350086 -0.8236175 0.6852639 -1.338691 0.8236175 0.685264 -1.338691 -0.8236175 0.6738689 -1.333971 0.8236175 0.673869 -1.333971 -0.8236175 0.6624739 -1.338691 0.8236175 0.662474 -1.338691 -0.8236175 0.657754 -1.350086 0.8236175 0.6577541 -1.350086 -0.8236175 0.6624739 -1.361481 0.8236175 0.6624741 -1.361481 0.8236175 0.673869 -1.350086 -0.8236175 0.6738689 -1.350086 0.8236174 -0.6738691 -1.350086 0.8236174 -0.662474 -1.361481 0.8236174 -0.6738691 -1.366201 -0.8236175 -0.6738691 -1.350086 -0.8236175 -0.6738691 -1.366201 -0.8236175 -0.6624742 -1.361481 0.8236174 -0.6577541 -1.350086 -0.8236175 -0.6577541 -1.350086 0.8236174 -0.662474 -1.338691 -0.8236175 -0.662474 -1.338691 0.8236174 -0.6738691 -1.333971 -0.8236175 -0.6738691 -1.333971 0.8236174 -0.6852641 -1.338691 -0.8236175 -0.6852641 -1.338691 0.8236174 -0.689984 -1.350086 -0.8236175 -0.689984 -1.350086 0.8236174 -0.6852641 -1.361481 -0.8236175 -0.6852641 -1.361481 0.5614412 0.08138328 0 0.5614412 0.07047998 -0.04069161 0.5614412 0.04069161 -0.07047998 0.5614412 0 -0.08138328 0.5614412 -0.04069161 -0.07047998 0.5614413 -0.07047998 -0.04069161 0.5614413 -0.08138328 0 0.5614413 -0.07047998 0.04069155 0.5614412 -0.04069167 0.07047992 0.5614412 0 0.08138328 0.5614412 0.04069155 0.07047998 0.5614412 0.07047992 0.04069167 2.084521 0.08138328 0 2.084521 0.07048004 -0.04069155 2.084521 0.04069167 -0.07047986 2.084521 0 -0.08138328 2.084521 -0.04069155 -0.07047998 2.084521 -0.07047986 -0.04069167 2.084521 -0.08138328 0 2.084521 -0.07048004 0.04069155 2.084521 -0.04069173 0.07047992 2.084521 0 0.08138328 2.084521 0.04069155 0.07048004 2.084521 0.07047992 0.04069173 0.5614412 0 0 2.084521 0 0 0.6738689 0.6899839 -1.332763 0.6852639 0.6852639 -1.332763 0.6899839 0.6738689 -1.332763 0.6852639 0.6624739 -1.332763 0.6738689 0.657754 -1.332763 0.6624739 0.6624739 -1.332763 0.657754 0.6738689 -1.332763 0.6624739 0.6852639 -1.332763 0.2994973 0.3156122 -0.303241 0.3108922 0.3108922 -0.303241 0.3156122 0.2994973 -0.303241 0.3108922 0.2881023 -0.303241 0.2994973 0.2833823 -0.303241 0.2881022 0.2881023 -0.303241 0.2833823 0.2994973 -0.303241 0.2881023 0.3108922 -0.303241 0.6738689 0.6738689 -1.332763 0.2994973 0.2994973 -0.303241 0.3156121 -0.2994973 -0.303241 0.6899838 -0.673869 -1.332763 0.6852638 -0.6624739 -1.332763 0.3108922 -0.2881023 -0.303241 0.6738688 -0.657754 -1.332763 0.2994972 -0.2833823 -0.303241 0.6624738 -0.6624739 -1.332763 0.2881022 -0.2881023 -0.303241 0.6577539 -0.673869 -1.332763 0.2833822 -0.2994973 -0.303241 0.6624738 -0.6852639 -1.332763 0.2881022 -0.3108923 -0.303241 0.6738688 -0.6899839 -1.332763 0.2994972 -0.3156122 -0.303241 0.6852638 -0.6852639 -1.332763 0.3108922 -0.3108922 -0.303241 0.2994972 -0.2994973 -0.303241 0.6738688 -0.673869 -1.332763 -0.673869 -0.6738688 -1.332763 -0.685264 -0.6852638 -1.332763 -0.6738691 -0.6899837 -1.332763 -0.2994973 -0.2994972 -0.303241 -0.2994973 -0.3156121 -0.303241 -0.3108923 -0.3108922 -0.303241 -0.689984 -0.6738687 -1.332763 -0.3156123 -0.2994972 -0.303241 -0.685264 -0.6624737 -1.332763 -0.3108923 -0.2881022 -0.303241 -0.673869 -0.6577538 -1.332763 -0.2994973 -0.2833822 -0.303241 -0.662474 -0.6624737 -1.332763 -0.2881023 -0.2881022 -0.303241 -0.6577541 -0.6738688 -1.332763 -0.2833824 -0.2994972 -0.303241 -0.662474 -0.6852638 -1.332763 -0.2881023 -0.3108922 -0.303241 -0.3156121 0.2994973 -0.303241 -0.6899837 0.6738693 -1.332763 -0.6852637 0.662474 -1.332763 -0.3108922 0.2881023 -0.303241 -0.6738687 0.6577541 -1.332763 -0.2994971 0.2833824 -0.303241 -0.6624737 0.662474 -1.332763 -0.2881022 0.2881023 -0.303241 -0.6577537 0.6738691 -1.332763 -0.2833822 0.2994973 -0.303241 -0.6624737 0.6852641 -1.332763 -0.2881022 0.3108924 -0.303241 -0.6738685 0.689984 -1.332763 -0.2994971 0.3156123 -0.303241 -0.6852637 0.6852641 -1.332763 -0.3108922 0.3108923 -0.303241 -0.2994971 0.2994973 -0.303241 -0.6738687 0.6738691 -1.332763 1.969194 0 0.1871857 2.886225 -0.3798463 0.2218515 2.671059 -0.7018645 0.2218514 1.969194 0 0.2620601 2.349041 -0.9170302 0.2218514 1.969195 -0.9925863 0.2218514 1.589348 -0.9170302 0.2218514 1.26733 -0.7018646 0.2218514 1.052164 -0.3798465 0.2218515 0.9766083 -2.36674e-7 0.2218515 1.052164 0.379846 0.2218516 1.26733 0.7018642 0.2218517 1.589348 0.9170299 0.2218517 1.969194 0.992586 0.2218518 2.34904 0.91703 0.2218517 2.671058 0.7018645 0.2218517 2.886224 0.3798464 0.2218516 2.96178 3.25924e-7 0.2218515 0 -0.5614412 0 0.08138316 -0.5614412 0 0.07047986 -0.5614412 -0.04069161 -2.69139e-7 -2.084521 0 0.07047975 -2.084521 -0.04069155 0.08138298 -2.084521 0 0.04069155 -0.5614412 -0.07047998 0.04069143 -2.084521 -0.07047992 0 -0.5614412 -0.08138328 -1.69274e-7 -2.084521 -0.08138328 -0.04069167 -0.5614412 -0.07047998 -0.04069179 -2.084521 -0.07047998 -0.07048004 -0.5614413 -0.04069167 -0.07048016 -2.084521 -0.04069167 -0.08138334 -0.5614413 0 -0.08138352 -2.084521 0 -0.07048004 -0.5614413 0.04069161 -0.07048028 -2.084521 0.04069155 -0.04069173 -0.5614412 0.07047998 -0.04069197 -2.084521 0.07047992 -1.3514e-7 -0.5614412 0.08138328 -3.81294e-7 -2.084521 0.08138328 0.04069143 -0.5614412 0.07047998 0.04069125 -2.084521 0.07048004 0.07047986 -0.5614412 0.04069167 0.07047963 -2.084521 0.04069173 0.379846 -2.886224 0.2218516 -2.61752e-7 -1.969194 0.1871857 0 -2.96178 0.2218515 -3.25223e-7 -1.969194 0.2620601 0.7018641 -2.671058 0.2218517 0.9170297 -2.34904 0.2218517 0.9925858 -1.969194 0.2218517 0.9170296 -1.589348 0.2218517 0.701864 -1.26733 0.2218517 0.3798459 -1.052164 0.2218516 -3.6789e-7 -0.9766083 0.2218515 -0.3798466 -1.052164 0.2218514 -0.7018647 -1.26733 0.2218514 -0.9170304 -1.589348 0.2218513 -0.9925865 -1.969194 0.2218513 -0.9170305 -2.34904 0.2218513 -0.7018648 -2.671059 0.2218514 -0.3798467 -2.886225 0.2218514 -2.96178 4.69959e-7 0.2218515 -2.886225 0.3798471 0.2218514 -1.969194 5.26331e-7 0.1871857 -1.969194 5.89802e-7 0.2620601 -2.671059 0.7018652 0.2218514 -2.34904 0.9170308 0.2218513 -1.969194 0.9925867 0.2218513 -1.589348 0.9170306 0.2218513 -1.26733 0.7018649 0.2218514 -1.052164 0.3798468 0.2218514 -0.9766083 4.99106e-7 0.2218515 -1.052164 -0.3798457 0.2218516 -1.26733 -0.7018638 0.2218517 -1.589348 -0.9170294 0.2218517 -1.969194 -0.9925855 0.2218517 -2.349041 -0.9170294 0.2218517 -2.671058 -0.7018638 0.2218517 -2.886224 -0.3798456 0.2218516 -0.5614412 -0.07047981 0.04069167 -0.5614412 -0.0813831 0 -2.084521 -0.08138269 0 -2.084521 -0.07047933 0.04069173 -0.5614412 -0.04069137 0.07047998 -2.084521 -0.04069095 0.07048004 -0.5614412 2.10574e-7 0.08138328 -2.084521 6.61367e-7 0.08138328 -0.5614412 0.04069179 0.07047998 -2.084521 0.04069226 0.07047992 -0.5614413 0.0704801 0.04069161 -2.084521 0.07048058 0.04069155 -0.5614413 0.0813834 0 -2.084521 0.08138382 0 -0.5614413 0.0704801 -0.04069167 -2.084521 0.07048046 -0.04069167 -0.5614412 0.04069179 -0.07047998 -2.084521 0.04069209 -0.07047998 -0.5614412 1.54427e-7 -0.08138328 -2.084521 4.49347e-7 -0.08138328 -0.5614412 -0.04069149 -0.07047998 -2.084521 -0.04069113 -0.07047992 -0.5614412 -0.07047981 -0.04069161 -2.084521 -0.07047945 -0.04069155 -2.084521 5.49213e-7 0 -0.5614412 1.61804e-7 0 2.37238e-7 0.5614412 0 -0.08138304 0.5614412 0 -0.07047975 0.5614412 -0.04069161 8.29287e-7 2.084521 0 -0.07047921 2.084521 -0.04069155 -0.08138245 2.084521 0 -0.04069137 0.5614412 -0.07047998 -0.04069083 2.084521 -0.07047992 2.29861e-7 0.5614412 -0.08138328 7.29421e-7 2.084521 -0.08138328 0.04069185 0.5614412 -0.07047998 0.04069238 2.084521 -0.07047998 0.07048016 0.5614413 -0.04069167 0.07048076 2.084521 -0.04069167 0.08138352 0.5614413 0 0.08138412 2.084521 0 0.07048022 0.5614413 0.04069161 0.07048088 2.084521 0.04069155 0.04069191 0.5614412 0.07047998 0.04069256 2.084521 0.07047992 2.86009e-7 0.5614412 0.08138328 9.41441e-7 2.084521 0.08138328 -0.04069131 0.5614412 0.07047998 -0.04069072 2.084521 0.07048004 -0.07047975 0.5614412 0.04069167 -0.07047903 2.084521 0.04069173 -0.3798453 2.886224 0.2218516 7.9091e-7 1.969194 0.1871857 8.67901e-7 2.96178 0.2218515 8.54381e-7 1.969194 0.2620601 -0.7018634 2.671058 0.2218517 -0.9170291 2.349041 0.2218517 -0.9925853 1.969195 0.2218517 -0.9170292 1.589348 0.2218517 -0.7018637 1.26733 0.2218517 -0.3798456 1.052164 0.2218516 6.30322e-7 0.9766083 0.2218515 0.3798469 1.052164 0.2218514 0.7018651 1.26733 0.2218514 0.9170309 1.589348 0.2218513 0.992587 1.969194 0.2218513 0.9170311 2.34904 0.2218513 0.7018656 2.671059 0.2218514 0.3798475 2.886225 0.2218514 0.3369342 0.5615574 -0.2994973 0.3369344 -0.5615572 -0.2994973 -0.3369344 -0.5615574 -0.2994973 -0.3369344 0.5615576 -0.2994973 0.3369346 0.5615574 0.2994973 0.3369344 -0.5615576 0.2994973 -0.3369344 -0.5615574 0.2994973 -0.3369344 0.5615572 0.2994973 0.5615572 0.3369344 -0.2994973 -0.5615572 0.3369347 -0.2994973 0.5615576 0.3369343 0.2994973 -0.5615572 0.3369344 0.2994973 0.5615572 -0.3369344 -0.2994973 -0.5615575 -0.3369343 -0.2994973 0.5615574 -0.3369347 0.2994973 -0.5615575 -0.3369344 0.2994973 + + + + + + + + + + 1 0 0 0.6302378 0 -0.7763603 0.6302378 0.548967 -0.548967 -0.6302378 0.548967 -0.548967 -0.6302378 0 -0.7763603 -1 0 0 0.6302378 0.7763603 0 -0.6302378 0.7763603 0 0.6302378 0.548967 0.548967 -0.6302378 0.548967 0.548967 0.6302378 0 0.7763603 -0.6302378 0 0.7763603 0.6302378 -0.548967 0.548967 -0.6302378 -0.548967 0.548967 0.6302378 -0.7763603 0 -0.6302378 -0.7763603 0 0.6302378 -0.548967 -0.548967 -0.6302378 -0.548967 -0.548967 1 0 0 0.6302378 0 -0.7763603 0.6302378 0.548967 -0.548967 -1 0 0 -0.6302378 0.548967 -0.548967 -0.6302378 0 -0.7763603 0.6302378 0.7763603 0 -0.6302378 0.7763603 0 0.6302378 0.548967 0.548967 -0.6302378 0.548967 0.548967 0.6302378 0 0.7763603 -0.6302378 0 0.7763603 0.6302378 -0.548967 0.548967 -0.6302378 -0.548967 0.548967 0.6302378 -0.7763603 0 -0.6302378 -0.7763603 0 0.6302378 -0.548967 -0.548967 -0.6302378 -0.548967 -0.548967 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 -2.53709e-6 1.46479e-6 1 0 0 -1 -1.46479e-6 -3.92489e-7 1 0 0 -1 -1.46479e-6 3.92489e-7 1 0 0 -1 -2.53709e-6 -1.46479e-6 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 0 0 -1 0.06228822 0.8714866 -0.486404 0.6329844 0.6329844 -0.4456618 0 0 1 0.4264656 0.4264656 0.7976318 -0.06045717 0.6646626 0.7446516 0.8714866 0.06228822 -0.486404 0.6646626 -0.06045717 0.7446516 0.6226387 -0.4941862 -0.6066775 0.4941862 -0.6226387 0.6066775 0.06045717 -0.6646626 -0.7446516 -0.06228822 -0.8714866 0.486404 -0.4264656 -0.4264656 -0.7976318 -0.6329844 -0.6329844 0.4456618 -0.6646626 0.06045717 -0.7446516 -0.8714866 -0.06228822 0.486404 -0.4941862 0.6226387 -0.6066775 -0.6226387 0.4941862 0.6066775 0 0 1 0.6646626 0.06045717 0.7446516 0.4941862 0.6226387 0.6066775 0.6226387 0.4941862 -0.6066775 0.8714866 -0.06228822 -0.486404 0 0 -1 -0.06228822 0.8714866 0.486404 0.06045717 0.6646626 -0.7446516 -0.6329844 0.6329844 0.4456618 -0.4264656 0.4264656 -0.7976318 -0.8714866 0.06228822 0.486404 -0.6646626 -0.06045717 -0.7446516 -0.6226387 -0.4941862 0.6066775 -0.4941862 -0.6226387 -0.6066775 -0.06045717 -0.6646626 0.7446516 0.06228822 -0.8714866 -0.486404 0.4264656 -0.4264656 0.7976318 0.6329844 -0.6329844 -0.4456618 0 0 -1 -0.06228822 -0.8714866 -0.486404 -0.6329844 -0.6329844 -0.4456618 0 0 1 -0.4264656 -0.4264656 0.7976318 0.06045717 -0.6646626 0.7446516 -0.8714866 -0.06228822 -0.486404 -0.6646626 0.06045717 0.7446516 -0.6226387 0.4941862 -0.6066775 -0.4941862 0.6226387 0.6066775 -0.06045717 0.6646626 -0.7446516 0.06228822 0.8714866 0.486404 0.4264656 0.4264656 -0.7976318 0.6329844 0.6329844 0.4456618 0.6646626 -0.06045717 -0.7446516 0.8714866 0.06228822 0.486404 0.4941862 -0.6226387 -0.6066775 0.6226387 -0.4941862 0.6066775 0 0 1 -0.6646626 -0.06045717 0.7446516 -0.4941862 -0.6226387 0.6066775 -0.6226387 -0.4941862 -0.6066775 -0.8714866 0.06228822 -0.486404 0 0 -1 0.06228822 -0.8714866 0.486404 -0.06045717 -0.6646626 -0.7446516 0.6329844 -0.6329844 0.4456618 0.4264656 -0.4264656 -0.7976318 0.8714866 -0.06228822 0.486404 0.6646626 0.06045717 -0.7446516 0.6226387 0.4941862 0.6066775 0.4941862 0.6226387 -0.6066775 0.06045717 0.6646626 0.7446516 -0.06228822 0.8714866 -0.486404 -0.4264656 0.4264656 0.7976318 -0.6329844 0.6329844 -0.4456618 0.03490257 -0.006942212 -0.9993667 0.04047429 -0.008050978 0.9991481 0.03431242 -0.02292704 0.9991481 0.02958893 -0.0197705 -0.9993667 0.01977074 -0.02958875 -0.9993666 0.02292686 -0.03431266 0.9991481 0.008050799 -0.04047453 0.9991481 0.00694251 -0.03490239 -0.9993667 -0.00694251 -0.03490239 -0.9993667 -0.008050799 -0.04047447 0.9991481 -0.02292686 -0.03431266 0.9991481 -0.01977074 -0.02958875 -0.9993666 -0.02958893 -0.01977056 -0.9993666 -0.03431248 -0.02292704 0.9991481 -0.04047429 -0.008051037 0.9991481 -0.03490257 -0.006942331 -0.9993666 -0.03490257 0.006942749 -0.9993666 -0.04047429 0.00805062 0.9991481 -0.03431248 0.02292662 0.999148 -0.02958899 0.01977092 -0.9993666 -0.01977074 0.02958917 -0.9993667 -0.02292686 0.03431224 0.9991482 -0.008050799 0.04047405 0.9991481 -0.00694251 0.03490281 -0.9993667 0.00694251 0.03490281 -0.9993667 0.008050799 0.04047411 0.9991481 0.0229268 0.03431224 0.9991482 0.01977074 0.02958923 -0.9993667 0.02958899 0.01977092 -0.9993667 0.03431248 0.02292662 0.9991481 0.04047429 0.00805062 0.9991481 0.03490257 0.006942749 -0.9993667 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 -2.53709e-6 1 1.46479e-6 0 -1 0 -1.46479e-6 1 -3.92489e-7 0 -1 0 -1.46479e-6 1 3.92489e-7 0 -1 0 -2.53709e-6 1 -1.46479e-6 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0.006942689 -0.03490263 -0.9993667 0.00805068 -0.04047423 0.9991481 0.02292662 -0.03431242 0.9991482 0.01977092 -0.02958899 -0.9993667 0.02958923 -0.01977068 -0.9993667 0.03431218 -0.02292686 0.9991481 0.04047405 -0.008050739 0.9991482 0.03490281 -0.00694257 -0.9993666 0.03490281 0.00694257 -0.9993667 0.04047405 0.008050799 0.9991481 0.03431218 0.02292686 0.9991481 0.02958923 0.01977068 -0.9993667 0.01977092 0.02958899 -0.9993666 0.02292662 0.03431242 0.9991481 0.00805062 0.04047423 0.9991481 0.006942689 0.03490263 -0.9993666 -0.006942212 0.03490263 -0.9993666 -0.008051097 0.04047423 0.9991481 -0.02292704 0.03431242 0.9991481 -0.0197705 0.02958893 -0.9993666 -0.02958869 0.01977074 -0.9993666 -0.03431266 0.0229268 0.9991481 -0.04047447 0.008050858 0.9991481 -0.03490233 0.00694251 -0.9993667 -0.03490233 -0.00694251 -0.9993667 -0.04047447 -0.008050858 0.9991481 -0.03431266 -0.0229268 0.9991481 -0.02958875 -0.01977074 -0.9993667 -0.0197705 -0.02958893 -0.9993667 -0.02292704 -0.03431242 0.9991481 -0.008051037 -0.04047423 0.999148 -0.006942152 -0.03490263 -0.9993667 -0.03490263 0.006942152 -0.9993667 -0.04047423 0.008051037 0.9991481 -0.03431242 0.02292704 0.9991481 -0.02958893 0.0197705 -0.9993667 -0.01977068 0.02958875 -0.9993666 -0.02292674 0.03431272 0.9991482 -0.008050858 0.04047447 0.9991481 -0.006942451 0.03490233 -0.9993666 0.00694251 0.03490239 -0.9993667 0.008050858 0.04047447 0.9991481 0.0229268 0.03431266 0.9991481 0.01977074 0.02958869 -0.9993666 0.02958893 0.0197705 -0.9993666 0.03431248 0.02292698 0.9991481 0.04047423 0.008051097 0.9991481 0.03490263 0.006942212 -0.9993666 0.03490263 -0.006942689 -0.9993666 0.04047423 -0.00805062 0.9991481 0.03431242 -0.02292662 0.9991482 0.02958899 -0.01977092 -0.9993667 0.01977068 -0.02958923 -0.9993667 0.02292686 -0.03431218 0.9991481 0.008050799 -0.04047405 0.9991481 0.00694257 -0.03490281 -0.9993667 -0.00694257 -0.03490281 -0.9993667 -0.008050799 -0.04047405 0.9991481 -0.02292686 -0.03431218 0.9991482 -0.01977068 -0.02958917 -0.9993667 -0.02958899 -0.01977092 -0.9993667 -0.03431242 -0.02292662 0.9991482 -0.04047423 -0.00805068 0.9991481 -0.03490263 -0.006942689 -0.9993667 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 2.53709e-6 -1.46479e-6 -1 0 0 1 1.46479e-6 3.92489e-7 -1 0 0 1 1.46479e-6 -3.92489e-7 -1 0 0 1 2.53709e-6 1.46479e-6 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 2.53709e-6 -1 1.46479e-6 0 1 0 1.46479e-6 -1 -3.92489e-7 0 1 0 1.46479e-6 -1 3.92489e-7 0 1 0 2.53709e-6 -1 -1.46479e-6 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 -0.006942689 0.03490263 -0.9993667 -0.00805068 0.04047423 0.9991481 -0.02292662 0.03431242 0.9991482 -0.01977092 0.02958899 -0.9993667 -0.02958917 0.01977074 -0.9993666 -0.03431218 0.02292692 0.9991483 -0.04047405 0.008050799 0.9991482 -0.03490281 0.00694257 -0.9993666 -0.03490281 -0.00694257 -0.9993667 -0.04047405 -0.008050799 0.9991481 -0.03431218 -0.02292686 0.9991481 -0.02958923 -0.01977068 -0.9993666 -0.01977092 -0.02958899 -0.9993667 -0.02292662 -0.03431242 0.9991481 -0.00805062 -0.04047423 0.9991481 -0.006942689 -0.03490263 -0.9993666 0.006942212 -0.03490263 -0.9993666 0.008051097 -0.04047423 0.9991481 0.02292698 -0.03431248 0.9991482 0.0197705 -0.02958899 -0.9993667 0.02958869 -0.01977074 -0.9993667 0.03431266 -0.0229268 0.999148 0.04047447 -0.008050858 0.9991481 0.03490233 -0.00694251 -0.9993667 0.03490239 0.006942451 -0.9993667 0.04047447 0.008050858 0.9991481 0.03431272 0.02292674 0.9991481 0.02958875 0.01977068 -0.9993667 0.0197705 0.02958893 -0.9993667 0.02292704 0.03431242 0.9991481 0.008051037 0.04047423 0.9991481 0.006942152 0.03490263 -0.9993667 -1 3.53806e-7 0 -1 3.53806e-7 0 -0.7071067 -0.707107 -1.40725e-7 -0.7071068 -0.7071068 0 0.7071068 -0.7071069 -4.92539e-7 0.7071067 -0.7071068 -4.8945e-7 1 -3.53806e-7 -1.99016e-7 1 0 -5.97047e-7 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.7071067 0.7071068 3.9156e-7 -0.7071068 0.7071067 4.92539e-7 0.7071067 0.7071068 -5.2772e-7 0.707107 0.7071065 -3.13248e-7 0 0 1 0 0 1 0 0 -1 0 0 -1 -2.65354e-7 1 0 3.53806e-7 1 6.96555e-7 -3.53806e-7 -1 -6.96555e-7 2.65354e-7 -1 0 -0.6557207 -0.6532182 0.3785516 -0.7571337 0.6532182 0 -0.7571337 -0.6532182 0 -0.6557207 0.6532182 0.3785516 -0.3785516 -0.6532182 0.6557207 -0.3785516 0.6532182 0.6557207 0 -0.6532182 0.7571337 0 0.6532182 0.7571337 0.3785516 -0.6532182 0.6557207 0.3785821 0.6532182 0.6557207 0.6557207 -0.6532182 0.3785516 0.6557207 0.6532182 0.3785516 0.7571337 -0.6532182 0 0.7571337 0.6532182 0 0.6557207 -0.6532182 -0.3785516 0.6557207 0.6532182 -0.3785516 0.3785516 -0.6532182 -0.6557207 0.3785516 0.6532182 -0.6557207 0 -0.6532182 -0.7571337 0 0.6532182 -0.7571337 -0.3785516 -0.6532182 -0.6557207 -0.3785516 0.6532182 -0.6557207 -0.6557207 -0.6532182 -0.3785516 -0.6557207 0.6532182 -0.3785516 0.6532182 -0.7571337 0 -0.6532182 -0.7571337 0 -0.6532182 -0.6557207 -0.3785516 0.6532182 -0.6557207 -0.3785516 -0.6532182 -0.3785516 -0.6557207 0.6532182 -0.3785516 -0.6557207 -0.6532182 0 -0.7571337 0.6532182 0 -0.7571337 -0.6532182 0.3785516 -0.6557207 0.6532182 0.3785516 -0.6557207 -0.6532182 0.6557207 -0.3785516 0.6532182 0.6557207 -0.3785516 -0.6532182 0.7571337 0 0.6532182 0.7571337 0 -0.6532182 0.6557207 0.3785516 0.6532182 0.6557207 0.3785516 -0.6532182 0.3785821 0.6557207 0.6532182 0.3785821 0.6557207 -0.6532182 0 0.7571337 0.6532182 0 0.7571337 -0.6532182 -0.3785516 0.6557207 0.6532182 -0.3785516 0.6557207 -0.6532182 -0.6557207 0.3785516 0.6532182 -0.6557207 0.3785516 0.6557207 0.6532182 0.3785516 0.7571337 -0.6532182 0 0.7571337 0.6532182 0 0.6557207 -0.6532182 0.3785516 0.3785516 0.6532182 0.6557207 0.3785516 -0.6532182 0.6557207 0 0.6532182 0.7571337 0 -0.6532182 0.7571337 -0.3785821 0.6532182 0.6557207 -0.3785821 -0.6532182 0.6557207 -0.6557207 0.6532182 0.3785516 -0.6557207 -0.6532182 0.3785516 -0.7571337 0.6532182 0 -0.7571337 -0.6532182 0 -0.6557207 0.6532182 -0.3785516 -0.6557207 -0.6532182 -0.3785516 -0.3785516 0.6532182 -0.6557207 -0.3785516 -0.6532182 -0.6557207 0 0.6532182 -0.7571337 0 -0.6532182 -0.7571337 0.3785516 0.6532182 -0.6557207 0.3785516 -0.6532182 -0.6557207 0.6557207 0.6532182 -0.3785516 0.6557207 -0.6532182 -0.3785516 0.6532182 0.7571337 0 -0.6532182 0.7571337 0 -0.6532182 0.6557207 0.3785516 0.6532182 0.6557207 0.3785516 -0.6532182 0.3785516 0.6557207 0.6532182 0.3785516 0.6557207 -0.6532182 0 0.7571337 0.6532182 0 0.7571337 -0.6532182 -0.3785821 0.6556902 0.6532182 -0.3785821 0.6557207 -0.6532182 -0.6557207 0.3785516 0.6532182 -0.6557207 0.3785516 -0.6532182 -0.7571337 0 0.6532182 -0.7571337 0 -0.6532182 -0.6557207 -0.3785516 0.6532182 -0.6557207 -0.3785516 -0.6532182 -0.3785516 -0.6557207 0.6532182 -0.3785516 -0.6557207 -0.6532182 0 -0.7571337 0.6532182 0 -0.7571337 -0.6532182 0.3785516 -0.6557207 0.6532182 0.3785516 -0.6557207 -0.6532182 0.6557207 -0.3785516 0.6532182 0.6557207 -0.3785516 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

60 36 36 36 37 36 61 37 49 37 48 37 60 38 37 38 38 38 61 39 50 39 49 39 60 40 38 40 39 40 61 41 51 41 50 41 60 42 39 42 40 42 61 43 52 43 51 43 60 44 40 44 41 44 61 45 53 45 52 45 60 46 41 46 42 46 61 47 54 47 53 47 60 48 42 48 43 48 61 49 55 49 54 49 60 50 43 50 44 50 61 51 56 51 55 51 60 52 44 52 45 52 61 53 57 53 56 53 60 54 45 54 46 54 61 55 58 55 57 55 60 56 46 56 47 56 61 57 59 57 58 57 47 58 36 58 60 58 61 59 48 59 59 59 48 432 36 433 47 434 48 432 47 434 59 435 46 436 58 437 59 435 46 436 59 435 47 434 45 438 57 439 58 437 45 438 58 437 46 436 44 440 56 441 57 439 44 440 57 439 45 438 43 442 55 443 56 441 43 442 56 441 44 440 42 444 54 445 55 443 42 444 55 443 43 442 41 446 53 447 54 445 41 446 54 445 42 444 40 448 52 449 53 447 40 448 53 447 41 446 39 450 51 451 52 449 39 450 52 449 40 448 38 452 50 453 51 451 38 452 51 451 39 450 37 454 49 455 50 453 37 454 50 453 38 452 36 433 48 432 49 455 36 433 49 455 37 454

+
+ + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

151 132 135 132 134 132 137 133 135 133 151 133 136 136 138 136 134 136 137 137 138 137 136 137 139 140 140 140 134 140 137 141 140 141 139 141 141 144 142 144 134 144 137 145 142 145 141 145 143 148 144 148 134 148 137 149 144 149 143 149 145 152 146 152 134 152 137 153 146 153 145 153 147 156 148 156 134 156 137 157 148 157 147 157 149 160 150 160 134 160 137 161 150 161 149 161 181 190 178 190 182 190 182 191 178 191 179 191 181 194 183 194 184 194 184 195 183 195 179 195 181 198 185 198 186 198 186 199 185 199 179 199 181 202 187 202 188 202 188 203 187 203 179 203 181 206 189 206 190 206 190 207 189 207 179 207 181 210 191 210 192 210 192 211 191 211 179 211 181 214 193 214 194 214 194 215 193 215 179 215 181 218 195 218 180 218 180 219 195 219 179 219 196 220 197 220 198 220 199 221 197 221 196 221 200 224 201 224 198 224 199 225 201 225 200 225 202 228 203 228 198 228 199 229 203 229 202 229 204 232 205 232 198 232 199 233 205 233 204 233 206 236 207 236 198 236 199 237 207 237 206 237 208 240 209 240 198 240 199 241 209 241 208 241 210 244 211 244 198 244 199 245 211 245 210 245 212 248 213 248 198 248 199 249 213 249 212 249 269 302 266 302 270 302 270 303 266 303 267 303 269 306 271 306 272 306 272 307 271 307 267 307 269 310 273 310 274 310 274 311 273 311 267 311 269 314 275 314 276 314 276 315 275 315 267 315 269 318 277 318 278 318 278 319 277 319 267 319 269 322 279 322 280 322 280 323 279 323 267 323 269 326 281 326 282 326 282 327 281 327 267 327 269 330 283 330 268 330 268 331 283 331 267 331

+
+ + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

16 0 0 1 3 2 2 3 1 4 17 5 16 0 3 2 5 6 17 5 4 7 2 3 16 0 5 6 7 8 17 5 6 9 4 7 16 0 7 8 9 10 17 5 8 11 6 9 16 0 9 10 11 12 17 5 10 13 8 11 16 0 11 12 13 14 17 5 12 15 10 13 16 0 13 14 15 16 17 5 14 17 12 15 15 16 0 1 16 0 17 5 1 4 14 17 18 18 20 19 19 20 21 21 23 22 22 23 18 18 19 20 24 24 21 21 25 25 23 22 18 18 24 24 26 26 21 21 27 27 25 25 18 18 26 26 28 28 21 21 29 29 27 27 18 18 28 28 30 30 21 21 31 31 29 29 18 18 30 30 32 32 21 21 33 33 31 31 18 18 32 32 34 34 21 21 35 35 33 33 34 34 20 19 18 18 35 35 21 21 22 23 78 60 62 61 63 62 79 63 71 64 70 65 78 60 63 62 64 66 79 63 72 67 71 64 78 60 64 66 65 68 79 63 73 69 72 67 78 60 65 68 66 70 79 63 74 71 73 69 78 60 66 70 67 72 79 63 75 73 74 71 78 60 67 72 68 74 79 63 76 75 75 73 78 60 68 74 69 76 79 63 77 77 76 75 69 76 62 61 78 60 79 63 70 65 77 77 96 78 80 79 83 80 82 81 81 82 97 83 96 78 83 80 85 84 97 83 84 85 82 81 96 78 85 84 87 86 97 83 86 87 84 85 96 78 87 86 89 88 97 83 88 89 86 87 96 78 89 88 91 90 97 83 90 91 88 89 96 78 91 90 93 92 97 83 92 93 90 91 96 78 93 92 95 94 97 83 94 95 92 93 96 78 95 94 80 79 97 83 81 82 94 95 98 96 100 97 99 98 101 99 103 100 102 101 98 96 99 98 104 102 101 99 105 103 103 100 98 96 104 102 106 104 101 99 107 105 105 103 98 96 106 104 108 106 101 99 109 107 107 105 98 96 108 106 110 108 101 99 111 109 109 107 98 96 110 108 112 110 101 99 113 111 111 109 98 96 112 110 114 112 101 99 115 113 113 111 114 112 100 97 98 96 101 99 102 101 115 113 132 114 116 115 119 116 118 117 117 118 133 119 132 114 119 116 121 120 133 119 120 121 118 117 132 114 121 120 123 122 133 119 122 123 120 121 132 114 123 122 125 124 133 119 124 125 122 123 132 114 125 124 127 126 133 119 126 127 124 125 132 114 127 126 129 128 133 119 128 129 126 127 132 114 129 128 131 130 133 119 130 131 128 129 132 114 131 130 116 115 133 119 117 118 130 131 152 164 153 164 154 164 155 165 156 165 157 165 152 166 154 166 158 166 155 167 159 167 156 167 152 168 158 168 160 168 155 169 161 169 159 169 152 170 160 170 162 170 155 171 163 171 161 171 152 172 162 172 164 172 155 173 165 173 163 173 152 174 164 174 166 174 155 175 167 175 165 175 152 176 166 176 168 176 155 177 169 177 167 177 152 178 168 178 170 178 155 179 171 179 169 179 152 180 170 180 172 180 155 181 173 181 171 181 152 182 172 182 174 182 155 183 175 183 173 183 152 184 174 184 176 184 155 185 177 185 175 185 152 186 176 186 153 186 155 187 157 187 177 187 238 252 216 252 217 252 239 253 214 253 215 253 238 254 217 254 219 254 239 255 218 255 214 255 238 256 219 256 221 256 239 257 220 257 218 257 238 258 221 258 223 258 239 259 222 259 220 259 238 260 223 260 225 260 239 261 224 261 222 261 238 262 225 262 227 262 239 263 226 263 224 263 238 264 227 264 229 264 239 265 228 265 226 265 238 266 229 266 231 266 239 267 230 267 228 267 238 268 231 268 233 268 239 269 232 269 230 269 238 270 233 270 235 270 239 271 234 271 232 271 238 272 235 272 237 272 239 273 236 273 234 273 238 274 237 274 216 274 239 275 215 275 236 275 240 276 241 276 242 276 243 277 244 277 245 277 240 278 242 278 246 278 243 279 247 279 244 279 240 280 246 280 248 280 243 281 249 281 247 281 240 282 248 282 250 282 243 283 251 283 249 283 240 284 250 284 252 284 243 285 253 285 251 285 240 286 252 286 254 286 243 287 255 287 253 287 240 288 254 288 256 288 243 289 257 289 255 289 240 290 256 290 258 290 243 291 259 291 257 291 240 292 258 292 260 292 243 293 261 293 259 293 240 294 260 294 262 294 243 295 263 295 261 295 240 296 262 296 264 296 243 297 265 297 263 297 240 298 264 298 241 298 243 299 245 299 265 299 299 332 295 332 297 332 295 333 293 333 297 333 290 334 299 334 297 334 290 335 297 335 286 335 298 336 289 336 285 336 298 337 285 337 296 337 294 338 298 338 296 338 294 339 296 339 292 339 299 340 290 340 298 340 290 341 289 341 298 341 295 342 299 342 298 342 295 343 298 343 294 343 296 344 285 344 286 344 296 345 286 345 297 345 292 346 296 346 297 346 292 347 297 347 293 347 295 348 291 348 293 348 291 349 287 349 293 349 292 350 284 350 288 350 292 351 288 351 294 351 291 352 295 352 288 352 295 353 294 353 288 353 284 354 292 354 293 354 284 355 293 355 287 355 288 356 284 356 291 356 284 357 287 357 291 357 285 358 289 358 290 358 285 359 290 359 286 359 264 360 245 361 241 362 264 360 265 363 245 361 262 364 265 363 264 360 262 364 263 365 265 363 260 366 263 365 262 364 260 366 261 367 263 365 258 368 261 367 260 366 258 368 259 369 261 367 256 370 259 369 258 368 256 370 257 371 259 369 254 372 257 371 256 370 254 372 255 373 257 371 252 374 255 373 254 372 252 374 253 375 255 373 250 376 253 375 252 374 250 376 251 377 253 375 248 378 251 377 250 376 248 378 249 379 251 377 246 380 249 379 248 378 246 380 247 381 249 379 242 382 247 381 246 380 242 382 244 383 247 381 241 362 244 383 242 382 241 362 245 361 244 383 215 384 216 385 237 386 215 384 237 386 236 387 236 387 237 386 235 388 236 387 235 388 234 389 234 389 235 388 233 390 234 389 233 390 232 391 232 391 233 390 231 392 232 391 231 392 230 393 230 393 231 392 229 394 230 393 229 394 228 395 228 395 229 394 227 396 228 395 227 396 226 397 226 397 227 396 225 398 226 397 225 398 224 399 224 399 225 398 223 400 224 399 223 400 222 401 222 401 223 400 221 402 222 401 221 402 220 403 220 403 221 402 219 404 220 403 219 404 218 405 218 405 219 404 217 406 218 405 217 406 214 407 214 407 217 406 216 385 214 407 216 385 215 384 176 408 157 409 153 410 176 408 177 411 157 409 174 412 177 411 176 408 174 412 175 413 177 411 172 414 175 413 174 412 172 414 173 415 175 413 170 416 173 415 172 414 170 416 171 417 173 415 168 418 171 417 170 416 168 418 169 419 171 417 166 420 169 419 168 418 166 420 167 421 169 419 164 422 167 421 166 420 164 422 165 423 167 421 162 424 165 423 164 422 162 424 163 425 165 423 160 426 163 425 162 424 160 426 161 427 163 425 158 428 161 427 160 426 158 428 159 429 161 427 154 430 159 429 158 428 154 430 156 431 159 429 153 410 156 431 154 430 153 410 157 409 156 431 117 118 131 130 130 131 117 118 116 115 131 130 130 131 131 130 128 129 128 129 131 130 129 128 128 129 129 128 126 127 126 127 129 128 127 126 126 127 127 126 124 125 124 125 127 126 125 124 124 125 125 124 122 123 122 123 125 124 123 122 122 123 121 120 120 121 122 123 123 122 121 120 120 121 119 116 118 117 120 121 121 120 119 116 116 115 118 117 119 116 116 115 117 118 118 117 102 101 100 97 114 112 102 101 114 112 115 113 112 110 113 111 115 113 112 110 115 113 114 112 110 108 111 109 113 111 110 108 113 111 112 110 108 106 109 107 110 108 109 107 111 109 110 108 106 104 107 105 108 106 107 105 109 107 108 106 104 102 105 103 106 104 105 103 107 105 106 104 99 98 103 100 104 102 103 100 105 103 104 102 100 97 102 101 103 100 100 97 103 100 99 98 81 82 95 94 94 95 81 82 80 79 95 94 94 95 95 94 92 93 92 93 95 94 93 92 92 93 93 92 90 91 90 91 93 92 91 90 90 91 91 90 88 89 88 89 91 90 89 88 88 89 89 88 86 87 86 87 89 88 87 86 86 87 85 84 84 85 86 87 87 86 85 84 84 85 83 80 82 81 84 85 85 84 83 80 80 79 82 81 83 80 80 79 81 82 82 81 70 65 62 61 69 76 70 65 69 76 77 77 68 74 76 75 77 77 68 74 77 77 69 76 67 72 75 73 76 75 67 72 76 75 68 74 66 70 74 71 67 72 74 71 75 73 67 72 65 68 73 69 66 70 73 69 74 71 66 70 64 66 72 67 65 68 72 67 73 69 65 68 63 62 71 64 64 66 71 64 72 67 64 66 62 61 70 65 71 64 62 61 71 64 63 62 22 23 20 19 34 34 22 23 34 34 35 35 32 32 33 33 35 35 32 32 35 35 34 34 30 30 31 31 33 33 30 30 33 33 32 32 28 28 29 29 31 31 28 28 31 31 30 30 26 26 27 27 29 29 26 26 29 29 28 28 24 24 25 25 27 27 24 24 27 27 26 26 19 20 23 22 25 25 19 20 25 25 24 24 23 22 19 20 20 19 23 22 20 19 22 23 1 4 0 1 15 16 15 16 14 17 1 4 14 17 13 14 12 15 14 17 15 16 13 14 12 15 11 12 10 13 12 15 13 14 11 12 10 13 9 10 8 11 10 13 11 12 9 10 8 11 7 8 6 9 8 11 9 10 7 8 6 9 5 6 4 7 6 9 7 8 5 6 4 7 3 2 2 3 4 7 5 6 3 2 0 1 2 3 3 2 0 1 1 4 2 3

+
+ + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

137 134 136 134 135 134 135 135 136 135 134 135 137 138 139 138 138 138 138 139 139 139 134 139 137 142 141 142 140 142 140 143 141 143 134 143 137 146 143 146 142 146 142 147 143 147 134 147 137 150 145 150 144 150 144 151 145 151 134 151 137 154 147 154 146 154 146 155 147 155 134 155 137 158 149 158 148 158 148 159 149 159 134 159 137 162 151 162 150 162 150 163 151 163 134 163 178 188 180 188 179 188 181 189 180 189 178 189 183 192 182 192 179 192 181 193 182 193 183 193 185 196 184 196 179 196 181 197 184 197 185 197 187 200 186 200 179 200 181 201 186 201 187 201 189 204 188 204 179 204 181 205 188 205 189 205 191 208 190 208 179 208 181 209 190 209 191 209 193 212 192 212 179 212 181 213 192 213 193 213 195 216 194 216 179 216 181 217 194 217 195 217 199 222 200 222 197 222 197 223 200 223 198 223 199 226 202 226 201 226 201 227 202 227 198 227 199 230 204 230 203 230 203 231 204 231 198 231 199 234 206 234 205 234 205 235 206 235 198 235 199 238 208 238 207 238 207 239 208 239 198 239 199 242 210 242 209 242 209 243 210 243 198 243 199 246 212 246 211 246 211 247 212 247 198 247 199 250 196 250 213 250 213 251 196 251 198 251 266 300 268 300 267 300 269 301 268 301 266 301 271 304 270 304 267 304 269 305 270 305 271 305 273 308 272 308 267 308 269 309 272 309 273 309 275 312 274 312 267 312 269 313 274 313 275 313 277 316 276 316 267 316 269 317 276 317 277 317 279 320 278 320 267 320 269 321 278 321 279 321 281 324 280 324 267 324 269 325 280 325 281 325 283 328 282 328 267 328 269 329 282 329 283 329

+
+
+ 1 +
+
+ + + + 0 0 0 + 0 0 1 0 + 0 1 0 0 + 1 0 0 0 + 0.1335572 0.1335572 0.1335572 + + + + + + + + + + + + + + + + +
diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/quadrotor_base.stl b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/quadrotor_base.stl new file mode 100644 index 0000000..d553efc Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/quadrotor_base.stl differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/quadrotor_base_red_none.dae b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/quadrotor_base_red_none.dae new file mode 100644 index 0000000..af9131f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/meshes/quadrotor/quadrotor_base_red_none.dae @@ -0,0 +1,229 @@ + + + + + Blender User + Blender 2.79.0 + + 2018-10-19T14:54:03 + 2018-10-19T14:54:03 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 1 0 0.0106101 1 + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 0.2 0.2 0.2 1 + + + 0 0 0 1 + + + 0.4575223 0.4575223 0.4575223 1 + + + 1 1 1 1 + + + 33 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.05496641 0.05496641 0.05496641 1 + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.5925679 0.5925679 0.5925679 1 + + + 0.5 0.5 0.5 1 + + + 20 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + + + + + + + + + + + + + + + 0.8236175 0.673869 -1.366201 -0.8236175 0.6738689 -1.366201 -0.8236175 0.6852639 -1.361481 0.8236175 0.6852641 -1.361481 -0.8236175 0.6899839 -1.350086 0.8236175 0.689984 -1.350086 -0.8236175 0.6852639 -1.338691 0.8236175 0.685264 -1.338691 -0.8236175 0.6738689 -1.333971 0.8236175 0.673869 -1.333971 -0.8236175 0.6624739 -1.338691 0.8236175 0.662474 -1.338691 -0.8236175 0.657754 -1.350086 0.8236175 0.6577541 -1.350086 -0.8236175 0.6624739 -1.361481 0.8236175 0.6624741 -1.361481 0.8236175 0.673869 -1.350086 -0.8236175 0.6738689 -1.350086 0.8236174 -0.6738691 -1.350086 0.8236174 -0.662474 -1.361481 0.8236174 -0.6738691 -1.366201 -0.8236175 -0.6738691 -1.350086 -0.8236175 -0.6738691 -1.366201 -0.8236175 -0.6624742 -1.361481 0.8236174 -0.6577541 -1.350086 -0.8236175 -0.6577541 -1.350086 0.8236174 -0.662474 -1.338691 -0.8236175 -0.662474 -1.338691 0.8236174 -0.6738691 -1.333971 -0.8236175 -0.6738691 -1.333971 0.8236174 -0.6852641 -1.338691 -0.8236175 -0.6852641 -1.338691 0.8236174 -0.689984 -1.350086 -0.8236175 -0.689984 -1.350086 0.8236174 -0.6852641 -1.361481 -0.8236175 -0.6852641 -1.361481 0.5614412 0.08138328 0 0.5614412 0.07047998 -0.04069161 0.5614412 0.04069161 -0.07047998 0.5614412 0 -0.08138328 0.5614412 -0.04069161 -0.07047998 0.5614413 -0.07047998 -0.04069161 0.5614413 -0.08138328 0 0.5614413 -0.07047998 0.04069155 0.5614412 -0.04069167 0.07047992 0.560442 -0.001217126 0.08256208 0.560442 0.03947442 0.07165879 0.5614412 0.07047992 0.04069167 2.084521 0.08138328 0 2.084521 0.07048004 -0.04069155 2.084521 0.04069167 -0.07047986 2.084521 0 -0.08138328 2.084521 -0.04069155 -0.07047998 2.084521 -0.07047986 -0.04069167 2.084521 -0.08138328 0 2.084521 -0.07048004 0.04069155 2.084521 -0.04069173 0.07047992 2.084521 0 0.08138328 2.083522 0.03947442 0.07165884 2.084521 0.07047992 0.04069173 0.5614412 0 0 2.084521 0 0 0.6738689 0.6899839 -1.332763 0.6852639 0.6852639 -1.332763 0.6899839 0.6738689 -1.332763 0.6852639 0.6624739 -1.332763 0.6738689 0.657754 -1.332763 0.6624739 0.6624739 -1.332763 0.657754 0.6738689 -1.332763 0.6624739 0.6852639 -1.332763 0.2994973 0.3156122 -0.303241 0.3108922 0.3108922 -0.303241 0.3156122 0.2994973 -0.303241 0.3108922 0.2881023 -0.303241 0.2994973 0.2833823 -0.303241 0.2881022 0.2881023 -0.303241 0.2833823 0.2994973 -0.303241 0.2881023 0.3108922 -0.303241 0.6738689 0.6738689 -1.332763 0.2994973 0.2994973 -0.303241 0.3156121 -0.2994973 -0.303241 0.6899838 -0.673869 -1.332763 0.6852638 -0.6624739 -1.332763 0.3108922 -0.2881023 -0.303241 0.6738688 -0.657754 -1.332763 0.2994972 -0.2833823 -0.303241 0.6624738 -0.6624739 -1.332763 0.2881022 -0.2881023 -0.303241 0.6577539 -0.673869 -1.332763 0.2833822 -0.2994973 -0.303241 0.6624738 -0.6852639 -1.332763 0.2881022 -0.3108923 -0.303241 0.6738688 -0.6899839 -1.332763 0.2994972 -0.3156122 -0.303241 0.6852638 -0.6852639 -1.332763 0.3108922 -0.3108922 -0.303241 0.2994972 -0.2994973 -0.303241 0.6738688 -0.673869 -1.332763 -0.673869 -0.6738688 -1.332763 -0.685264 -0.6852638 -1.332763 -0.6738691 -0.6899837 -1.332763 -0.2994973 -0.2994972 -0.303241 -0.2994973 -0.3156121 -0.303241 -0.3108923 -0.3108922 -0.303241 -0.689984 -0.6738687 -1.332763 -0.3156123 -0.2994972 -0.303241 -0.685264 -0.6624737 -1.332763 -0.3108923 -0.2881022 -0.303241 -0.673869 -0.6577538 -1.332763 -0.2994973 -0.2833822 -0.303241 -0.662474 -0.6624737 -1.332763 -0.2881023 -0.2881022 -0.303241 -0.6577541 -0.6738688 -1.332763 -0.2833824 -0.2994972 -0.303241 -0.662474 -0.6852638 -1.332763 -0.2881023 -0.3108922 -0.303241 -0.3156121 0.2994973 -0.303241 -0.6899837 0.6738693 -1.332763 -0.6852637 0.662474 -1.332763 -0.3108922 0.2881023 -0.303241 -0.6738687 0.6577541 -1.332763 -0.2994971 0.2833824 -0.303241 -0.6624737 0.662474 -1.332763 -0.2881022 0.2881023 -0.303241 -0.6577537 0.6738691 -1.332763 -0.2833822 0.2994973 -0.303241 -0.6624737 0.6852641 -1.332763 -0.2881022 0.3108924 -0.303241 -0.6738685 0.689984 -1.332763 -0.2994971 0.3156123 -0.303241 -0.6852637 0.6852641 -1.332763 -0.3108922 0.3108923 -0.303241 -0.2994971 0.2994973 -0.303241 -0.6738687 0.6738691 -1.332763 1.969194 0 0.1871857 2.886225 -0.3798463 0.2218515 2.671059 -0.7018645 0.2218514 1.969194 0 0.2620601 2.349041 -0.9170302 0.2218514 1.969195 -0.9925863 0.2218514 1.589348 -0.9170302 0.2218514 1.26733 -0.7018646 0.2218514 1.052164 -0.3798465 0.2218515 0.9766083 -2.36674e-7 0.2218515 1.052164 0.379846 0.2218516 1.26733 0.7018642 0.2218517 1.589348 0.9170299 0.2218517 1.969194 0.992586 0.2218518 2.34904 0.91703 0.2218517 2.671058 0.7018645 0.2218517 2.886224 0.3798464 0.2218516 2.96178 3.25924e-7 0.2218515 0 -0.5614412 0 0.08138316 -0.5614412 0 0.07047986 -0.5614412 -0.04069161 -2.69139e-7 -2.084521 0 0.07047975 -2.084521 -0.04069155 0.08138298 -2.084521 0 0.04069155 -0.5614412 -0.07047998 0.04069143 -2.084521 -0.07047992 0 -0.5614412 -0.08138328 -1.69274e-7 -2.084521 -0.08138328 -0.04069167 -0.5614412 -0.07047998 -0.04069179 -2.084521 -0.07047998 -0.07048004 -0.5614413 -0.04069167 -0.07048016 -2.084521 -0.04069167 -0.08138334 -0.5614413 0 -0.08138352 -2.084521 0 -0.07048004 -0.5614413 0.04069161 -0.07048028 -2.084521 0.04069155 -0.04069173 -0.5614412 0.07047998 -0.04069197 -2.084521 0.07047992 -1.3514e-7 -0.5614412 0.08138328 -3.81294e-7 -2.084521 0.08138328 0.04069143 -0.5614412 0.07047998 0.04069125 -2.084521 0.07048004 0.07047986 -0.5614412 0.04069167 0.07047963 -2.084521 0.04069173 0.379846 -2.886224 0.2218516 -2.61752e-7 -1.969194 0.1871857 0 -2.96178 0.2218515 -3.25223e-7 -1.969194 0.2620601 0.7018641 -2.671058 0.2218517 0.9170297 -2.34904 0.2218517 0.9925858 -1.969194 0.2218517 0.9170296 -1.589348 0.2218517 0.701864 -1.26733 0.2218517 0.3798459 -1.052164 0.2218516 -3.6789e-7 -0.9766083 0.2218515 -0.3798466 -1.052164 0.2218514 -0.7018647 -1.26733 0.2218514 -0.9170304 -1.589348 0.2218513 -0.9925865 -1.969194 0.2218513 -0.9170305 -2.34904 0.2218513 -0.7018648 -2.671059 0.2218514 -0.3798467 -2.886225 0.2218514 -2.96178 4.69959e-7 0.2218515 -2.886225 0.3798471 0.2218514 -1.969194 5.26331e-7 0.1871857 -1.969194 5.89802e-7 0.2620601 -2.671059 0.7018652 0.2218514 -2.34904 0.9170308 0.2218513 -1.969194 0.9925867 0.2218513 -1.589348 0.9170306 0.2218513 -1.26733 0.7018649 0.2218514 -1.052164 0.3798468 0.2218514 -0.9766083 4.99106e-7 0.2218515 -1.052164 -0.3798457 0.2218516 -1.26733 -0.7018638 0.2218517 -1.589348 -0.9170294 0.2218517 -1.969194 -0.9925855 0.2218517 -2.349041 -0.9170294 0.2218517 -2.671058 -0.7018638 0.2218517 -2.886224 -0.3798456 0.2218516 -0.5614412 -0.07047981 0.04069167 -0.5614412 -0.0813831 0 -2.084521 -0.08138269 0 -2.084521 -0.07047933 0.04069173 -0.5614412 -0.04069137 0.07047998 -2.084521 -0.04069095 0.07048004 -0.5614412 2.10574e-7 0.08138328 -2.084521 6.61367e-7 0.08138328 -0.5614412 0.04069179 0.07047998 -2.084521 0.04069226 0.07047992 -0.5614413 0.0704801 0.04069161 -2.084521 0.07048058 0.04069155 -0.5614413 0.0813834 0 -2.084521 0.08138382 0 -0.5614413 0.0704801 -0.04069167 -2.084521 0.07048046 -0.04069167 -0.5614412 0.04069179 -0.07047998 -2.084521 0.04069209 -0.07047998 -0.5614412 1.54427e-7 -0.08138328 -2.084521 4.49347e-7 -0.08138328 -0.5614412 -0.04069149 -0.07047998 -2.084521 -0.04069113 -0.07047992 -0.5614412 -0.07047981 -0.04069161 -2.084521 -0.07047945 -0.04069155 -2.084521 5.49213e-7 0 -0.5614412 1.61804e-7 0 2.37238e-7 0.5614412 0 -0.08138304 0.5614412 0 -0.07047975 0.5614412 -0.04069161 8.29287e-7 2.084521 0 -0.07047921 2.084521 -0.04069155 -0.08138245 2.084521 0 -0.04069137 0.5614412 -0.07047998 -0.04069083 2.084521 -0.07047992 2.29861e-7 0.5614412 -0.08138328 7.29421e-7 2.084521 -0.08138328 0.04069185 0.5614412 -0.07047998 0.04069238 2.084521 -0.07047998 0.07048016 0.5614413 -0.04069167 0.07048076 2.084521 -0.04069167 0.08138352 0.5614413 0 0.08138412 2.084521 0 0.07048022 0.5614413 0.04069161 0.07048088 2.084521 0.04069155 0.04069191 0.5614412 0.07047998 0.04069256 2.084521 0.07047992 2.86009e-7 0.5614412 0.08138328 9.41441e-7 2.084521 0.08138328 -0.04069131 0.5614412 0.07047998 -0.04069072 2.084521 0.07048004 -0.07047975 0.5614412 0.04069167 -0.07047903 2.084521 0.04069173 -0.3798453 2.886224 0.2218516 7.9091e-7 1.969194 0.1871857 8.67901e-7 2.96178 0.2218515 8.54381e-7 1.969194 0.2620601 -0.7018634 2.671058 0.2218517 -0.9170291 2.349041 0.2218517 -0.9925853 1.969195 0.2218517 -0.9170292 1.589348 0.2218517 -0.7018637 1.26733 0.2218517 -0.3798456 1.052164 0.2218516 6.30322e-7 0.9766083 0.2218515 0.3798469 1.052164 0.2218514 0.7018651 1.26733 0.2218514 0.9170309 1.589348 0.2218513 0.992587 1.969194 0.2218513 0.9170311 2.34904 0.2218513 0.7018656 2.671059 0.2218514 0.3798475 2.886225 0.2218514 0.3369342 0.5615574 -0.2994973 0.3369344 -0.5615572 -0.2994973 -0.3369344 -0.5615574 -0.2994973 -0.3369344 0.5615576 -0.2994973 0.3369346 0.5615574 0.2994973 0.3369344 -0.5615576 0.2994973 -0.3369344 -0.5615574 0.2994973 -0.3369344 0.5615572 0.2994973 0.5615572 0.3369344 -0.2994973 -0.5615572 0.3369347 -0.2994973 0.5615576 0.3369343 0.2994973 -0.5615572 0.3369344 0.2994973 0.5615572 -0.3369344 -0.2994973 -0.5615575 -0.3369343 -0.2994973 0.5615574 -0.3369347 0.2994973 -0.5615575 -0.3369344 0.2994973 + + + + + + + + + + 1 0 0 0.6302583 0 -0.7763856 0.6302602 0.5489864 -0.5489864 -0.6302602 0.5489864 -0.5489864 -0.6302583 0 -0.7763856 -1 0 0 0.6302583 0.7763856 0 -0.6302583 0.7763856 0 0.6302602 0.5489864 0.5489864 -0.6302602 0.5489864 0.5489864 0.6302583 0 0.7763856 -0.6302583 0 0.7763856 0.6302602 -0.5489864 0.5489864 -0.6302602 -0.5489864 0.5489864 0.6302583 -0.7763856 0 -0.6302583 -0.7763856 0 0.6302602 -0.5489864 -0.5489864 -0.6302602 -0.5489864 -0.5489864 1 -2.24983e-6 0 -1 2.81229e-7 0 1 -3.37475e-6 0 1 7.8744e-6 0 -1 -3.37475e-6 1.46479e-6 1 -4.49967e-6 0 -1 -1.12492e-6 -3.92489e-7 -1 -1.12492e-6 3.92489e-7 -1 -2.24983e-6 -1.46479e-6 -0.9996916 -0.02150607 -0.01241582 1 2.24983e-6 0 -0.9999209 -0.003253757 -0.01214957 0.9996798 0.02530705 0 -0.9997215 0.01180022 -0.02044135 0.9997214 -0.01180779 0.02044135 -1 5.52928e-7 0 0 0 -1 0.06228959 0.8715052 -0.4864144 0.6329994 0.6329994 -0.4456723 0 0 1 0.4264737 0.4264737 0.7976468 -0.06045901 0.6646835 0.744675 0.8715052 0.06228959 -0.4864144 0.6646835 -0.06045901 0.744675 0.6226522 -0.494197 -0.6066907 0.494197 -0.6226522 0.6066907 0.06045901 -0.6646835 -0.744675 -0.06228959 -0.8715052 0.4864144 -0.4264737 -0.4264737 -0.7976468 -0.6329994 -0.6329994 0.4456723 -0.6646835 0.06045901 -0.744675 -0.8715052 -0.06228959 0.4864144 -0.494197 0.6226522 -0.6066907 -0.6226522 0.494197 0.6066907 0.6646835 0.06045901 0.744675 0.494197 0.6226522 0.6066907 0.6226522 0.494197 -0.6066907 0.871518 -0.06229048 -0.486391 -0.06228959 0.8715052 0.4864144 0.06045901 0.6646835 -0.744675 -0.6329994 0.6329994 0.4456723 -0.4264737 0.4264737 -0.7976468 -0.8715052 0.06228959 0.4864144 -0.6646835 -0.06045901 -0.744675 -0.6226522 -0.494197 0.6066907 -0.494197 -0.6226522 -0.6066907 -0.06045901 -0.6646835 0.744675 0.06228959 -0.8715052 -0.4864144 0.4264737 -0.4264737 0.7976468 0.6329994 -0.6329994 -0.4456723 -0.06229048 -0.871518 -0.486391 -0.6329994 -0.6329994 -0.4456723 -0.4264737 -0.4264737 0.7976468 0.06045901 -0.6646835 0.744675 -0.871518 -0.06229048 -0.486391 -0.6646835 0.06045901 0.744675 -0.6226522 0.494197 -0.6066907 -0.494197 0.6226522 0.6066907 -0.06045901 0.6646835 -0.744675 0.06228959 0.8715052 0.4864144 0.4264737 0.4264737 -0.7976468 0.6329994 0.6329994 0.4456723 0.6646835 -0.06045901 -0.744675 0.8715052 0.06228959 0.4864144 0.494197 -0.6226522 -0.6066907 0.6226522 -0.494197 0.6066907 -0.6646835 -0.06045901 0.744675 -0.494197 -0.6226522 0.6066907 -0.6226522 -0.494197 -0.6066907 -0.8715052 0.06228959 -0.4864144 0.06228959 -0.8715052 0.4864144 -0.06045901 -0.6646835 -0.744675 0.6329994 -0.6329994 0.4456723 0.4264737 -0.4264737 -0.7976468 0.871518 -0.06229048 0.486391 0.6646835 0.06045901 -0.744675 0.6226522 0.494197 0.6066907 0.494197 0.6226522 -0.6066907 0.06045901 0.6646835 0.744675 -0.06228959 0.8715052 -0.4864144 -0.4264737 0.4264737 0.7976468 -0.6329994 0.6329994 -0.4456723 0.03490263 -0.006942212 -0.9993667 0.04047435 -0.008050978 0.9991483 0.03431254 -0.0229271 0.9991481 0.02958899 -0.01977056 -0.9993667 0.01977074 -0.02958875 -0.9993667 0.0229268 -0.0343126 0.9991483 0.008050799 -0.04047453 0.9991482 0.00694257 -0.03490233 -0.9993667 -0.00694257 -0.03490239 -0.9993667 -0.008050799 -0.04047447 0.9991481 -0.02292686 -0.03431266 0.9991482 -0.01977074 -0.02958875 -0.9993667 -0.02958893 -0.01977056 -0.9993667 -0.03431242 -0.02292704 0.9991483 -0.04047429 -0.008051037 0.9991483 -0.03490263 -0.006942272 -0.9993666 -0.03490257 0.006942689 -0.9993666 -0.04047429 0.00805062 0.9991483 -0.03431254 0.02292662 0.9991483 -0.02958899 0.01977092 -0.9993666 -0.01977074 0.02958923 -0.9993667 -0.0229268 0.03431224 0.9991482 -0.008050799 0.04047405 0.9991483 -0.00694257 0.03490281 -0.9993667 0.00694257 0.03490275 -0.9993667 0.008050799 0.04047405 0.9991483 0.02292686 0.0343123 0.9991482 0.01977068 0.02958923 -0.9993667 0.02958899 0.01977097 -0.9993666 0.03431248 0.02292656 0.9991482 0.04047429 0.00805068 0.9991483 0.03490263 0.006942689 -0.9993667 0 1 2.81229e-7 0 -1 4.49966e-6 0 1 1.12492e-6 0 -1 -2.24983e-6 0 1 0 0 -1 0 -2.53709e-6 1 0 0 -1 2.24983e-6 -1.46479e-6 1 -1.12492e-6 0 -1 2.24983e-6 -1.46479e-6 1 5.62457e-7 0 -1 -4.49966e-6 -2.53709e-6 1 0 0 1 1.12491e-6 0 -1 4.49966e-6 0 1 -1.12492e-6 0 -1 -4.49966e-6 0 1 -1.12491e-6 0 1 2.81229e-7 0 -1 -2.24983e-6 0.006942749 -0.03490263 -0.9993666 0.00805068 -0.04047423 0.9991482 0.02292668 -0.03431242 0.9991481 0.01977086 -0.02958899 -0.9993667 0.02958923 -0.01977074 -0.9993667 0.03431218 -0.02292686 0.9991483 0.04047405 -0.008050799 0.9991483 0.03490281 -0.00694257 -0.9993666 0.03490281 0.00694257 -0.9993666 0.04047405 0.008050799 0.9991483 0.03431218 0.02292686 0.9991483 0.02958923 0.01977068 -0.9993667 0.01977092 0.02958899 -0.9993666 0.02292668 0.03431242 0.9991483 0.00805062 0.04047423 0.9991482 0.006942689 0.03490263 -0.9993667 -0.006942272 0.03490263 -0.9993667 -0.008051097 0.04047423 0.9991482 -0.02292704 0.03431242 0.9991482 -0.0197705 0.02958893 -0.9993667 -0.02958875 0.01977074 -0.9993667 -0.03431266 0.0229268 0.9991482 -0.04047447 0.008050858 0.9991481 -0.03490233 0.006942451 -0.9993667 -0.03490233 -0.00694251 -0.9993667 -0.04047453 -0.008050858 0.9991481 -0.03431266 -0.0229268 0.9991482 -0.02958869 -0.01977074 -0.9993667 -0.01977056 -0.02958893 -0.9993667 -0.02292704 -0.03431242 0.9991482 -0.008051037 -0.04047423 0.9991482 -0.006942212 -0.03490263 -0.9993667 -0.03490257 0.006942093 -0.9993667 -0.04047429 0.008051097 0.9991483 -0.03431242 0.02292704 0.9991482 -0.02958899 0.01977056 -0.9993667 -0.01977068 0.02958875 -0.9993667 -0.0229268 0.03431272 0.9991481 -0.008050799 0.04047447 0.9991482 -0.00694251 0.03490233 -0.9993667 0.00694251 0.03490233 -0.9993667 0.008050799 0.04047453 0.9991481 0.0229268 0.03431266 0.9991481 0.01977074 0.02958875 -0.9993667 0.02958899 0.0197705 -0.9993667 0.03431242 0.02292698 0.9991482 0.04047423 0.008051156 0.9991482 0.03490263 0.006942212 -0.9993667 0.03490263 -0.006942689 -0.9993667 0.04047423 -0.00805062 0.9991482 0.03431242 -0.02292668 0.9991482 0.02958899 -0.01977092 -0.9993667 0.01977068 -0.02958917 -0.9993666 0.02292686 -0.03431218 0.9991483 0.008050739 -0.04047411 0.9991483 0.00694257 -0.03490281 -0.9993667 -0.00694257 -0.03490275 -0.9993667 -0.008050739 -0.04047411 0.9991483 -0.02292692 -0.03431218 0.9991482 -0.01977068 -0.02958923 -0.9993667 -0.02958893 -0.01977092 -0.9993666 -0.03431242 -0.02292656 0.9991483 -0.04047423 -0.008050739 0.9991482 -0.03490263 -0.006942689 -0.9993667 -1 5.62457e-6 0 -1 -2.24983e-6 0 1 2.24983e-6 -1.46479e-6 1 2.24983e-6 3.92489e-7 1 2.24983e-6 -3.92489e-7 -1 4.49966e-6 0 1 2.24983e-6 1.46479e-6 -1 -7.8744e-6 0 -1 2.24983e-6 0 0 -1 2.81229e-7 0 1 4.49966e-6 0 1 2.24983e-6 0 -1 -1.12492e-6 2.53709e-6 -1 2.24983e-6 1.46479e-6 -1 -1.12492e-6 0 1 -6.74949e-6 1.46479e-6 -1 5.62457e-7 0 1 4.49966e-6 2.53709e-6 -1 -1.12492e-6 0 1 2.24983e-6 0 -1 1.12491e-6 0 1 4.49966e-6 0 -1 -1.12492e-6 0 1 -4.49966e-6 0 1 -4.49966e-6 0 -1 2.81229e-7 0 1 -2.24983e-6 -0.006942749 0.03490263 -0.9993667 -0.00805068 0.04047423 0.9991482 -0.02292662 0.03431242 0.9991482 -0.01977092 0.02958899 -0.9993666 -0.02958917 0.01977074 -0.9993667 -0.03431218 0.02292692 0.9991481 -0.04047405 0.008050799 0.9991482 -0.03490281 0.00694257 -0.9993666 -0.03490281 -0.00694257 -0.9993666 -0.04047405 -0.008050799 0.9991483 -0.03431212 -0.02292686 0.9991482 -0.02958923 -0.01977068 -0.9993667 -0.01977092 -0.02958899 -0.9993666 -0.02292668 -0.03431242 0.9991482 -0.00805062 -0.04047423 0.9991482 -0.006942689 -0.03490263 -0.9993667 0.006942272 -0.03490263 -0.9993667 0.008051037 -0.04047423 0.9991482 0.02292704 -0.03431248 0.9991481 0.0197705 -0.02958899 -0.9993667 0.02958869 -0.01977074 -0.9993667 0.03431266 -0.0229268 0.9991482 0.04047447 -0.008050858 0.9991481 0.03490239 -0.00694251 -0.9993667 0.03490233 0.006942451 -0.9993667 0.04047453 0.008050858 0.9991481 0.03431272 0.02292674 0.9991481 0.02958875 0.01977068 -0.9993667 0.01977056 0.02958893 -0.9993667 0.02292704 0.03431242 0.9991482 0.008051037 0.04047423 0.9991482 0.006942212 0.03490257 -0.9993667 -1 4.42999e-7 0 -1 2.95333e-7 0 -0.7071066 -0.7071071 0 -0.707107 -0.7071067 0 0.7071068 -0.7071068 -4.69872e-7 0.7071068 -0.7071068 -5.48184e-7 1 -4.42999e-7 -1.99016e-7 1 0 -5.97047e-7 0 0 1 0 0 -1 0 0 -1 -0.7071068 0.7071068 3.9156e-7 -0.7071069 0.7071067 5.48184e-7 0.7071068 0.7071068 -5.24176e-7 0.7071069 0.7071067 -2.34936e-7 0 0 -1 0 0 -1 -2.65354e-7 1 0 3.53806e-7 1 5.90666e-7 -3.53806e-7 -1 -5.90666e-7 2.65354e-7 -1 0 -0.6557323 -0.6532297 0.3785583 -0.7571544 0.653236 0 -0.7571544 -0.653236 0 -0.6557323 0.6532297 0.3785583 -0.3785582 -0.6532296 0.6557322 -0.3785658 0.6532427 0.6557148 0 -0.653236 0.7571544 0 0.653236 0.7571544 0.3785582 -0.6532296 0.6557322 0.3785582 0.6532296 0.6557322 0.6557323 -0.6532297 0.3785583 0.6557247 0.6532222 0.3785844 0.7571544 -0.653236 0 0.7571544 0.653236 0 0.6557323 -0.6532297 -0.3785583 0.6557072 0.6532351 -0.378592 0.3785582 -0.6532296 -0.6557322 0.3785582 0.6532296 -0.6557322 0 -0.653236 -0.7571544 0 0.653236 -0.7571544 -0.3785582 -0.6532296 -0.6557322 -0.3785582 0.6532296 -0.6557322 -0.6557323 -0.6532297 -0.3785583 -0.6557323 0.6532297 -0.3785583 0.653236 -0.7571544 0 -0.653236 -0.7571544 0 -0.6532297 -0.6557323 -0.3785583 0.6532297 -0.6557323 -0.3785583 -0.6532296 -0.3785582 -0.6557322 0.6532296 -0.3785582 -0.6557322 -0.653236 0 -0.7571544 0.653236 0 -0.7571544 -0.6532296 0.3785582 -0.6557322 0.6532296 0.3785582 -0.6557322 -0.6532297 0.6557323 -0.3785583 0.6532297 0.6557323 -0.3785583 -0.653236 0.7571544 0 0.653236 0.7571544 0 -0.6532297 0.6557323 0.3785583 0.6532297 0.6557323 0.3785583 -0.6532296 0.3785582 0.6557322 0.6532296 0.3785582 0.6557322 -0.653236 0 0.7571544 0.653236 0 0.7571544 -0.6532296 -0.3785582 0.6557322 0.6532296 -0.3785582 0.6557322 -0.6532297 -0.6557323 0.3785583 0.6532297 -0.6557323 0.3785583 0.6557323 0.6532297 0.3785583 -0.3785582 0.6532296 0.6557322 0.6557323 0.6532297 -0.3785583 -0.6503974 0.6608045 0.3745942 0.6558382 0.6504973 0.383053 -0.6598159 0.3809048 0.6477304 0.6418532 0.3770365 0.6677336 -0.6564947 -0.020051 0.7540641 0.658137 -8.85044e-4 0.7528977 -0.6533265 -0.3956215 0.645483 + + + + + + + + + + + + + + +

60 5 36 5 37 5 60 5 37 5 38 5 60 19 38 19 39 19 60 19 39 19 40 19 60 22 40 22 41 22 60 24 41 24 42 24 60 25 42 25 43 25 60 26 43 26 44 26 60 27 44 27 45 27 60 29 45 29 46 29 60 31 46 31 47 31 47 33 36 33 60 33

+
+ + + +

151 100 135 100 134 100 137 101 135 101 151 101 136 104 138 104 134 104 137 105 138 105 136 105 139 108 140 108 134 108 137 109 140 109 139 109 141 112 142 112 134 112 137 113 142 113 141 113 143 116 144 116 134 116 137 117 144 117 143 117 145 120 146 120 134 120 137 121 146 121 145 121 147 124 148 124 134 124 137 125 148 125 147 125 149 128 150 128 134 128 137 129 150 129 149 129 181 154 178 154 182 154 182 155 178 155 179 155 181 158 183 158 184 158 184 159 183 159 179 159 181 162 185 162 186 162 186 163 185 163 179 163 181 166 187 166 188 166 188 167 187 167 179 167 181 170 189 170 190 170 190 171 189 171 179 171 181 174 191 174 192 174 192 175 191 175 179 175 181 178 193 178 194 178 194 179 193 179 179 179 181 182 195 182 180 182 180 183 195 183 179 183 196 184 197 184 198 184 199 185 197 185 196 185 200 188 201 188 198 188 199 189 201 189 200 189 202 192 203 192 198 192 199 193 203 193 202 193 204 196 205 196 198 196 199 197 205 197 204 197 206 200 207 200 198 200 199 201 207 201 206 201 208 204 209 204 198 204 199 205 209 205 208 205 210 208 211 208 198 208 199 209 211 209 210 209 212 212 213 212 198 212 199 213 213 213 212 213 269 245 266 245 270 245 270 246 266 246 267 246 269 249 271 249 272 249 272 250 271 250 267 250 269 253 273 253 274 253 274 254 273 254 267 254 269 257 275 257 276 257 276 258 275 258 267 258 269 261 277 261 278 261 278 262 277 262 267 262 269 265 279 265 280 265 280 266 279 266 267 266 269 269 281 269 282 269 282 270 281 270 267 270 269 273 283 273 268 273 268 274 283 274 267 274

+
+ + + +

16 0 0 1 3 2 2 3 1 4 17 5 16 0 3 2 5 6 17 5 4 7 2 3 16 0 5 6 7 8 17 5 6 9 4 7 16 0 7 8 9 10 17 5 8 11 6 9 16 0 9 10 11 12 17 5 10 13 8 11 16 0 11 12 13 14 17 5 12 15 10 13 16 0 13 14 15 16 17 5 14 17 12 15 15 16 0 1 16 0 17 5 1 4 14 17 18 0 20 1 19 2 21 5 23 3 22 4 18 0 19 2 24 6 21 5 25 7 23 3 18 0 24 6 26 8 21 5 27 9 25 7 18 0 26 8 28 10 21 5 29 11 27 9 18 0 28 10 30 12 21 5 31 13 29 11 18 0 30 12 32 14 21 5 33 15 31 13 18 0 32 14 34 16 21 5 35 17 33 15 34 16 20 1 18 0 35 17 21 5 22 4 61 0 49 0 48 0 61 18 50 18 49 18 61 20 51 20 50 20 61 21 52 21 51 21 61 23 53 23 52 23 61 0 54 0 53 0 61 0 55 0 54 0 61 0 56 0 55 0 61 28 57 28 56 28 61 30 58 30 57 30 61 32 59 32 58 32 61 0 48 0 59 0 78 34 62 35 63 36 79 37 71 38 70 39 78 34 63 36 64 40 79 37 72 41 71 38 78 34 64 40 65 42 79 37 73 43 72 41 78 34 65 42 66 44 79 37 74 45 73 43 78 34 66 44 67 46 79 37 75 47 74 45 78 34 67 46 68 48 79 37 76 49 75 47 78 34 68 48 69 50 79 37 77 51 76 49 69 50 62 35 78 34 79 37 70 39 77 51 96 37 80 52 83 53 82 54 81 55 97 34 96 37 83 53 85 56 97 34 84 57 82 54 96 37 85 56 87 58 97 34 86 59 84 57 96 37 87 58 89 60 97 34 88 61 86 59 96 37 89 60 91 62 97 34 90 63 88 61 96 37 91 62 93 64 97 34 92 65 90 63 96 37 93 64 95 66 97 34 94 67 92 65 96 37 95 66 80 52 97 34 81 55 94 67 98 34 100 68 99 69 101 37 103 70 102 71 98 34 99 69 104 72 101 37 105 73 103 70 98 34 104 72 106 74 101 37 107 75 105 73 98 34 106 74 108 76 101 37 109 77 107 75 98 34 108 76 110 78 101 37 111 79 109 77 98 34 110 78 112 80 101 37 113 81 111 79 98 34 112 80 114 82 101 37 115 83 113 81 114 82 100 68 98 34 101 37 102 71 115 83 132 37 116 84 119 85 118 86 117 87 133 34 132 37 119 85 121 88 133 34 120 89 118 86 132 37 121 88 123 90 133 34 122 91 120 89 132 37 123 90 125 92 133 34 124 93 122 91 132 37 125 92 127 94 133 34 126 95 124 93 132 37 127 94 129 96 133 34 128 97 126 95 132 37 129 96 131 98 133 34 130 99 128 97 132 37 131 98 116 84 133 34 117 87 130 99 152 132 153 132 154 132 155 133 156 133 157 133 152 134 154 134 158 134 155 135 159 135 156 135 152 136 158 136 160 136 155 137 161 137 159 137 152 136 160 136 162 136 155 137 163 137 161 137 152 138 162 138 164 138 155 139 165 139 163 139 152 140 164 140 166 140 155 141 167 141 165 141 152 142 166 142 168 142 155 143 169 143 167 143 152 144 168 144 170 144 155 135 171 135 169 135 152 145 170 145 172 145 155 146 173 146 171 146 152 147 172 147 174 147 155 148 175 148 173 148 152 149 174 149 176 149 155 137 177 137 175 137 152 150 176 150 153 150 155 151 157 151 177 151 238 5 216 5 217 5 239 0 214 0 215 0 238 5 217 5 219 5 239 0 218 0 214 0 238 216 219 216 221 216 239 0 220 0 218 0 238 217 221 217 223 217 239 0 222 0 220 0 238 5 223 5 225 5 239 218 224 218 222 218 238 5 225 5 227 5 239 219 226 219 224 219 238 5 227 5 229 5 239 220 228 220 226 220 238 221 229 221 231 221 239 222 230 222 228 222 238 223 231 223 233 223 239 0 232 0 230 0 238 224 233 224 235 224 239 0 234 0 232 0 238 5 235 5 237 5 239 0 236 0 234 0 238 5 237 5 216 5 239 0 215 0 236 0 240 225 241 225 242 225 243 226 244 226 245 226 240 137 242 137 246 137 243 227 247 227 244 227 240 137 246 137 248 137 243 136 249 136 247 136 240 228 248 228 250 228 243 136 251 136 249 136 240 229 250 229 252 229 243 136 253 136 251 136 240 230 252 230 254 230 243 231 255 231 253 231 240 232 254 232 256 232 243 233 257 233 255 233 240 234 256 234 258 234 243 235 259 235 257 235 240 236 258 236 260 236 243 237 261 237 259 237 240 238 260 238 262 238 243 239 263 239 261 239 240 137 262 137 264 137 243 240 265 240 263 240 240 241 264 241 241 241 243 242 245 242 265 242 299 275 295 275 297 275 295 276 293 276 297 276 290 277 299 277 297 277 290 278 297 278 286 278 298 279 289 279 285 279 298 280 285 280 296 280 294 281 298 281 296 281 294 282 296 282 292 282 299 37 290 37 298 37 290 37 289 37 298 37 295 283 299 283 298 283 295 37 298 37 294 37 296 284 285 284 286 284 296 34 286 34 297 34 292 285 296 285 297 285 292 34 297 34 293 34 295 286 291 286 293 286 291 287 287 287 293 287 292 288 284 288 288 288 292 289 288 289 294 289 291 37 295 37 288 37 295 37 294 37 288 37 284 290 292 290 293 290 284 291 293 291 287 291 288 292 284 292 291 292 284 293 287 293 291 293 285 294 289 294 290 294 285 295 290 295 286 295 264 296 245 297 241 298 264 296 265 299 245 297 262 300 265 299 264 296 262 300 263 301 265 299 260 302 263 301 262 300 260 302 261 303 263 301 258 304 261 303 260 302 258 304 259 305 261 303 256 306 259 305 258 304 256 306 257 307 259 305 254 308 257 307 256 306 254 308 255 309 257 307 252 310 255 309 254 308 252 310 253 311 255 309 250 312 253 311 252 310 250 312 251 313 253 311 248 314 251 313 250 312 248 314 249 315 251 313 246 316 249 315 248 314 246 316 247 317 249 315 242 318 247 317 246 316 242 318 244 319 247 317 241 298 244 319 242 318 241 298 245 297 244 319 215 320 216 321 237 322 215 320 237 322 236 323 236 323 237 322 235 324 236 323 235 324 234 325 234 325 235 324 233 326 234 325 233 326 232 327 232 327 233 326 231 328 232 327 231 328 230 329 230 329 231 328 229 330 230 329 229 330 228 331 228 331 229 330 227 332 228 331 227 332 226 333 226 333 227 332 225 334 226 333 225 334 224 335 224 335 225 334 223 336 224 335 223 336 222 337 222 337 223 336 221 338 222 337 221 338 220 339 220 339 221 338 219 340 220 339 219 340 218 341 218 341 219 340 217 342 218 341 217 342 214 343 214 343 217 342 216 321 214 343 216 321 215 320 176 344 157 308 153 309 176 344 177 306 157 308 174 305 177 306 176 344 174 305 175 304 177 306 172 303 175 304 174 305 172 303 173 302 175 304 170 345 173 302 172 303 170 345 171 300 173 302 168 299 171 300 170 345 168 299 169 296 171 300 166 297 169 296 168 299 166 297 167 298 169 296 164 319 167 298 166 297 164 319 165 318 167 298 162 317 165 318 164 319 162 317 163 316 165 318 160 315 163 316 162 317 160 315 161 314 163 316 158 313 161 314 160 315 158 313 159 312 161 314 154 346 159 312 158 313 154 346 156 310 159 312 153 309 156 310 154 346 153 309 157 308 156 310 117 87 131 98 130 99 117 87 116 84 131 98 130 99 131 98 128 97 128 97 131 98 129 96 128 97 129 96 126 95 126 95 129 96 127 94 126 95 127 94 124 93 124 93 127 94 125 92 124 93 125 92 122 91 122 91 125 92 123 90 122 91 121 88 120 89 122 91 123 90 121 88 120 89 119 85 118 86 120 89 121 88 119 85 116 84 118 86 119 85 116 84 117 87 118 86 102 71 100 68 114 82 102 71 114 82 115 83 112 80 113 81 115 83 112 80 115 83 114 82 110 78 111 79 113 81 110 78 113 81 112 80 108 76 109 77 110 78 109 77 111 79 110 78 106 74 107 75 108 76 107 75 109 77 108 76 104 72 105 73 106 74 105 73 107 75 106 74 99 69 103 70 104 72 103 70 105 73 104 72 100 68 102 71 103 70 100 68 103 70 99 69 81 55 95 66 94 67 81 55 80 52 95 66 94 67 95 66 92 65 92 65 95 66 93 64 92 65 93 64 90 63 90 63 93 64 91 62 90 63 91 62 88 61 88 61 91 62 89 60 88 61 89 60 86 59 86 59 89 60 87 58 86 59 85 56 84 57 86 59 87 58 85 56 84 57 83 53 82 54 84 57 85 56 83 53 80 52 82 54 83 53 80 52 81 55 82 54 70 39 62 35 69 50 70 39 69 50 77 51 68 48 76 49 77 51 68 48 77 51 69 50 67 46 75 47 76 49 67 46 76 49 68 48 66 44 74 45 67 46 74 45 75 47 67 46 65 42 73 43 66 44 73 43 74 45 66 44 64 40 72 41 65 42 72 41 73 43 65 42 63 36 71 38 64 40 71 38 72 41 64 40 62 35 70 39 71 38 62 35 71 38 63 36 48 333 36 332 47 347 48 333 47 347 59 348 46 349 58 350 59 348 46 349 59 348 47 347 45 351 57 352 58 350 45 351 58 350 46 349 44 353 56 341 57 352 44 353 57 352 45 351 43 342 55 343 56 341 43 342 56 341 44 353 42 321 54 320 55 343 42 321 55 343 43 342 41 322 53 323 54 320 41 322 54 320 42 321 40 324 52 325 53 323 40 324 53 323 41 322 39 326 51 327 52 325 39 326 52 325 40 324 38 328 50 329 51 327 38 328 51 327 39 326 37 330 49 331 50 329 37 330 50 329 38 328 36 332 48 333 49 331 36 332 49 331 37 330 22 4 20 1 34 16 22 4 34 16 35 17 32 14 33 15 35 17 32 14 35 17 34 16 30 12 31 13 33 15 30 12 33 15 32 14 28 10 29 11 31 13 28 10 31 13 30 12 26 8 27 9 29 11 26 8 29 11 28 10 24 6 25 7 27 9 24 6 27 9 26 8 19 2 23 3 25 7 19 2 25 7 24 6 23 3 19 2 20 1 23 3 20 1 22 4 1 4 0 1 15 16 15 16 14 17 1 4 14 17 13 14 12 15 14 17 15 16 13 14 12 15 11 12 10 13 12 15 13 14 11 12 10 13 9 10 8 11 10 13 11 12 9 10 8 11 7 8 6 9 8 11 9 10 7 8 6 9 5 6 4 7 6 9 7 8 5 6 4 7 3 2 2 3 4 7 5 6 3 2 0 1 2 3 3 2 0 1 1 4 2 3

+
+ + + +

137 102 136 102 135 102 135 103 136 103 134 103 137 106 139 106 138 106 138 107 139 107 134 107 137 110 141 110 140 110 140 111 141 111 134 111 137 114 143 114 142 114 142 115 143 115 134 115 137 118 145 118 144 118 144 119 145 119 134 119 137 122 147 122 146 122 146 123 147 123 134 123 137 126 149 126 148 126 148 127 149 127 134 127 137 130 151 130 150 130 150 131 151 131 134 131 178 152 180 152 179 152 181 153 180 153 178 153 183 156 182 156 179 156 181 157 182 157 183 157 185 160 184 160 179 160 181 161 184 161 185 161 187 164 186 164 179 164 181 165 186 165 187 165 189 168 188 168 179 168 181 169 188 169 189 169 191 172 190 172 179 172 181 173 190 173 191 173 193 176 192 176 179 176 181 177 192 177 193 177 195 180 194 180 179 180 181 181 194 181 195 181 199 186 200 186 197 186 197 187 200 187 198 187 199 190 202 190 201 190 201 191 202 191 198 191 199 194 204 194 203 194 203 195 204 195 198 195 199 198 206 198 205 198 205 199 206 199 198 199 199 202 208 202 207 202 207 203 208 203 198 203 199 206 210 206 209 206 209 207 210 207 198 207 199 210 212 210 211 210 211 211 212 211 198 211 199 214 196 214 213 214 213 215 196 215 198 215 266 243 268 243 267 243 269 244 268 244 266 244 271 247 270 247 267 247 269 248 270 248 271 248 273 251 272 251 267 251 269 252 272 252 273 252 275 255 274 255 267 255 269 256 274 256 275 256 277 259 276 259 267 259 269 260 276 260 277 260 279 263 278 263 267 263 269 264 278 264 279 264 281 267 280 267 267 267 269 268 280 268 281 268 283 271 282 271 267 271 269 272 282 272 283 272

+
+
+ 1 +
+
+ + + + + 0.1335572 0 0 0 0 0.1335572 0 0 0 0 0.1335572 0 0 0 0 1 + + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/package.xml new file mode 100644 index 0000000..5381aba --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/package.xml @@ -0,0 +1,25 @@ + + hector_quadrotor_description + 0.3.5 + hector_quadrotor_description provides an URDF model of a quadrotor UAV. + Johannes Meyer + + BSD + + http://ros.org/wiki/hector_quadrotor_description + https://github.com/tu-darmstadt-ros-pkg/hector_quadrotor/issues + + Johannes Meyer + Stefan Kohlbrecher + + + catkin + + + + + hector_sensors_description + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/extend/aircraft_camera_state_pub.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/extend/aircraft_camera_state_pub.xacro new file mode 100644 index 0000000..f2fa0a1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/extend/aircraft_camera_state_pub.xacro @@ -0,0 +1,18 @@ + + + + + + + + + + ${namespace} + base_link + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/extend/aircraft_pub.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/extend/aircraft_pub.xacro new file mode 100644 index 0000000..725df5a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/extend/aircraft_pub.xacro @@ -0,0 +1,18 @@ + + + + + + + + + + ${namespace} + base_link + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/extend/aircraft_truth.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/extend/aircraft_truth.xacro new file mode 100644 index 0000000..743e60f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/extend/aircraft_truth.xacro @@ -0,0 +1,18 @@ + + + + + + + + + + ${namespace} + base_link + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/extend/aircraft_udp_receive.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/extend/aircraft_udp_receive.xacro new file mode 100644 index 0000000..5578cdc --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/extend/aircraft_udp_receive.xacro @@ -0,0 +1,18 @@ + + + + + + + + + + ${namespace} + base_link + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/generic_camera.urdf.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/generic_camera.urdf.xacro new file mode 100644 index 0000000..ab5e16f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/generic_camera.urdf.xacro @@ -0,0 +1,72 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + ${update_rate} + + ${hfov * M_PI/180.0} + + ${image_format} + ${res_x} + ${res_y} + + + 0.001 + 100000 + + + + + ${name} + ${ros_topic} + ${cam_info_topic} + ${name}_optical_frame + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor.gazebo.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor.gazebo.xacro new file mode 100644 index 0000000..005fde1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor.gazebo.xacro @@ -0,0 +1,7 @@ + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor.urdf.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor.urdf.xacro new file mode 100644 index 0000000..5962ccd --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor.urdf.xacro @@ -0,0 +1,14 @@ + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_base.urdf.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_base.urdf.xacro new file mode 100644 index 0000000..6690f4c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_base.urdf.xacro @@ -0,0 +1,38 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_base_shadow.urdf.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_base_shadow.urdf.xacro new file mode 100644 index 0000000..bfd2895 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_base_shadow.urdf.xacro @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_shadow.gazebo.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_shadow.gazebo.xacro new file mode 100644 index 0000000..5f5e08d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_shadow.gazebo.xacro @@ -0,0 +1,6 @@ + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_shadow.urdf.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_shadow.urdf.xacro new file mode 100644 index 0000000..c79ca0c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_shadow.urdf.xacro @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_with_downward_cam.gazebo.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_with_downward_cam.gazebo.xacro new file mode 100644 index 0000000..4b8a552 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_with_downward_cam.gazebo.xacro @@ -0,0 +1,7 @@ + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_with_downward_cam.urdf.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_with_downward_cam.urdf.xacro new file mode 100644 index 0000000..b56257b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/quadrotor_with_downward_cam.urdf.xacro @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/test_robot.gv b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/test_robot.gv new file mode 100644 index 0000000..c77429b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/test_robot.gv @@ -0,0 +1,14 @@ +digraph G { +node [shape=box]; +"link1" [label="link1"]; +"link2" [label="link2"]; +"link3" [label="link3"]; +"link4" [label="link4"]; +node [shape=ellipse, color=blue, fontcolor=blue]; +"link1" -> "joint1" [label="xyz: 5 3 0 \nrpy: 0 -0 0"] +"joint1" -> "link2" +"link1" -> "joint2" [label="xyz: -2 5 0 \nrpy: 0 -0 1.57"] +"joint2" -> "link3" +"link3" -> "joint3" [label="xyz: 5 0 0 \nrpy: 0 0 -1.57"] +"joint3" -> "link4" +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/test_robot.pdf b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/test_robot.pdf new file mode 100644 index 0000000..820d5e1 Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_description/urdf/test_robot.pdf differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/CHANGELOG.rst b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/CHANGELOG.rst new file mode 100644 index 0000000..3bc0795 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/CHANGELOG.rst @@ -0,0 +1,55 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package hector_quadrotor_gazebo +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.5 (2015-03-28) +------------------ + +0.3.4 (2015-02-22) +------------------ +* added missing run_depend hector_quadrotor_pose_estimation to package.xml +* set pose_estimation/publish_world_nav_transform parameter to true explicitly +* updated package for the latest version of hector_pose_estimation + * Geographic reference latitude and longitude set to 49.860246N 8.687077E (Lichtwiese). + * Reenabled auto_elevation, auto_reference and auto_heading parameters for hector_pose_estimation. + hector_pose_estimation will publish the world->nav transform depending on its reference pose. +* added parameter file for hector_quadrotor_pose_estimation for a simulated quadrotor + The parameter file disables the auto_elevation, auto_reference, auto_heading modes of hector_pose_estimation and sets the corresponding values + manually with what is simulated in the gazebo sensor plugins. This simplifies the comparison of estimated poses with ground truth information. +* explicitly set the pose_estimation/nav_frame parameter in spawn_quadrotor.launch +* disabled detection of available plugins in cmake + The aerodynamics and propulsion plugins are built unconditinally now in hector_quadrotor_gazebo_plugins and the detection is obsolete. + Additionally we used platform-specific library prefixes and suffixes in find_libary() which caused errors on different platforms. +* Contributors: Johannes Meyer + +0.3.3 (2014-09-01) +------------------ +* cleaned up launch files and fixed argument forwarding to spawn_quadrotor.launch +* removed all RTT related plugins +* added separate update timer for MotorStatus output in propulsion plugin +* added launch file argument to enable/disable pose estimation +* moved simulation package dependencies from hector_quadrotor metapackage to hector_quadrotor_gazebo +* Contributors: Johannes Meyer + +0.3.2 (2014-03-30) +------------------ + +0.3.1 (2013-12-26) +------------------ +* also check if a target exists when searching available plugins +* enables aerodynamics plugin in default configuration +* limit controlPeriod to 100Hz +* a few fixes for RTT integration in hector_quadrotor. Added urdf macro for rtt_gazebo_plugin macro. +* deprecated quadrotor_simple_controller.gazebo.xacro +* fixed node type for static_transform_publisher in spawn_quadrotor.launch +* changed frame_id for gazebo fixed frame to /world and added a static_transform_publisher for world->nav +* increased drift for the barometric pressure sensor +* added some command input ports to quadrotor_controller.gazebo.xacro +* Contributors: Johannes Meyer + +0.3.0 (2013-09-11) +------------------ +* Catkinized stack hector_quadrotor and integrated hector_quadrotor_demo package from former hector_quadrotor_apps stack +* increased drift for the barometric pressure sensor +* added some command input ports to quadrotor_controller.gazebo.xacro +* added launch file for two quadrotors diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/CMakeLists.txt new file mode 100644 index 0000000..92255ca --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/CMakeLists.txt @@ -0,0 +1,74 @@ +cmake_minimum_required(VERSION 2.8.3) +project(hector_quadrotor_gazebo) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package() + + +########### +## Build ## +########### + +add_subdirectory(urdf) + + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +# install(TARGETS @{name} @{name}_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) +install(DIRECTORY urdf DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/distributed_gazebo/hector_10.launch b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/distributed_gazebo/hector_10.launch new file mode 100644 index 0000000..c5ab427 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/distributed_gazebo/hector_10.launch @@ -0,0 +1,126 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/distributed_gazebo/hector_2.launch b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/distributed_gazebo/hector_2.launch new file mode 100644 index 0000000..b8642bf --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/distributed_gazebo/hector_2.launch @@ -0,0 +1,38 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/distributed_gazebo/hector_30.launch b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/distributed_gazebo/hector_30.launch new file mode 100644 index 0000000..45cde24 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/distributed_gazebo/hector_30.launch @@ -0,0 +1,346 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/distributed_gazebo/hector_4.launch b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/distributed_gazebo/hector_4.launch new file mode 100644 index 0000000..ed109c2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/distributed_gazebo/hector_4.launch @@ -0,0 +1,60 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/hector_add_1_test.launch b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/hector_add_1_test.launch new file mode 100644 index 0000000..4da92ff --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/hector_add_1_test.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/spawn_quadrotor.launch b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/spawn_quadrotor.launch new file mode 100644 index 0000000..6b6eb47 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/spawn_quadrotor.launch @@ -0,0 +1,74 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/spawn_quadrotor_shadow.launch b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/spawn_quadrotor_shadow.launch new file mode 100644 index 0000000..4b2cd19 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/launch/spawn_quadrotor_shadow.launch @@ -0,0 +1,74 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/package.xml new file mode 100644 index 0000000..eb570c0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/package.xml @@ -0,0 +1,44 @@ + + hector_quadrotor_gazebo + 0.3.5 + hector_quadrotor_gazebo provides a quadrotor model for the gazebo simulator. + It can be commanded using geometry_msgs/Twist messages. + Johannes Meyer + + BSD + + http://ros.org/wiki/hector_quadrotor_gazebo + https://github.com/tu-darmstadt-ros-pkg/hector_quadrotor/issues + + Johannes Meyer + Stefan Kohlbrecher + + + catkin + + + gazebo_plugins + hector_gazebo_plugins + hector_sensors_gazebo + hector_quadrotor_gazebo_plugins + hector_quadrotor_controller_gazebo + message_to_tf + robot_state_publisher + + + gazebo_plugins + hector_gazebo_plugins + hector_sensors_gazebo + hector_quadrotor_description + hector_quadrotor_model + hector_quadrotor_gazebo_plugins + hector_quadrotor_controller_gazebo + hector_quadrotor_pose_estimation + hector_quadrotor_teleop + hector_uav_msgs + message_to_tf + robot_state_publisher + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/CMakeLists.txt new file mode 100644 index 0000000..5cdebd7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/CMakeLists.txt @@ -0,0 +1,49 @@ +# This CMakeLists.txt configures the plugins used for the quadrotor model. +set(MODEL_PLUGINS) + +# configuration +option(USE_EXTERNAL_CONTROLLER "Do not run the hector_quadrotor_controller_gazebo plugin." OFF) +option(USE_PROPULSION_PLUGIN "Use a model of the quadrotor propulsion system" ON) +option(USE_AERODYNAMICS_PLUGIN "Use a model of the quadrotor aerodynamics" ON) + +# sensor plugins +list(APPEND MODEL_PLUGINS quadrotor_sensors) + +# controller plugin +if(NOT USE_EXTERNAL_CONTROLLER) + list(APPEND MODEL_PLUGINS quadrotor_controller) +endif() + +# propulsion plugin +#if(USE_PROPULSION_PLUGIN) +# find_library(hector_gazebo_quadrotor_propulsion_LIBRARY hector_gazebo_quadrotor_propulsion) + +# if(NOT TARGET hector_gazebo_quadrotor_propulsion AND NOT hector_gazebo_quadrotor_propulsion_LIBRARY) +# message(SEND_ERROR "Cannot use the propulsion model as the required Gazebo plugin 'hector_gazebo_quadrotor_propulsion' has not been found.") +# set(USE_PROPULSION_PLUGIN OFF) +# endif() +#endif() +if(USE_PROPULSION_PLUGIN) + list(APPEND MODEL_PLUGINS quadrotor_propulsion) +endif() + +# aerodynamics plugin +#if(USE_AERODYNAMICS_PLUGIN) +# find_library(hector_gazebo_quadrotor_aerodynamics_LIBRARY hector_gazebo_quadrotor_aerodynamics) + +# if(NOT TARGET hector_gazebo_quadrotor_aerodynamics AND NOT hector_gazebo_quadrotor_aerodynamics_LIBRARY) +# message(SEND_ERROR "Cannot use the aerodynamics model as the required Gazebo plugin 'hector_gazebo_quadrotor_aerodynamics' has not been found.") +# set(USE_AERODYNAMICS_PLUGIN OFF) +# endif() +#endif() +if(USE_AERODYNAMICS_PLUGIN) + list(APPEND MODEL_PLUGINS quadrotor_aerodynamics) +endif() + +# write urdf +set(MODEL_PLUGINS_URDF) +foreach(PLUGIN ${MODEL_PLUGINS}) + set(MODEL_PLUGINS_URDF "${MODEL_PLUGINS_URDF} \n") +endforeach() +configure_file(quadrotor_plugins.gazebo.xacro.in ${PROJECT_SOURCE_DIR}/urdf/quadrotor_plugins.gazebo.xacro @ONLY) +set_directory_properties(PROPERTIES ADDITIONAL_MAKE_CLEAN_FILES ${PROJECT_SOURCE_DIR}/urdf/quadrotor_plugins.gazebo.xacro) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_aerodynamics.gazebo.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_aerodynamics.gazebo.xacro new file mode 100644 index 0000000..29c3587 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_aerodynamics.gazebo.xacro @@ -0,0 +1,18 @@ + + + + + + + + + true + 0.0 + base_link + $(arg base_link_frame) + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_controller.gazebo.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_controller.gazebo.xacro new file mode 100644 index 0000000..4330c95 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_controller.gazebo.xacro @@ -0,0 +1,11 @@ + + + + + + 0.01 + hector_quadrotor_controller_gazebo/QuadrotorHardwareSim + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_plugins.gazebo.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_plugins.gazebo.xacro new file mode 100644 index 0000000..c5445c7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_plugins.gazebo.xacro @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_plugins.gazebo.xacro.in b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_plugins.gazebo.xacro.in new file mode 100644 index 0000000..b17d7d6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_plugins.gazebo.xacro.in @@ -0,0 +1,16 @@ + + + + + + + + + + + + + +@MODEL_PLUGINS_URDF@ + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_propulsion.gazebo.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_propulsion.gazebo.xacro new file mode 100644 index 0000000..b4c08fe --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_propulsion.gazebo.xacro @@ -0,0 +1,22 @@ + + + + + + + + + true + 0.0 + base_link + $(arg base_link_frame) + 100.0 + + 0.01 + 100.0 + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_sensors.gazebo.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_sensors.gazebo.xacro new file mode 100644 index 0000000..149a4c2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/urdf/quadrotor_sensors.gazebo.xacro @@ -0,0 +1,67 @@ + + + + + + + + + + + 100.0 + base_link + ground_truth/state + 0.0 + $(arg world_frame) + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/empty.world b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/empty.world new file mode 100644 index 0000000..e31fe38 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/empty.world @@ -0,0 +1,47 @@ + + + + + + model://sun + + + + + + + 0.68 0.68 0.68 1.0 + + + + 0 + + + + + + + + 0 + 0.001 + 0 + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/empty_origin.world b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/empty_origin.world new file mode 100644 index 0000000..e24271c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/empty_origin.world @@ -0,0 +1,35 @@ + + + + + + model://sun + + + + + model://ground_plane + + + + 50.0 + 0.02 + 1.0 + + + quick + 20 + 0 + 1.300000 + 1 + + + 0.00 + 0.2 + 10000.000000 + 0.01000 + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport.world b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport.world new file mode 100644 index 0000000..77c5639 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport.world @@ -0,0 +1,309 @@ + + + + + + model://sun + + + + model://kunming_airport + 0 0 0 0 0 0 + + + + + + + + + + 0.68 0.68 0.68 1.0 + + + + 0 + + + + + + + + + + + bebop_0 + bebop_1 + bebop_2 + bebop_3 + bebop_4 + + + bebop_5 + bebop_6 + bebop_7 + bebop_8 + bebop_9 + bebop_10 + + + bebop_11 + bebop_12 + bebop_13 + bebop_14 + + + + + + + + + + + 0 + 0.001 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport_distribution_10hector.world b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport_distribution_10hector.world new file mode 100644 index 0000000..b551c23 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport_distribution_10hector.world @@ -0,0 +1,55 @@ + + + + + + model://sun + + + + model://kunming_airport + 0 0 0 0 0 0 + + + + 0.68 0.68 0.68 1.0 + + + + 0 + + + + + + + + bebop_0 + bebop_1 + bebop_2 + bebop_3 + bebop_4 + + + bebop_5 + bebop_6 + bebop_7 + bebop_8 + bebop_9 + + + + + 0 + 0.001 + 0 + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport_distribution_2hector.world b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport_distribution_2hector.world new file mode 100644 index 0000000..400e8f4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport_distribution_2hector.world @@ -0,0 +1,47 @@ + + + + + + model://sun + + + + model://kunming_airport + 0 0 0 0 0 0 + + + + 0.68 0.68 0.68 1.0 + + + + 0 + + + + + + + + bebop_0 + + + bebop_1 + + + + + 0 + 0.001 + 0 + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport_distribution_30hector.world b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport_distribution_30hector.world new file mode 100644 index 0000000..15d2406 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport_distribution_30hector.world @@ -0,0 +1,75 @@ + + + + + + model://sun + + + + model://kunming_airport + 0 0 0 0 0 0 + + + + 0.68 0.68 0.68 1.0 + + + + 0 + + + + + + + + bebop_0 + bebop_1 + bebop_2 + bebop_3 + bebop_4 + bebop_5 + bebop_6 + bebop_7 + bebop_8 + bebop_9 + bebop_10 + bebop_11 + bebop_12 + bebop_13 + bebop_14 + + + bebop_15 + bebop_16 + bebop_17 + bebop_18 + bebop_19 + bebop_20 + bebop_21 + bebop_22 + bebop_23 + bebop_24 + bebop_25 + bebop_26 + bebop_27 + bebop_28 + bebop_29 + + + + + 0 + 0.001 + 0 + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport_distribution_4hector.world b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport_distribution_4hector.world new file mode 100644 index 0000000..74279ef --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo/worlds/kunming_airport_distribution_4hector.world @@ -0,0 +1,49 @@ + + + + + + model://sun + + + + model://kunming_airport + 0 0 0 0 0 0 + + + + 0.68 0.68 0.68 1.0 + + + + 0 + + + + + + + + bebop_0 + bebop_1 + + + bebop_2 + bebop_3 + + + + + 0 + 0.001 + 0 + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/CHANGELOG.rst b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/CHANGELOG.rst new file mode 100644 index 0000000..4976229 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/CHANGELOG.rst @@ -0,0 +1,50 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package hector_quadrotor_gazebo_plugins +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.5 (2015-03-28) +------------------ + +0.3.4 (2015-02-22) +------------------ +* added dynamic_reconfigure server to gazebo_ros_baro plugin + See https://github.com/tu-darmstadt-ros-pkg/hector_gazebo/commit/e1698e1c7bfa5fce6a724ab0a922a88bd49c9733 for + the equivalent commit in hector_gazebo_plugins. +* publish propulsion and aerodynamic wrench as WrenchStamped + This is primarily for debugging purposes. + The default topic for the propulsion plugin has been changed to propulsion/wrench. +* disabled detection of available plugins in cmake + The aerodynamics and propulsion plugins are built unconditinally now in hector_quadrotor_gazebo_plugins and the detection is obsolete. + Additionally we used platform-specific library prefixes and suffixes in find_libary() which caused errors on different platforms. +* Contributors: Johannes Meyer + +0.3.3 (2014-09-01) +------------------ +* fixed some compiler warnings and missing return values +* added separate update timer for MotorStatus output in propulsion plugin +* Contributors: Johannes Meyer + +0.3.2 (2014-03-30) +------------------ + +0.3.1 (2013-12-26) +------------------ +* disabled separate queue thread for the aerodynamics plugin +* fixed configuration namespace and plugin cleanup +* aerodynamics plugin should apply forces and torques in world frame +* accept hector_uav_msgs/MotorCommand messages directly for the propulsion model/plugin +* deleted deprecated export section from package.xml +* abort with a fatal error if ROS is not yet initialized + minor code cleanup +* fixed commanded linear z velocity upper bound for auto shutdown in simple controller plugin +* improved auto shutdown to prevent shutdowns while airborne +* added motor engage/shutdown, either automatically (default) or using ROS services /engage and /shutdown + (std_srvs/Empty) +* using ROS parameters to configure state topics +* use controller_manager in gazebo_ros_control instead of running standalone pose_controller +* Contributors: Johannes Meyer + +0.3.0 (2013-09-11) +------------------ +* Catkinized stack hector_quadrotor and integrated hector_quadrotor_demo package from former hector_quadrotor_apps stack +* added wrench publisher to the quadrotor_simple_controller plugin +* created new package hector_quadrotor_model and moved all gazebo plugins to hector_quadrotor_gazebo_plugins diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/CMakeLists.txt new file mode 100644 index 0000000..5d5ce70 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/CMakeLists.txt @@ -0,0 +1,122 @@ +cmake_minimum_required(VERSION 2.8.3) +project(hector_quadrotor_gazebo_plugins) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS roscpp hector_gazebo_plugins hector_quadrotor_model geometry_msgs hector_uav_msgs dynamic_reconfigure) +include_directories(include ${catkin_INCLUDE_DIRS}) + +# Depend on system install of Gazebo +find_package(gazebo REQUIRED) +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}") +link_directories(${GAZEBO_LIBRARY_DIRS}) +include_directories(${GAZEBO_INCLUDE_DIRS}) + +## Find hector_quadrotor_model optional libraries +if(TARGET hector_quadrotor_propulsion) + set(hector_quadrotor_propulsion_LIBRARY hector_quadrotor_propulsion) +else() + find_library(hector_quadrotor_propulsion_LIBRARY hector_quadrotor_propulsion) +endif() +if(TARGET hector_quadrotor_propulsion) + set(hector_quadrotor_aerodynamics_LIBRARY hector_quadrotor_aerodynamics) +else() + find_library(hector_quadrotor_aerodynamics_LIBRARY hector_quadrotor_aerodynamics) +endif() + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS thread) +# include_directories(${Boost_INCLUDE_DIRS}) + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + INCLUDE_DIRS include + LIBRARIES + CATKIN_DEPENDS roscpp hector_gazebo_plugins hector_quadrotor_model geometry_msgs hector_uav_msgs dynamic_reconfigure + DEPENDS gazebo +) + +########### +## Build ## +########### + +add_library(hector_gazebo_ros_baro src/gazebo_ros_baro.cpp) +target_link_libraries(hector_gazebo_ros_baro ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES}) +add_dependencies(hector_gazebo_ros_baro hector_uav_msgs_generate_messages_cpp) + +add_library(hector_gazebo_quadrotor_simple_controller src/gazebo_quadrotor_simple_controller.cpp) +target_link_libraries(hector_gazebo_quadrotor_simple_controller ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES}) + +if(hector_quadrotor_propulsion_LIBRARY) + add_library(hector_gazebo_quadrotor_propulsion src/gazebo_quadrotor_propulsion.cpp) + target_link_libraries(hector_gazebo_quadrotor_propulsion ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES} ${hector_quadrotor_propulsion_LIBRARY}) + add_dependencies(hector_gazebo_quadrotor_propulsion hector_uav_msgs_generate_messages_cpp) +else() + message(WARNING "Quadrotor propulsion model is not available. Skipping target hector_gazebo_quadrotor_propulsion...") +endif() + +if(hector_quadrotor_aerodynamics_LIBRARY) + add_library(hector_gazebo_quadrotor_aerodynamics src/gazebo_quadrotor_aerodynamics.cpp) + target_link_libraries(hector_gazebo_quadrotor_aerodynamics ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES} ${hector_quadrotor_aerodynamics_LIBRARY}) +else() + message(WARNING "Quadrotor aerodynamics model is not available. Skipping target hector_gazebo_quadrotor_aerodynamics...") +endif() + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +install(TARGETS hector_gazebo_ros_baro hector_gazebo_quadrotor_simple_controller + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +if(TARGET hector_gazebo_quadrotor_propulsion) + install(TARGETS hector_gazebo_quadrotor_propulsion LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) +endif() + +if(TARGET hector_gazebo_quadrotor_aerodynamics) + install(TARGETS hector_gazebo_quadrotor_aerodynamics LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) +endif() + +## Mark cpp header files for installation +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE +) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/include/hector_quadrotor_gazebo_plugins/gazebo_quadrotor_aerodynamics.h b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/include/hector_quadrotor_gazebo_plugins/gazebo_quadrotor_aerodynamics.h new file mode 100644 index 0000000..bbc7a04 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/include/hector_quadrotor_gazebo_plugins/gazebo_quadrotor_aerodynamics.h @@ -0,0 +1,90 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#ifndef HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_AERODYNAMICS_H +#define HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_AERODYNAMICS_H + +#include +#include +#include + +#include +#include + +#include + +#include + +namespace gazebo +{ + +class GazeboQuadrotorAerodynamics : public ModelPlugin +{ +public: + GazeboQuadrotorAerodynamics(); + virtual ~GazeboQuadrotorAerodynamics(); + +protected: + virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf); + virtual void Reset(); + virtual void Update(); + +private: + /// \brief The parent World + physics::WorldPtr world; + + /// \brief The link referred to by this plugin + physics::LinkPtr link; + + hector_quadrotor_model::QuadrotorAerodynamics model_; + + ros::NodeHandle* node_handle_; + ros::CallbackQueue callback_queue_; + boost::thread callback_queue_thread_; + void QueueThread(); + + ros::Subscriber wind_subscriber_; + ros::Publisher wrench_publisher_; + + std::string body_name_; + std::string namespace_; + std::string param_namespace_; + double control_rate_; + std::string wind_topic_; + std::string wrench_topic_; + std::string frame_id_; + + common::Time last_time_; + + // Pointer to the update event connection + event::ConnectionPtr updateConnection; +}; + +} + +#endif // HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_AERODYNAMICS_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/include/hector_quadrotor_gazebo_plugins/gazebo_quadrotor_propulsion.h b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/include/hector_quadrotor_gazebo_plugins/gazebo_quadrotor_propulsion.h new file mode 100644 index 0000000..47a97ba --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/include/hector_quadrotor_gazebo_plugins/gazebo_quadrotor_propulsion.h @@ -0,0 +1,106 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#ifndef HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_PROPULSION_H +#define HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_PROPULSION_H + +#include +#include +#include + +#include +#include + +#include +#include + +#include + +namespace gazebo +{ + +class GazeboQuadrotorPropulsion : public ModelPlugin +{ +public: + GazeboQuadrotorPropulsion(); + virtual ~GazeboQuadrotorPropulsion(); + +protected: + virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf); + virtual void Reset(); + virtual void Update(); + +private: + /// \brief The parent World + physics::WorldPtr world; + + /// \brief The link referred to by this plugin + physics::LinkPtr link; + + hector_quadrotor_model::QuadrotorPropulsion model_; + + ros::NodeHandle* node_handle_; + ros::CallbackQueue callback_queue_; + boost::thread callback_queue_thread_; + void QueueThread(); + + ros::Publisher trigger_publisher_; + ros::Subscriber command_subscriber_; + ros::Subscriber pwm_subscriber_; + ros::Publisher wrench_publisher_; + ros::Publisher supply_publisher_; + ros::Publisher motor_status_publisher_; + + std::string body_name_; + std::string namespace_; + std::string param_namespace_; + std::string trigger_topic_; + std::string command_topic_; + std::string pwm_topic_; + std::string wrench_topic_; + std::string supply_topic_; + std::string status_topic_; + std::string frame_id_; + ros::Duration control_delay_; + ros::Duration control_tolerance_; + + common::Time last_time_; + common::Time last_trigger_time_; + common::Time last_motor_status_time_; + common::Time last_supply_time_; + + // Pointer to the update event connection + event::ConnectionPtr updateConnection; + + UpdateTimer controlTimer; + UpdateTimer motorStatusTimer; +}; + +} + +#endif // HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_PROPULSION_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/include/hector_quadrotor_gazebo_plugins/gazebo_quadrotor_simple_controller.h b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/include/hector_quadrotor_gazebo_plugins/gazebo_quadrotor_simple_controller.h new file mode 100644 index 0000000..c3a2596 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/include/hector_quadrotor_gazebo_plugins/gazebo_quadrotor_simple_controller.h @@ -0,0 +1,143 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#ifndef HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_SIMPLE_CONTROLLER_H +#define HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_SIMPLE_CONTROLLER_H + +#include + +#include +#include + +#include +#include +#include +#include + +#include + +namespace gazebo +{ + +class GazeboQuadrotorSimpleController : public ModelPlugin +{ +public: + GazeboQuadrotorSimpleController(); + virtual ~GazeboQuadrotorSimpleController(); + +protected: + virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf); + virtual void Update(); + virtual void Reset(); + +private: + /// \brief The parent World + physics::WorldPtr world; + + /// \brief The link referred to by this plugin + physics::LinkPtr link; + + ros::NodeHandle* node_handle_; + ros::CallbackQueue callback_queue_; + ros::Subscriber velocity_subscriber_; + ros::Subscriber imu_subscriber_; + ros::Subscriber state_subscriber_; + ros::Publisher wrench_publisher_; + + ros::ServiceServer engage_service_server_; + ros::ServiceServer shutdown_service_server_; + + // void CallbackQueueThread(); + // boost::mutex lock_; + // boost::thread callback_queue_thread_; + + geometry_msgs::Twist velocity_command_; + void VelocityCallback(const geometry_msgs::TwistConstPtr&); + void ImuCallback(const sensor_msgs::ImuConstPtr&); + void StateCallback(const nav_msgs::OdometryConstPtr&); + + bool EngageCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&); + bool ShutdownCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&); + + ros::Time state_stamp; + math::Pose pose; + math::Vector3 euler, velocity, acceleration, angular_velocity; + + std::string link_name_; + std::string namespace_; + std::string velocity_topic_; + std::string imu_topic_; + std::string state_topic_; + std::string wrench_topic_; + double max_force_; + + bool running_; + bool auto_engage_; + + class PIDController { + public: + PIDController(); + virtual ~PIDController(); + virtual void Load(sdf::ElementPtr _sdf, const std::string& prefix = ""); + + double gain_p; + double gain_i; + double gain_d; + double time_constant; + double limit; + + double input; + double dinput; + double output; + double p, i, d; + + double update(double input, double x, double dx, double dt); + void reset(); + }; + + struct Controllers { + PIDController roll; + PIDController pitch; + PIDController yaw; + PIDController velocity_x; + PIDController velocity_y; + PIDController velocity_z; + } controllers_; + + math::Vector3 inertia; + double mass; + + math::Vector3 force, torque; + + UpdateTimer controlTimer; + event::ConnectionPtr updateConnection; +}; + +} + +#endif // HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_SIMPLE_CONTROLLER_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/include/hector_quadrotor_gazebo_plugins/gazebo_ros_baro.h b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/include/hector_quadrotor_gazebo_plugins/gazebo_ros_baro.h new file mode 100644 index 0000000..3c8ab18 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/include/hector_quadrotor_gazebo_plugins/gazebo_ros_baro.h @@ -0,0 +1,90 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#ifndef HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_BARO_H +#define HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_BARO_H + +#include + +#include +#include +#include + +#include +#include + +#include + +namespace gazebo +{ + +class GazeboRosBaro : public ModelPlugin +{ +public: + GazeboRosBaro(); + virtual ~GazeboRosBaro(); + +protected: + virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf); + virtual void Reset(); + virtual void Update(); + +private: + /// \brief The parent World + physics::WorldPtr world; + + /// \brief The link referred to by this plugin + physics::LinkPtr link; + + ros::NodeHandle* node_handle_; + ros::Publisher height_publisher_; + ros::Publisher altimeter_publisher_; + + geometry_msgs::PointStamped height_; + hector_uav_msgs::Altimeter altimeter_; + + std::string namespace_; + std::string height_topic_; + std::string altimeter_topic_; + std::string link_name_; + std::string frame_id_; + + double elevation_; + double qnh_; + + SensorModel sensor_model_; + + UpdateTimer updateTimer; + event::ConnectionPtr updateConnection; + + boost::shared_ptr > dynamic_reconfigure_server_; +}; + +} // namespace gazebo + +#endif // HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_BARO_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/package.xml new file mode 100644 index 0000000..6d16192 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/package.xml @@ -0,0 +1,40 @@ + + hector_quadrotor_gazebo_plugins + 0.3.5 + hector_quadrotor_gazebo_plugins provides gazebo plugins for using quadrotors in gazebo. + The hector_gazebo_ros_baro sensor plugin simulates an altimeter based on barometric pressure. + hector_quadrotor_simple_controller is a simple controller allowing to command the quadrotor's velocity + using a geometry_msgs/Twist message for teleoperation just by means of applying forces and torques to the model. + Johannes Meyer + + BSD + + http://ros.org/wiki/hector_quadrotor_gazebo_plugins + https://github.com/tu-darmstadt-ros-pkg/hector_quadrotor/issues + + Johannes Meyer + + + catkin + + + roscpp + gazebo + hector_gazebo_plugins + hector_quadrotor_model + geometry_msgs + hector_uav_msgs + std_srvs + dynamic_reconfigure + + + roscpp + gazebo_ros + hector_gazebo_plugins + hector_quadrotor_model + geometry_msgs + hector_uav_msgs + std_srvs + dynamic_reconfigure + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/src/gazebo_quadrotor_aerodynamics.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/src/gazebo_quadrotor_aerodynamics.cpp new file mode 100644 index 0000000..69b7d75 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/src/gazebo_quadrotor_aerodynamics.cpp @@ -0,0 +1,193 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include +#include + +#include +#include + +#include + +namespace gazebo { + +using namespace common; +using namespace math; +using namespace hector_quadrotor_model; + +GazeboQuadrotorAerodynamics::GazeboQuadrotorAerodynamics() + : node_handle_(0) +{ +} + +GazeboQuadrotorAerodynamics::~GazeboQuadrotorAerodynamics() +{ + event::Events::DisconnectWorldUpdateBegin(updateConnection); + if (node_handle_) { + node_handle_->shutdown(); + if (callback_queue_thread_.joinable()) + callback_queue_thread_.join(); + delete node_handle_; + } +} + +//////////////////////////////////////////////////////////////////////////////// +// Load the controller +void GazeboQuadrotorAerodynamics::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf) +{ + world = _model->GetWorld(); + link = _model->GetLink(); + + // default parameters + namespace_.clear(); + param_namespace_ = "quadrotor_aerodynamics"; + wind_topic_ = "/wind"; + wrench_topic_ = "aerodynamics/wrench"; + frame_id_ = link->GetName(); + + // load parameters + if (_sdf->HasElement("robotNamespace")) namespace_ = _sdf->GetElement("robotNamespace")->Get(); + if (_sdf->HasElement("paramNamespace")) param_namespace_ = _sdf->GetElement("paramNamespace")->Get(); + if (_sdf->HasElement("windTopicName")) wind_topic_ = _sdf->GetElement("windTopicName")->Get(); + if (_sdf->HasElement("wrenchTopic")) wrench_topic_ = _sdf->GetElement("wrenchTopic")->Get(); + if (_sdf->HasElement("frameId")) frame_id_= _sdf->GetElement("frameId")->Get(); + + // Make sure the ROS node for Gazebo has already been initialized + if (!ros::isInitialized()) + { + ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. " + << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)"); + return; + } + + node_handle_ = new ros::NodeHandle(namespace_); + + // get model parameters + if (!model_.configure(ros::NodeHandle(*node_handle_, param_namespace_))) { + gzwarn << "[quadrotor_propulsion] Could not properly configure the aerodynamics plugin. Make sure you loaded the parameter file." << std::endl; + return; + } + + // subscribe command + if (!wind_topic_.empty()) + { + ros::SubscribeOptions ops; + ops.callback_queue = &callback_queue_; + ops.initByFullCallbackType( + wind_topic_, 1, + boost::bind(&QuadrotorAerodynamics::setWind, &model_, _1) + ); + wind_subscriber_ = node_handle_->subscribe(ops); + } + + // advertise wrench + if (!wrench_topic_.empty()) + { + ros::AdvertiseOptions ops; + ops.callback_queue = &callback_queue_; + ops.init(wrench_topic_, 10); + wrench_publisher_ = node_handle_->advertise(ops); + } + + // callback_queue_thread_ = boost::thread( boost::bind( &GazeboQuadrotorAerodynamics::QueueThread,this ) ); + + // New Mechanism for Updating every World Cycle + // Listen to the update event. This event is broadcast every + // simulation iteration. + updateConnection = event::Events::ConnectWorldUpdateBegin( + boost::bind(&GazeboQuadrotorAerodynamics::Update, this)); +} + +//////////////////////////////////////////////////////////////////////////////// +// Update the controller +void GazeboQuadrotorAerodynamics::Update() +{ + // Get simulator time + Time current_time = world->GetSimTime(); + Time dt = current_time - last_time_; + last_time_ = current_time; + if (dt <= 0.0) return; + + // Get new commands/state + callback_queue_.callAvailable(); + + // fill input vector u for drag model + geometry_msgs::Quaternion orientation; + fromQuaternion(link->GetWorldPose().rot, orientation); + model_.setOrientation(orientation); + + geometry_msgs::Twist twist; + fromVector(link->GetWorldLinearVel(), twist.linear); + fromVector(link->GetWorldAngularVel(), twist.angular); + model_.setTwist(twist); + + // update the model + model_.update(dt.Double()); + + // get wrench from model + Vector3 force, torque; + toVector(model_.getWrench().force, force); + toVector(model_.getWrench().torque, torque); + + // publish wrench + if (wrench_publisher_) { + geometry_msgs::WrenchStamped wrench_msg; + wrench_msg.header.stamp = ros::Time(current_time.sec, current_time.nsec); + wrench_msg.header.frame_id = frame_id_; + wrench_msg.wrench = model_.getWrench(); + wrench_publisher_.publish(wrench_msg); + } + + // set force and torque in gazebo + link->AddRelativeForce(force); + link->AddRelativeTorque(torque - link->GetInertial()->GetCoG().Cross(force)); +} + +//////////////////////////////////////////////////////////////////////////////// +// Reset the controller +void GazeboQuadrotorAerodynamics::Reset() +{ + model_.reset(); +} + +//////////////////////////////////////////////////////////////////////////////// +// custom callback queue thread +void GazeboQuadrotorAerodynamics::QueueThread() +{ + static const double timeout = 0.01; + + while (node_handle_->ok()) + { + callback_queue_.callAvailable(ros::WallDuration(timeout)); + } +} + +// Register this plugin with the simulator +GZ_REGISTER_MODEL_PLUGIN(GazeboQuadrotorAerodynamics) + +} // namespace gazebo diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/src/gazebo_quadrotor_propulsion.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/src/gazebo_quadrotor_propulsion.cpp new file mode 100644 index 0000000..3492ce3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/src/gazebo_quadrotor_propulsion.cpp @@ -0,0 +1,284 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include +#include + +#include +#include + +#include +#include + +namespace gazebo { + +using namespace common; +using namespace math; +using namespace hector_quadrotor_model; + +GazeboQuadrotorPropulsion::GazeboQuadrotorPropulsion() + : node_handle_(0) +{ +} + +GazeboQuadrotorPropulsion::~GazeboQuadrotorPropulsion() +{ + event::Events::DisconnectWorldUpdateBegin(updateConnection); + if (node_handle_) { + node_handle_->shutdown(); + if (callback_queue_thread_.joinable()) + callback_queue_thread_.join(); + delete node_handle_; + } +} + +//////////////////////////////////////////////////////////////////////////////// +// Load the controller +void GazeboQuadrotorPropulsion::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf) +{ + world = _model->GetWorld(); + link = _model->GetLink(); + + // default parameters + namespace_.clear(); + param_namespace_ = "quadrotor_propulsion"; + trigger_topic_ = "quadro/trigger"; + command_topic_ = "command/motor"; + pwm_topic_ = "motor_pwm"; + wrench_topic_ = "propulsion/wrench"; + supply_topic_ = "supply"; + status_topic_ = "motor_status"; + control_tolerance_ = ros::Duration(); + control_delay_ = ros::Duration(); + frame_id_ = link->GetName(); + + // load parameters + if (_sdf->HasElement("robotNamespace")) namespace_ = _sdf->GetElement("robotNamespace")->Get(); + if (_sdf->HasElement("paramNamespace")) param_namespace_ = _sdf->GetElement("paramNamespace")->Get(); + if (_sdf->HasElement("triggerTopic")) trigger_topic_ = _sdf->GetElement("triggerTopic")->Get(); + if (_sdf->HasElement("topicName")) command_topic_ = _sdf->GetElement("topicName")->Get(); + if (_sdf->HasElement("pwmTopicName")) pwm_topic_ = _sdf->GetElement("pwmTopicName")->Get(); + if (_sdf->HasElement("wrenchTopic")) wrench_topic_ = _sdf->GetElement("wrenchTopic")->Get(); + if (_sdf->HasElement("supplyTopic")) supply_topic_ = _sdf->GetElement("supplyTopic")->Get(); + if (_sdf->HasElement("statusTopic")) status_topic_ = _sdf->GetElement("statusTopic")->Get(); + if (_sdf->HasElement("frameId")) frame_id_= _sdf->GetElement("frameId")->Get(); + + if (_sdf->HasElement("voltageTopicName")) { + gzwarn << "[quadrotor_propulsion] Plugin parameter 'voltageTopicName' is deprecated! Plese change your config to use " + << "'topicName' for MotorCommand messages or 'pwmTopicName' for MotorPWM messages." << std::endl; + pwm_topic_ = _sdf->GetElement("voltageTopicName")->Get(); + } + + // set control timing parameters + controlTimer.Load(world, _sdf, "control"); + motorStatusTimer.Load(world, _sdf, "motorStatus"); + if (_sdf->HasElement("controlTolerance")) control_tolerance_.fromSec(_sdf->GetElement("controlTolerance")->Get()); + if (_sdf->HasElement("controlDelay")) control_delay_.fromSec(_sdf->GetElement("controlDelay")->Get()); + + // set initial supply voltage + if (_sdf->HasElement("supplyVoltage")) model_.setInitialSupplyVoltage(_sdf->GetElement("supplyVoltage")->Get()); + + // Make sure the ROS node for Gazebo has already been initialized + if (!ros::isInitialized()) + { + ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. " + << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)"); + return; + } + + node_handle_ = new ros::NodeHandle(namespace_); + + // get model parameters + if (!model_.configure(ros::NodeHandle(*node_handle_, param_namespace_))) { + gzwarn << "[quadrotor_propulsion] Could not properly configure the propulsion plugin. Make sure you loaded the parameter file." << std::endl; + return; + } + + // publish trigger + if (!trigger_topic_.empty()) + { + ros::AdvertiseOptions ops; + ops.callback_queue = &callback_queue_; + ops.init(trigger_topic_, 10); + trigger_publisher_ = node_handle_->advertise(ops); + } + + // subscribe voltage command + if (!command_topic_.empty()) + { + ros::SubscribeOptions ops; + ops.callback_queue = &callback_queue_; + ops.init(command_topic_, 1, boost::bind(&QuadrotorPropulsion::addCommandToQueue, &model_, _1)); + command_subscriber_ = node_handle_->subscribe(ops); + } + + // subscribe pwm command + if (!pwm_topic_.empty()) + { + ros::SubscribeOptions ops; + ops.callback_queue = &callback_queue_; + ops.init(pwm_topic_, 1, boost::bind(&QuadrotorPropulsion::addPWMToQueue, &model_, _1)); + pwm_subscriber_ = node_handle_->subscribe(ops); + } + + // advertise wrench + if (!wrench_topic_.empty()) + { + ros::AdvertiseOptions ops; + ops.callback_queue = &callback_queue_; + ops.init(wrench_topic_, 10); + wrench_publisher_ = node_handle_->advertise(ops); + } + + // advertise and latch supply + if (!supply_topic_.empty()) + { + ros::AdvertiseOptions ops; + ops.callback_queue = &callback_queue_; + ops.latch = true; + ops.init(supply_topic_, 10); + supply_publisher_ = node_handle_->advertise(ops); + supply_publisher_.publish(model_.getSupply()); + } + + // advertise motor_status + if (!status_topic_.empty()) + { + ros::AdvertiseOptions ops; + ops.callback_queue = &callback_queue_; + ops.init(status_topic_, 10); + motor_status_publisher_ = node_handle_->advertise(ops); + } + + // callback_queue_thread_ = boost::thread( boost::bind( &GazeboQuadrotorPropulsion::QueueThread,this ) ); + + Reset(); + + // New Mechanism for Updating every World Cycle + // Listen to the update event. This event is broadcast every + // simulation iteration. + updateConnection = event::Events::ConnectWorldUpdateBegin( + boost::bind(&GazeboQuadrotorPropulsion::Update, this)); +} + +//////////////////////////////////////////////////////////////////////////////// +// Update the controller +void GazeboQuadrotorPropulsion::Update() +{ + // Get simulator time + Time current_time = world->GetSimTime(); + Time dt = current_time - last_time_; + last_time_ = current_time; + if (dt <= 0.0) return; + + // Send trigger + bool trigger = controlTimer.getUpdatePeriod() > 0.0 ? controlTimer.update() : false; + if (trigger && trigger_publisher_) { + rosgraph_msgs::Clock clock; + clock.clock = ros::Time(current_time.sec, current_time.nsec); + trigger_publisher_.publish(clock); + + ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "Sent a trigger message at t = " << current_time.Double() << " (dt = " << (current_time - last_trigger_time_).Double() << ")"); + last_trigger_time_ = current_time; + } + + // Get new commands/state + callback_queue_.callAvailable(); + + // Process input queue + model_.processQueue(ros::Time(current_time.sec, current_time.nsec), control_tolerance_, control_delay_, (model_.getMotorStatus().on && trigger) ? ros::WallDuration(1.0) : ros::WallDuration(), &callback_queue_); + + // fill input vector u for propulsion model + geometry_msgs::Twist twist; + fromVector(link->GetRelativeLinearVel(), twist.linear); + fromVector(link->GetRelativeAngularVel(), twist.angular); + model_.setTwist(twist); + + // update the model + model_.update(dt.Double()); + + // get wrench from model + Vector3 force, torque; + toVector(model_.getWrench().force, force); + toVector(model_.getWrench().torque, torque); + + // publish wrench + if (wrench_publisher_) { + geometry_msgs::WrenchStamped wrench_msg; + wrench_msg.header.stamp = ros::Time(current_time.sec, current_time.nsec); + wrench_msg.header.frame_id = frame_id_; + wrench_msg.wrench = model_.getWrench(); + wrench_publisher_.publish(wrench_msg); + } + + // publish motor status + if (motor_status_publisher_ && motorStatusTimer.update() /* && current_time >= last_motor_status_time_ + control_period_ */) { + hector_uav_msgs::MotorStatus motor_status = model_.getMotorStatus(); + motor_status.header.stamp = ros::Time(current_time.sec, current_time.nsec); + motor_status_publisher_.publish(motor_status); + last_motor_status_time_ = current_time; + } + + // publish supply + if (supply_publisher_ && current_time >= last_supply_time_ + 1.0) { + supply_publisher_.publish(model_.getSupply()); + last_supply_time_ = current_time; + } + + // set force and torque in gazebo + link->AddRelativeForce(force); + link->AddRelativeTorque(torque - link->GetInertial()->GetCoG().Cross(force)); +} + +//////////////////////////////////////////////////////////////////////////////// +// Reset the controller +void GazeboQuadrotorPropulsion::Reset() +{ + model_.reset(); + last_time_ = Time(); + last_trigger_time_ = Time(); + last_motor_status_time_ = Time(); + last_supply_time_ = Time(); +} + +//////////////////////////////////////////////////////////////////////////////// +// custom callback queue thread +void GazeboQuadrotorPropulsion::QueueThread() +{ + static const double timeout = 0.01; + + while (node_handle_->ok()) + { + callback_queue_.callAvailable(ros::WallDuration(timeout)); + } +} + +// Register this plugin with the simulator +GZ_REGISTER_MODEL_PLUGIN(GazeboQuadrotorPropulsion) + +} // namespace gazebo diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/src/gazebo_quadrotor_simple_controller.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/src/gazebo_quadrotor_simple_controller.cpp new file mode 100644 index 0000000..7b23f46 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/src/gazebo_quadrotor_simple_controller.cpp @@ -0,0 +1,425 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include +#include +#include + +#include + +#include + +namespace gazebo { + +GazeboQuadrotorSimpleController::GazeboQuadrotorSimpleController() +{ +} + +//////////////////////////////////////////////////////////////////////////////// +// Destructor +GazeboQuadrotorSimpleController::~GazeboQuadrotorSimpleController() +{ + event::Events::DisconnectWorldUpdateBegin(updateConnection); + + node_handle_->shutdown(); + delete node_handle_; +} + +//////////////////////////////////////////////////////////////////////////////// +// Load the controller +void GazeboQuadrotorSimpleController::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf) +{ + gzwarn << "The GazeboQuadrotorSimpleController plugin is DEPRECATED in ROS hydro. Please use the twist_controller in package hector_quadrotor_controller instead." << std::endl; + + world = _model->GetWorld(); + link = _model->GetLink(); + link_name_ = link->GetName(); + + // default parameters + namespace_.clear(); + velocity_topic_ = "cmd_vel"; + imu_topic_.clear(); + state_topic_.clear(); + wrench_topic_ = "wrench_out"; + max_force_ = -1; + auto_engage_ = true; + + // load parameters from sdf + if (_sdf->HasElement("robotNamespace")) namespace_ = _sdf->GetElement("robotNamespace")->Get(); + if (_sdf->HasElement("topicName")) velocity_topic_ = _sdf->GetElement("topicName")->Get(); + if (_sdf->HasElement("imuTopic")) imu_topic_ = _sdf->GetElement("imuTopic")->Get(); + if (_sdf->HasElement("stateTopic")) state_topic_ = _sdf->GetElement("stateTopic")->Get(); + if (_sdf->HasElement("wrenchTopic")) wrench_topic_ = _sdf->GetElement("wrenchTopic")->Get(); + if (_sdf->HasElement("maxForce")) max_force_ = _sdf->GetElement("maxForce")->Get(); + if (_sdf->HasElement("autoEngage")) auto_engage_ = _sdf->GetElement("autoEngage")->Get(); + + if (_sdf->HasElement("bodyName") && _sdf->GetElement("bodyName")->GetValue()) { + link_name_ = _sdf->GetElement("bodyName")->Get(); + link = _model->GetLink(link_name_); + } + + if (!link) + { + ROS_FATAL("gazebo_ros_baro plugin error: bodyName: %s does not exist\n", link_name_.c_str()); + return; + } + + // configure controllers + controllers_.roll.Load(_sdf, "rollpitch"); + controllers_.pitch.Load(_sdf, "rollpitch"); + controllers_.yaw.Load(_sdf, "yaw"); + controllers_.velocity_x.Load(_sdf, "velocityXY"); + controllers_.velocity_y.Load(_sdf, "velocityXY"); + controllers_.velocity_z.Load(_sdf, "velocityZ"); + + // Get inertia and mass of quadrotor body + inertia = link->GetInertial()->GetPrincipalMoments(); + mass = link->GetInertial()->GetMass(); + + // Make sure the ROS node for Gazebo has already been initialized + if (!ros::isInitialized()) + { + ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. " + << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)"); + return; + } + + node_handle_ = new ros::NodeHandle(namespace_); + ros::NodeHandle param_handle(*node_handle_, "controller"); + + // subscribe command + param_handle.getParam("velocity_topic", velocity_topic_); + if (!velocity_topic_.empty()) + { + ros::SubscribeOptions ops = ros::SubscribeOptions::create( + velocity_topic_, 1, + boost::bind(&GazeboQuadrotorSimpleController::VelocityCallback, this, _1), + ros::VoidPtr(), &callback_queue_); + velocity_subscriber_ = node_handle_->subscribe(ops); + } + + // subscribe imu + param_handle.getParam("imu_topic", imu_topic_); + if (!imu_topic_.empty()) + { + ros::SubscribeOptions ops = ros::SubscribeOptions::create( + imu_topic_, 1, + boost::bind(&GazeboQuadrotorSimpleController::ImuCallback, this, _1), + ros::VoidPtr(), &callback_queue_); + imu_subscriber_ = node_handle_->subscribe(ops); + + ROS_INFO_NAMED("quadrotor_simple_controller", "Using imu information on topic %s as source of orientation and angular velocity.", imu_topic_.c_str()); + } + + // subscribe state + param_handle.getParam("state_topic", state_topic_); + if (!state_topic_.empty()) + { + ros::SubscribeOptions ops = ros::SubscribeOptions::create( + state_topic_, 1, + boost::bind(&GazeboQuadrotorSimpleController::StateCallback, this, _1), + ros::VoidPtr(), &callback_queue_); + state_subscriber_ = node_handle_->subscribe(ops); + + ROS_INFO_NAMED("quadrotor_simple_controller", "Using state information on topic %s as source of state information.", state_topic_.c_str()); + } + + // advertise wrench + param_handle.getParam("wrench_topic", wrench_topic_); + if (!wrench_topic_.empty()) + { + ros::AdvertiseOptions ops = ros::AdvertiseOptions::create( + wrench_topic_, 10, + ros::SubscriberStatusCallback(), ros::SubscriberStatusCallback(), ros::VoidConstPtr(), &callback_queue_ + ); + wrench_publisher_ = node_handle_->advertise(ops); + } + + // engage/shutdown service servers + { + ros::AdvertiseServiceOptions ops = ros::AdvertiseServiceOptions::create( + "engage", boost::bind(&GazeboQuadrotorSimpleController::EngageCallback, this, _1, _2), + ros::VoidConstPtr(), &callback_queue_ + ); + engage_service_server_ = node_handle_->advertiseService(ops); + + ops = ros::AdvertiseServiceOptions::create( + "shutdown", boost::bind(&GazeboQuadrotorSimpleController::ShutdownCallback, this, _1, _2), + ros::VoidConstPtr(), &callback_queue_ + ); + shutdown_service_server_ = node_handle_->advertiseService(ops); + } + + // callback_queue_thread_ = boost::thread( boost::bind( &GazeboQuadrotorSimpleController::CallbackQueueThread,this ) ); + + + Reset(); + + // New Mechanism for Updating every World Cycle + // Listen to the update event. This event is broadcast every + // simulation iteration. + controlTimer.Load(world, _sdf); + updateConnection = event::Events::ConnectWorldUpdateBegin( + boost::bind(&GazeboQuadrotorSimpleController::Update, this)); +} + +//////////////////////////////////////////////////////////////////////////////// +// Callbacks +void GazeboQuadrotorSimpleController::VelocityCallback(const geometry_msgs::TwistConstPtr& velocity) +{ + velocity_command_ = *velocity; +} + +void GazeboQuadrotorSimpleController::ImuCallback(const sensor_msgs::ImuConstPtr& imu) +{ + pose.rot.Set(imu->orientation.w, imu->orientation.x, imu->orientation.y, imu->orientation.z); + euler = pose.rot.GetAsEuler(); + angular_velocity = pose.rot.RotateVector(math::Vector3(imu->angular_velocity.x, imu->angular_velocity.y, imu->angular_velocity.z)); +} + +void GazeboQuadrotorSimpleController::StateCallback(const nav_msgs::OdometryConstPtr& state) +{ + math::Vector3 velocity1(velocity); + + if (imu_topic_.empty()) { + pose.pos.Set(state->pose.pose.position.x, state->pose.pose.position.y, state->pose.pose.position.z); + pose.rot.Set(state->pose.pose.orientation.w, state->pose.pose.orientation.x, state->pose.pose.orientation.y, state->pose.pose.orientation.z); + euler = pose.rot.GetAsEuler(); + angular_velocity.Set(state->twist.twist.angular.x, state->twist.twist.angular.y, state->twist.twist.angular.z); + } + + velocity.Set(state->twist.twist.linear.x, state->twist.twist.linear.y, state->twist.twist.linear.z); + + // calculate acceleration + double dt = !state_stamp.isZero() ? (state->header.stamp - state_stamp).toSec() : 0.0; + state_stamp = state->header.stamp; + if (dt > 0.0) { + acceleration = (velocity - velocity1) / dt; + } else { + acceleration.Set(); + } +} + +bool GazeboQuadrotorSimpleController::EngageCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &) +{ + ROS_INFO_NAMED("quadrotor_simple_controller", "Engaging motors!"); + running_ = true; + return true; +} + +bool GazeboQuadrotorSimpleController::ShutdownCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &) +{ + ROS_INFO_NAMED("quadrotor_simple_controller", "Shutting down motors!"); + running_ = false; + return true; +} + +//////////////////////////////////////////////////////////////////////////////// +// Update the controller +void GazeboQuadrotorSimpleController::Update() +{ + // Get new commands/state + callback_queue_.callAvailable(); + + double dt; + if (controlTimer.update(dt) && dt > 0.0) { + // Get Pose/Orientation from Gazebo (if no state subscriber is active) + if (imu_topic_.empty()) { + pose = link->GetWorldPose(); + angular_velocity = link->GetWorldAngularVel(); + euler = pose.rot.GetAsEuler(); + } + if (state_topic_.empty()) { + acceleration = (link->GetWorldLinearVel() - velocity) / dt; + velocity = link->GetWorldLinearVel(); + } + + // Auto engage/shutdown + if (auto_engage_) { + if (!running_ && velocity_command_.linear.z > 0.1) { + running_ = true; + ROS_INFO_NAMED("quadrotor_simple_controller", "Engaging motors!"); + } else if (running_ && controllers_.velocity_z.i < -1.0 && velocity_command_.linear.z < -0.1 && (velocity.z > -0.1 && velocity.z < 0.1)) { + running_ = false; + ROS_INFO_NAMED("quadrotor_simple_controller", "Shutting down motors!"); + } + } + + // static Time lastDebug; + // if ((world->GetSimTime() - lastDebug).Double() > 0.5) { + // ROS_DEBUG_STREAM_NAMED("quadrotor_simple_controller", "Velocity: gazebo = [" << link->GetWorldLinearVel() << "], state = [" << velocity << "]"); + // ROS_DEBUG_STREAM_NAMED("quadrotor_simple_controller", "Acceleration: gazebo = [" << link->GetWorldLinearAccel() << "], state = [" << acceleration << "]"); + // ROS_DEBUG_STREAM_NAMED("quadrotor_simple_controller", "Angular Velocity: gazebo = [" << link->GetWorldAngularVel() << "], state = [" << angular_velocity << "]"); + // lastDebug = world->GetSimTime(); + // } + + // Get gravity + math::Vector3 gravity_body = pose.rot.RotateVector(world->GetPhysicsEngine()->GetGravity()); + double gravity = gravity_body.GetLength(); + double load_factor = gravity * gravity / world->GetPhysicsEngine()->GetGravity().Dot(gravity_body); // Get gravity + + // Rotate vectors to coordinate frames relevant for control + math::Quaternion heading_quaternion(cos(euler.z/2),0,0,sin(euler.z/2)); + math::Vector3 velocity_xy = heading_quaternion.RotateVectorReverse(velocity); + math::Vector3 acceleration_xy = heading_quaternion.RotateVectorReverse(acceleration); + math::Vector3 angular_velocity_body = pose.rot.RotateVectorReverse(angular_velocity); + + // update controllers + force.Set(0.0, 0.0, 0.0); + torque.Set(0.0, 0.0, 0.0); + if (running_) { + double pitch_command = controllers_.velocity_x.update(velocity_command_.linear.x, velocity_xy.x, acceleration_xy.x, dt) / gravity; + double roll_command = -controllers_.velocity_y.update(velocity_command_.linear.y, velocity_xy.y, acceleration_xy.y, dt) / gravity; + torque.x = inertia.x * controllers_.roll.update(roll_command, euler.x, angular_velocity_body.x, dt); + torque.y = inertia.y * controllers_.pitch.update(pitch_command, euler.y, angular_velocity_body.y, dt); + // torque.x = inertia.x * controllers_.roll.update(-velocity_command_.linear.y/gravity, euler.x, angular_velocity_body.x, dt); + // torque.y = inertia.y * controllers_.pitch.update(velocity_command_.linear.x/gravity, euler.y, angular_velocity_body.y, dt); + torque.z = inertia.z * controllers_.yaw.update(velocity_command_.angular.z, angular_velocity.z, 0, dt); + force.z = mass * (controllers_.velocity_z.update(velocity_command_.linear.z, velocity.z, acceleration.z, dt) + load_factor * gravity); + if (max_force_ > 0.0 && force.z > max_force_) force.z = max_force_; + if (force.z < 0.0) force.z = 0.0; + + } else { + controllers_.roll.reset(); + controllers_.pitch.reset(); + controllers_.yaw.reset(); + controllers_.velocity_x.reset(); + controllers_.velocity_y.reset(); + controllers_.velocity_z.reset(); + } + + // static double lastDebugOutput = 0.0; + // if (last_time.Double() - lastDebugOutput > 0.1) { + // ROS_DEBUG_NAMED("quadrotor_simple_controller", "Velocity = [%g %g %g], Acceleration = [%g %g %g]", velocity.x, velocity.y, velocity.z, acceleration.x, acceleration.y, acceleration.z); + // ROS_DEBUG_NAMED("quadrotor_simple_controller", "Command: linear = [%g %g %g], angular = [%g %g %g], roll/pitch = [%g %g]", velocity_command_.linear.x, velocity_command_.linear.y, velocity_command_.linear.z, velocity_command_.angular.x*180/M_PI, velocity_command_.angular.y*180/M_PI, velocity_command_.angular.z*180/M_PI, roll_command*180/M_PI, pitch_command*180/M_PI); + // ROS_DEBUG_NAMED("quadrotor_simple_controller", "Mass: %g kg, Inertia: [%g %g %g], Load: %g g", mass, inertia.x, inertia.y, inertia.z, load_factor); + // ROS_DEBUG_NAMED("quadrotor_simple_controller", "Force: [%g %g %g], Torque: [%g %g %g]", force.x, force.y, force.z, torque.x, torque.y, torque.z); + // lastDebugOutput = last_time.Double(); + // } + + // Publish wrench + if (wrench_publisher_) { + geometry_msgs::Wrench wrench; + wrench.force.x = force.x; + wrench.force.y = force.y; + wrench.force.z = force.z; + wrench.torque.x = torque.x; + wrench.torque.y = torque.y; + wrench.torque.z = torque.z; + wrench_publisher_.publish(wrench); + } + } + + // set force and torque in gazebo + link->AddRelativeForce(force); + link->AddRelativeTorque(torque - link->GetInertial()->GetCoG().Cross(force)); +} + +//////////////////////////////////////////////////////////////////////////////// +// Reset the controller +void GazeboQuadrotorSimpleController::Reset() +{ + controllers_.roll.reset(); + controllers_.pitch.reset(); + controllers_.yaw.reset(); + controllers_.velocity_x.reset(); + controllers_.velocity_y.reset(); + controllers_.velocity_z.reset(); + + force.Set(); + torque.Set(); + + // reset state + pose.Reset(); + velocity.Set(); + angular_velocity.Set(); + acceleration.Set(); + euler.Set(); + state_stamp = ros::Time(); + + running_ = false; +} + +//////////////////////////////////////////////////////////////////////////////// +// PID controller implementation +GazeboQuadrotorSimpleController::PIDController::PIDController() +{ +} + +GazeboQuadrotorSimpleController::PIDController::~PIDController() +{ +} + +void GazeboQuadrotorSimpleController::PIDController::Load(sdf::ElementPtr _sdf, const std::string& prefix) +{ + gain_p = 0.0; + gain_d = 0.0; + gain_i = 0.0; + time_constant = 0.0; + limit = -1.0; + + if (!_sdf) return; + // _sdf->PrintDescription(_sdf->GetName()); + if (_sdf->HasElement(prefix + "ProportionalGain")) gain_p = _sdf->GetElement(prefix + "ProportionalGain")->Get(); + if (_sdf->HasElement(prefix + "DifferentialGain")) gain_d = _sdf->GetElement(prefix + "DifferentialGain")->Get(); + if (_sdf->HasElement(prefix + "IntegralGain")) gain_i = _sdf->GetElement(prefix + "IntegralGain")->Get(); + if (_sdf->HasElement(prefix + "TimeConstant")) time_constant = _sdf->GetElement(prefix + "TimeConstant")->Get(); + if (_sdf->HasElement(prefix + "Limit")) limit = _sdf->GetElement(prefix + "Limit")->Get(); +} + +double GazeboQuadrotorSimpleController::PIDController::update(double new_input, double x, double dx, double dt) +{ + // limit command + if (limit > 0.0 && fabs(new_input) > limit) new_input = (new_input < 0 ? -1.0 : 1.0) * limit; + + // filter command + if (dt + time_constant > 0.0) { + dinput = (new_input - input) / (dt + time_constant); + input = (dt * new_input + time_constant * input) / (dt + time_constant); + } + + // update proportional, differential and integral errors + p = input - x; + d = dinput - dx; + i = i + dt * p; + + // update control output + output = gain_p * p + gain_d * d + gain_i * i; + return output; +} + +void GazeboQuadrotorSimpleController::PIDController::reset() +{ + input = dinput = 0; + p = i = d = output = 0; +} + +// Register this plugin with the simulator +GZ_REGISTER_MODEL_PLUGIN(GazeboQuadrotorSimpleController) + +} // namespace gazebo diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/src/gazebo_ros_baro.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/src/gazebo_ros_baro.cpp new file mode 100644 index 0000000..f6ed76c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_gazebo_plugins/src/gazebo_ros_baro.cpp @@ -0,0 +1,160 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include +#include +#include + +static const double DEFAULT_ELEVATION = 0.0; +static const double DEFAULT_QNH = 1013.25; + +namespace gazebo { + +GazeboRosBaro::GazeboRosBaro() +{ +} + +//////////////////////////////////////////////////////////////////////////////// +// Destructor +GazeboRosBaro::~GazeboRosBaro() +{ + updateTimer.Disconnect(updateConnection); + + dynamic_reconfigure_server_.reset(); + + node_handle_->shutdown(); + delete node_handle_; +} + +//////////////////////////////////////////////////////////////////////////////// +// Load the controller +void GazeboRosBaro::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf) +{ + world = _model->GetWorld(); + link = _model->GetLink(); + link_name_ = link->GetName(); + + if (_sdf->HasElement("bodyName")) + { + link_name_ = _sdf->GetElement("bodyName")->Get(); + link = _model->GetLink(link_name_); + } + + if (!link) + { + ROS_FATAL("gazebo_ros_baro plugin error: bodyName: %s does not exist\n", link_name_.c_str()); + return; + } + + // default parameters + namespace_.clear(); + frame_id_ = link->GetName(); + height_topic_ = "pressure_height"; + altimeter_topic_ = "altimeter"; + elevation_ = DEFAULT_ELEVATION; + qnh_ = DEFAULT_QNH; + + // load parameters + if (_sdf->HasElement("robotNamespace")) namespace_ = _sdf->GetElement("robotNamespace")->Get(); + if (_sdf->HasElement("frameId")) frame_id_ = _sdf->GetElement("frameId")->Get(); + if (_sdf->HasElement("topicName")) height_topic_ = _sdf->GetElement("topicName")->Get(); + if (_sdf->HasElement("altimeterTopicName")) altimeter_topic_ = _sdf->GetElement("altimeterTopicName")->Get(); + if (_sdf->HasElement("elevation")) elevation_ = _sdf->GetElement("elevation")->Get(); + if (_sdf->HasElement("qnh")) qnh_ = _sdf->GetElement("qnh")->Get(); + + // load sensor model + sensor_model_.Load(_sdf); + + height_.header.frame_id = frame_id_; + + // Make sure the ROS node for Gazebo has already been initialized + if (!ros::isInitialized()) + { + ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. " + << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)"); + return; + } + + node_handle_ = new ros::NodeHandle(namespace_); + + // advertise height + if (!height_topic_.empty()) { + height_publisher_ = node_handle_->advertise(height_topic_, 10); + } + + // advertise altimeter + if (!altimeter_topic_.empty()) { + altimeter_publisher_ = node_handle_->advertise(altimeter_topic_, 10); + } + + // setup dynamic_reconfigure server + dynamic_reconfigure_server_.reset(new dynamic_reconfigure::Server(ros::NodeHandle(*node_handle_, altimeter_topic_))); + dynamic_reconfigure_server_->setCallback(boost::bind(&SensorModel::dynamicReconfigureCallback, &sensor_model_, _1, _2)); + + Reset(); + + // connect Update function + updateTimer.Load(world, _sdf); + updateConnection = updateTimer.Connect(boost::bind(&GazeboRosBaro::Update, this)); +} + +void GazeboRosBaro::Reset() +{ + updateTimer.Reset(); + sensor_model_.reset(); +} + +//////////////////////////////////////////////////////////////////////////////// +// Update the controller +void GazeboRosBaro::Update() +{ + common::Time sim_time = world->GetSimTime(); + double dt = updateTimer.getTimeSinceLastUpdate().Double(); + + math::Pose pose = link->GetWorldPose(); + double height = sensor_model_(pose.pos.z, dt); + + if (height_publisher_) { + height_.header.stamp = ros::Time(sim_time.sec, sim_time.nsec); + height_.point.z = height; + height_publisher_.publish(height_); + } + + if (altimeter_publisher_) { + altimeter_.header = height_.header; + altimeter_.altitude = height + elevation_; + altimeter_.pressure = pow((1.0 - altimeter_.altitude / 44330.0), 5.263157) * qnh_; + altimeter_.qnh = qnh_; + altimeter_publisher_.publish(altimeter_); + } +} + +// Register this plugin with the simulator +GZ_REGISTER_MODEL_PLUGIN(GazeboRosBaro) + +} // namespace gazebo diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/CHANGELOG.rst b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/CHANGELOG.rst new file mode 100644 index 0000000..a4b55c0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/CHANGELOG.rst @@ -0,0 +1,48 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package hector_quadrotor_model +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.5 (2015-03-28) +------------------ + +0.3.4 (2015-02-22) +------------------ +* make models more robust against irregular input values + Especially on collisions with walls and obstacles Gazebo can output very high + velocity values for some reason, which caused the propulsion and aerodynamic + models to output infinite values or NaN as resulting forces and torques, with + the consequence that Gazebo effectively stopped simulation and showed the quadrotor + at the origin of the world frame. + With this patch the simulation is much more stable in case of collisions or + hard landings. +* disabled quadratic term (CT2s) in propeller speed to performance factor J + Because of this term the model output a non-zero thrust even if the propeller speed was zero. + The quadratic term is due to drag and therefore covered in the aerodynamics model. +* Contributors: Johannes Meyer + +0.3.3 (2014-09-01) +------------------ +* fixed target_link_libraries() line for the quadrotor_aerodynamics library +* fixed missing cmake commands to link with boost and roscpp +* always use newest available motor command in propulsion plugin +* added cmake_modules dependency +* Contributors: Johannes Meyer, Rasit Eskicioglu + +0.3.2 (2014-03-30) +------------------ + +0.3.1 (2013-12-26) +------------------ +* fixed copy&paste error in quadrotor_aerodynamics.cpp +* output drag forces in body coordinate system and added orientation input +* fixed configuration namespace and plugin cleanup +* added boolean return value for configure() methods +* accept hector_uav_msgs/MotorCommand messages directly for the propulsion model/plugin +* copied generated C code within the cpp classes to not require Matlab for compilation +* fixed sign of aerodynamic forces +* use precompiled codegen libraries if available +* Contributors: Johannes Meyer + +0.3.0 (2013-09-11) +------------------ +* Catkinized stack hector_quadrotor and integrated hector_quadrotor_demo package from former hector_quadrotor_apps stack diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/CMakeLists.txt new file mode 100644 index 0000000..a5cab85 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/CMakeLists.txt @@ -0,0 +1,72 @@ +cmake_minimum_required(VERSION 2.8.3) +project(hector_quadrotor_model) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS geometry_msgs hector_uav_msgs roscpp cmake_modules) +include_directories(include ${catkin_INCLUDE_DIRS}) + +## System dependencies are found with CMake's conventions +find_package(Boost REQUIRED COMPONENTS thread) +include_directories(${Boost_INCLUDE_DIRS}) + +find_package(Eigen REQUIRED) +include_directories(${EIGEN_INCLUDE_DIRS}) + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + INCLUDE_DIRS include + LIBRARIES hector_quadrotor_propulsion hector_quadrotor_aerodynamics + CATKIN_DEPENDS geometry_msgs hector_uav_msgs roscpp + DEPENDS Boost +) + +########### +## Build ## +########### + +add_library(hector_quadrotor_propulsion src/quadrotor_propulsion.cpp) +add_dependencies(hector_quadrotor_propulsion hector_uav_msgs_generate_messages_cpp) +target_link_libraries(hector_quadrotor_propulsion ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +#target_link_libraries(hector_quadrotor_propulsion quadrotorPropulsion) + +add_library(hector_quadrotor_aerodynamics src/quadrotor_aerodynamics.cpp) +target_link_libraries(hector_quadrotor_aerodynamics ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +#target_link_libraries(hector_quadrotor_aerodynamics quadrotorDrag) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +install( + TARGETS hector_quadrotor_propulsion hector_quadrotor_aerodynamics + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +) + +## Mark cpp header files for installation +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE +) + +install(DIRECTORY param DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/include/hector_quadrotor_model/helpers.h b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/include/hector_quadrotor_model/helpers.h new file mode 100644 index 0000000..bc817ee --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/include/hector_quadrotor_model/helpers.h @@ -0,0 +1,177 @@ +//================================================================================================= +// Copyright (c) 2013, Johannes Meyer and contributors, Technische Universitat Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#ifndef HECTOR_QUADROTOR_MODEL_HELPERS_H +#define HECTOR_QUADROTOR_MODEL_HELPERS_H + +#include +#include + +namespace hector_quadrotor_model +{ + +template int isnan(const T& value) { + return std::isnan(value); +} + +template int isnan(const boost::array& array) { + for(typename boost::array::const_iterator it = array.begin(); it != array.end(); ++it) + if (std::isnan(*it)) return std::isnan(*it); + return false; +} + +template int isnan(const boost::iterator_range& range, const typename boost::iterator_range::value_type& min, const typename boost::iterator_range::value_type& max) { + for(IteratorT it = range.begin(); it != range.end(); ++it) + if (std::isnan(*it)) return std::isnan(*it); + return false; +} + +template int isinf(const T& value) { + return std::isinf(value); +} + +template int isinf(const boost::array& array) { + for(typename boost::array::const_iterator it = array.begin(); it != array.end(); ++it) + if (std::isinf(*it)) return std::isinf(*it); + return false; +} + +template int isinf(const boost::iterator_range& range, const typename boost::iterator_range::value_type& min, const typename boost::iterator_range::value_type& max) { + for(IteratorT it = range.begin(); it != range.end(); ++it) + if (std::isinf(*it)) return std::isinf(*it); + return false; +} + +template void limit(T& value, const T& min, const T& max) { + if (!isnan(min) && value < min) value = min; + if (!isnan(max) && value > max) value = max; +} + +template void limit(boost::array& array, const T& min, const T& max) { + for(typename boost::array::iterator it = array.begin(); it != array.end(); ++it) + limit(*it, min, max); +} + +template void limit(const boost::iterator_range& range, const typename boost::iterator_range::value_type& min, const typename boost::iterator_range::value_type& max) { + for(IteratorT it = range.begin(); it != range.end(); ++it) + limit(*it, min, max); +} + +template static inline void checknan(T& value, const std::string& text = "") { + if (isnan(value)) { +#ifndef NDEBUG + if (!text.empty()) std::cerr << text << " contains **!?* Nan values!" << std::endl; +#endif + value = T(); + return; + } + + if (isinf(value)) { +#ifndef NDEBUG + if (!text.empty()) std::cerr << text << " is +-Inf!" << std::endl; +#endif + value = T(); + return; + } +} + +template static inline void toVector(const Message& msg, Vector& vector) +{ + vector.x = msg.x; + vector.y = msg.y; + vector.z = msg.z; +} + +template static inline void fromVector(const Vector& vector, Message& msg) +{ + msg.x = vector.x; + msg.y = vector.y; + msg.z = vector.z; +} + +template static inline void toQuaternion(const Message& msg, Quaternion& vector) +{ + vector.w = msg.w; + vector.x = msg.x; + vector.y = msg.y; + vector.z = msg.z; +} + +template static inline void fromQuaternion(const Quaternion& vector, Message& msg) +{ + msg.w = vector.w; + msg.x = vector.x; + msg.y = vector.y; + msg.z = vector.z; +} + +static inline geometry_msgs::Vector3 operator+(const geometry_msgs::Vector3& a, const geometry_msgs::Vector3& b) +{ + geometry_msgs::Vector3 result; + result.x = a.x + b.x; + result.y = a.y + b.y; + result.z = a.z + b.z; + return result; +} + +static inline geometry_msgs::Wrench operator+(const geometry_msgs::Wrench& a, const geometry_msgs::Wrench& b) +{ + geometry_msgs::Wrench result; + result.force = a.force + b.force; + result.torque = a.torque + b.torque; + return result; +} + +template +class PrintVector { +public: + typedef const T* const_iterator; + PrintVector(const_iterator begin, const_iterator end, const std::string &delimiter = "[ ]") : begin_(begin), end_(end), delimiter_(delimiter) {} + const_iterator begin() const { return begin_; } + const_iterator end() const { return end_; } + std::size_t size() const { return end_ - begin_; } + + std::ostream& operator>>(std::ostream& os) const { + if (!delimiter_.empty()) os << delimiter_.substr(0, delimiter_.size() - 1); + for(const_iterator it = begin(); it != end(); ++it) { + if (it != begin()) os << " "; + os << *it; + } + if (!delimiter_.empty()) os << delimiter_.substr(1, delimiter_.size() - 1); + return os; + } + +private: + const_iterator begin_, end_; + std::string delimiter_; +}; +template std::ostream &operator<<(std::ostream& os, const PrintVector& vector) { return vector >> os; } + +} + +#endif // HECTOR_QUADROTOR_MODEL_HELPERS_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/include/hector_quadrotor_model/quadrotor_aerodynamics.h b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/include/hector_quadrotor_model/quadrotor_aerodynamics.h new file mode 100644 index 0000000..0ad8d18 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/include/hector_quadrotor_model/quadrotor_aerodynamics.h @@ -0,0 +1,77 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#ifndef HECTOR_QUADROTOR_MODEL_QUADROTOR_AERODYNAMICS_H +#define HECTOR_QUADROTOR_MODEL_QUADROTOR_AERODYNAMICS_H + +#include +#include +#include +#include + +#include + +#include + +namespace hector_quadrotor_model +{ + +class QuadrotorAerodynamics { +public: + QuadrotorAerodynamics(); + ~QuadrotorAerodynamics(); + + bool configure(const ros::NodeHandle ¶m = ros::NodeHandle("~")); + void reset(); + void update(double dt); + + void setOrientation(const geometry_msgs::Quaternion& orientation); + void setTwist(const geometry_msgs::Twist& twist); + void setBodyTwist(const geometry_msgs::Twist& twist); + void setWind(const geometry_msgs::Vector3& wind); + + const geometry_msgs::Wrench& getWrench() const { return wrench_; } + + void f(const double uin[6], double dt, double y[6]) const; + +private: + geometry_msgs::Quaternion orientation_; + geometry_msgs::Twist twist_; + geometry_msgs::Vector3 wind_; + + geometry_msgs::Wrench wrench_; + + boost::mutex mutex_; + + class DragModel; + DragModel *drag_model_; +}; + +} + +#endif // HECTOR_QUADROTOR_MODEL_QUADROTOR_AERODYNAMICS_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/include/hector_quadrotor_model/quadrotor_propulsion.h b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/include/hector_quadrotor_model/quadrotor_propulsion.h new file mode 100644 index 0000000..d103847 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/include/hector_quadrotor_model/quadrotor_propulsion.h @@ -0,0 +1,99 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#ifndef HECTOR_QUADROTOR_MODEL_QUADROTOR_PROPULSION_H +#define HECTOR_QUADROTOR_MODEL_QUADROTOR_PROPULSION_H + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include +#include + +namespace hector_quadrotor_model +{ + +class QuadrotorPropulsion +{ +public: + QuadrotorPropulsion(); + ~QuadrotorPropulsion(); + + bool configure(const ros::NodeHandle ¶m = ros::NodeHandle("~")); + void reset(); + void update(double dt); + + void engage(); + void shutdown(); + + void setTwist(const geometry_msgs::Twist& twist); + void setVoltage(const hector_uav_msgs::MotorPWM& command); + + const geometry_msgs::Wrench& getWrench() const { return wrench_; } + const hector_uav_msgs::Supply& getSupply() const { return supply_; } + const hector_uav_msgs::MotorStatus& getMotorStatus() const { return motor_status_; } + + void addCommandToQueue(const hector_uav_msgs::MotorCommandConstPtr& command); + void addPWMToQueue(const hector_uav_msgs::MotorPWMConstPtr& pwm); + bool processQueue(const ros::Time& timestamp, const ros::Duration& tolerance = ros::Duration(), const ros::Duration& delay = ros::Duration(), const ros::WallDuration &wait = ros::WallDuration(), ros::CallbackQueue *callback_queue = 0); + + void f(const double xin[4], const double uin[10], double dt, double y[14], double xpred[4]) const; + + void setInitialSupplyVoltage(double voltage) { initial_voltage_ = voltage; } + +private: + geometry_msgs::Wrench wrench_; + hector_uav_msgs::Supply supply_; + hector_uav_msgs::MotorStatus motor_status_; + ros::Time last_command_time_; + + double initial_voltage_; + + std::queue command_queue_; + boost::mutex command_queue_mutex_; + boost::condition command_condition_; + + boost::mutex mutex_; + + class PropulsionModel; + PropulsionModel *propulsion_model_; +}; + +} + +#endif // HECTOR_QUADROTOR_MODEL_QUADROTOR_PROPULSION_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/CMakeLists.txt new file mode 100644 index 0000000..b2a0b47 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/CMakeLists.txt @@ -0,0 +1,60 @@ +find_program(MATLAB NAMES matlab) + +if(MATLAB) + message(STATUS "Using Matlab at ${MATLAB}") + file(GLOB MFILES "*.m") + + include_directories(codegen/lib) + + add_custom_command( + OUTPUT codegen/lib/quadrotorPropulsion/quadrotorPropulsion.a codegen/lib/quadrotorDrag/quadrotorDrag.a + COMMAND ${MATLAB} -nojvm -nodesktop -nosplash -r "compile_all; quit;" + DEPENDS ${MFILES} + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} + VERBATIM + ) + +# add_library(quadrotorPropulsion STATIC IMPORTED GLOBAL) +# set_target_properties(quadrotorPropulsion PROPERTIES IMPORTED_LOCATION ${CMAKE_CURRENT_SOURCE_DIR}/codegen/lib/quadrotorPropulsion/quadrotorPropulsion.a) + + # workaround for cmake <2.8.8 + add_library(quadrotorPropulsion STATIC dummy.c) + target_link_libraries(quadrotorPropulsion ${CMAKE_CURRENT_SOURCE_DIR}/codegen/lib/quadrotorPropulsion/quadrotorPropulsion.a) + +# add_library(quadrotorDrag STATIC IMPORTED GLOBAL) +# set_target_properties(quadrotorDrag PROPERTIES IMPORTED_LOCATION ${CMAKE_CURRENT_SOURCE_DIR}/codegen/lib/quadrotorDrag/quadrotorDrag.a) + + # workaround for cmake <2.8.8 + add_library(quadrotorDrag STATIC dummy.c) + target_link_libraries(quadrotorDrag ${CMAKE_CURRENT_SOURCE_DIR}/codegen/lib/quadrotorDrag/quadrotorDrag.a) + +else() + if(EXISTS ${CMAKE_CURRENT_SOURCE_DIR}/codegen/lib/quadrotorPropulsion/quadrotorPropulsion.a) + message(STATUS "Found precompiled hector_quadrotor propulsion model.") + +# add_library(quadrotorPropulsion STATIC IMPORTED GLOBAL) +# set_target_properties(quadrotorPropulsion PROPERTIES IMPORTED_LOCATION ${CMAKE_CURRENT_SOURCE_DIR}/codegen/lib/quadrotorPropulsion/quadrotorPropulsion.a) + + # workaround for cmake <2.8.8 + add_library(quadrotorPropulsion STATIC dummy.c) + target_link_libraries(quadrotorPropulsion ${CMAKE_CURRENT_SOURCE_DIR}/codegen/lib/quadrotorPropulsion/quadrotorPropulsion.a) + + endif() + + if(EXISTS ${CMAKE_CURRENT_SOURCE_DIR}/codegen/lib/quadrotorDrag/quadrotorDrag.a) + message(STATUS "Found precompiled hector_quadrotor drag model.") + +# add_library(quadrotorDrag STATIC IMPORTED GLOBAL) +# set_target_properties(quadrotorDrag PROPERTIES IMPORTED_LOCATION ${CMAKE_CURRENT_SOURCE_DIR}/codegen/lib/quadrotorDrag/quadrotorDrag.a) + + # workaround for cmake <2.8.8 + add_library(quadrotorDrag STATIC dummy.c) + target_link_libraries(quadrotorDrag ${CMAKE_CURRENT_SOURCE_DIR}/codegen/lib/quadrotorDrag/quadrotorDrag.a) + endif() + + if(NOT TARGET quadrotorPropulsion OR NOT TARGET quadrotorDrag) + message(WARNING "Matlab not found. Cannot build hector_quadrotor_model libraries.") + endif() +endif(MATLAB) + +set_directory_properties(PROPERTIES ADDITIONAL_MAKE_CLEAN_FILES ${CMAKE_CURRENT_SOURCE_DIR}/codegen) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/compile_all.m b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/compile_all.m new file mode 100644 index 0000000..c771b06 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/compile_all.m @@ -0,0 +1,8 @@ +rtw_config = coder.config('LIB'); +rtw_config.TargetLang = 'C'; +rtw_config.CodeReplacementLibrary = 'C89/C90 (ANSI)'; +rtw_config.CCompilerOptimization = 'On'; + +codegen -config rtw_config -v quadrotorPropulsion motorspeed -o quadrotorPropulsion +codegen -config rtw_config -v quadrotorDrag -o quadrotorDrag + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/dummy.c b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/dummy.c new file mode 100644 index 0000000..8b13789 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/dummy.c @@ -0,0 +1 @@ + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/motorspeed.m b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/motorspeed.m new file mode 100644 index 0000000..2bc3f66 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/motorspeed.m @@ -0,0 +1,71 @@ +function [M_e,I,xpred] = motorspeed(xin, uin, parameter, dt) +%#eml + +assert(isa(xin,'double')); +assert(all(size(xin) == 1)); + +assert(isa(uin,'double')); +assert(all(size(uin) == [2 1])); + +assert(isa(parameter,'struct')); +assert(isa(parameter.k_m,'double')); +assert(isa(parameter.k_t,'double')); + +assert(isa(parameter.CT2s,'double')); +assert(isa(parameter.CT1s,'double')); +assert(isa(parameter.CT0s,'double')); + +assert(isa(parameter.Psi,'double')); +assert(isa(parameter.J_M,'double')); +assert(isa(parameter.R_A,'double')); + +assert(isa(parameter.alpha_m,'double')); +assert(isa(parameter.beta_m,'double')); + +assert(isa(parameter.l_m,'double')); + +assert(isa(dt,'double')); +assert(all(size(dt) == 1)); + +eml.cstructname(parameter,'PropulsionParameters'); + +% Identification of Roxxy2827-34 motor with 10x4.5 propeller +Psi = parameter.Psi; +J_M = parameter.J_M; +R_A = parameter.R_A; +k_m = parameter.k_m; +k_t = parameter.k_t; +alpha_m = parameter.alpha_m; +beta_m = parameter.beta_m; + +% temporarily used Expressions +U = uin(1); +F_m = uin(2); +omega_m = xin(1); + +M_m = k_t*F_m + k_m*omega_m; + +temp = (U*beta_m-Psi*omega_m)./(2*R_A); +I = temp + sqrt(temp.^2 + (U*alpha_m./R_A)); +M_e = Psi*I; % electrical torque motor 1-4 + +% new version +fx = 1/J_M.*(M_e - M_m); + +% old version +% fx = (Psi/R_A*(U-Psi*omega_m) - M_m)/J_M; +% A = -(Psi^2/R_A)/J_M; +% B(1) = Psi/(J_M*R_A); +% B(2) = -1/J_M; + +% system outputs. Use euler solver to predict next time step +% predicted motor speed +xpred = xin + dt*fx; +% electric torque +%y = [M_e I]; + +% system jacobian +% A = 1 + dt*A; +% input jacobian +% B = A*B*dt; + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/parameter_QK_propulsion.m b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/parameter_QK_propulsion.m new file mode 100644 index 0000000..fbb1e87 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/parameter_QK_propulsion.m @@ -0,0 +1,56 @@ +% init-file for quadrotor +rho = 1.225; % [kg/m³] Dichte der Luft +g = 9.81; % [m/s²] Erdbeschleunigung +w_e = 7.2921151467e-5; % [rad/s] Erddrehrate +c_w = 0.9228*2/3; % [1] Widerstandsbeiwert bei translatorischer Bewegung +c_M = 0.9228*4/5; % [1] Widerstandsbeiwert bei rotatorischer Bewegung +R_p = 0.1269; % [m] Rotorradius +A_xy = 2*0.023*0.2 + .11*0.12; % [m²] Fläche in x-/y-Achse +A_z = 4*0.023*0.2 + .12^2 + 0*R_p^2*pi*4; % [m²] Fläche in z-Achse, ohne Rotoren +l_m = 0.275; % [m] Abstand Motor zu Kern +z_m = -0.03; % [m] z-Abstand Propeller-Schwerpunkt +m = 1.477; % [kg] Gesamtmasse des Quadrokopters, ohne Cam, +40g mit Cam +m_M = 0.072; % [kg] Masse Motor + Propeller +m_R = 0.044; % [kg] Masse Rohr +m_C = m - 4*m_M - 2*m_R; % [kg] Masse Kern +I_x = 2*m_M*l_m^2 + 1/12*m_C*(2*.12^2) + 1/12*m_R*(2*l_m)^2; % [kg m²] Massenträgheitsmoment um x-Achse +I_y = I_x; % [kg m²] Massenträgheitsmoment um y-Achse +I_z = 4*m_M*l_m^2 + 1/12*m_C*(2*.12^2) + 2*1/12*m_R*(2*l_m)^2; % [kg m²] Massenträgheitsmoment um z-Achse +inertia = diag([I_x I_y I_z]); % [kg m²] Massenträgheitstensor des Quadrokopters +U_max = 14.8; % [V] Maximale Eingangsspannung für Motor + +% Identification of Roxxy2827-34 motor with 10x4.5 propeller +J_M = 2.5730480633e-5; % [kgm^2] + +% identification from 27.11.2012 with old data, best data +R_A = 0.201084219222241; +Psi = 0.007242179827506; + +% new controller model: u_motor = U_in*(alpha_m/i + beta_m) +alpha_m = 0.104863758313889; +beta_m = 0.549262344777900; + +%% Thrust T = CT*rho*pi*R^4*omega^2 +% J = v_z_Motor*60/(UPM*2*R) = v_z*pi/(R_p*w_M) % Fortschrittsgrad +% CT = CT3*J^3 + CT2*J^2 + CT1*J + CT0 + +% witz normalized rotational speed of motor --> increased matrix condition +CT2s = -1.3077e-2; +CT1s = -2.5224e-4; +CT0s = 1.5393579917e-5; % identification from 15.11.2012 +% torque constant, i.e. Torque = k_t*Thrust +k_t = 0.018228626171312; +k_m = -7.011631909766668e-5; + +%% Drag coefficients + +C_wxy = 1/2*A_xy*rho*c_w; % bezogene Widerstandsgröße udot, vdot +C_wz = 1/2*A_z*rho*c_w; % bezogene Widerstandsgröße wdot +C_mxy = 1/2*A_z*rho*c_M; % bezogene Widerstandsgröße pdot, qdot +C_mz = 1/2*A_xy*rho*c_M; % bezogene Widerstandsgröße rdot + +%% Initial conditions + +F0 = m*g; +w0 = sqrt(m*g/4/CT0s); +U0 = R_A/Psi*k_t*m*g/4 + Psi*w0; diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/quadrotorDrag.m b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/quadrotorDrag.m new file mode 100644 index 0000000..64a66c4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/quadrotorDrag.m @@ -0,0 +1,50 @@ +function y = quadrotorDrag(uin, parameter, dt) +%#eml + +assert(isa(uin,'double')); +assert(all(size(uin) == [6 1])); + +assert(isa(parameter,'struct')); +assert(isa(parameter.C_wxy,'double')); +assert(isa(parameter.C_wz,'double')); + +assert(isa(parameter.C_mxy,'double')); +assert(isa(parameter.C_mz,'double')); + + +assert(isa(dt,'double')); +assert(all(size(dt) == 1)); + +eml.cstructname(parameter,'DragParameters'); + +% initialize vectors +y = zeros(6,1); + +% Input variables +u = uin(1); +v = uin(2); +w = uin(3); +p = uin(4); +q = uin(5); +r = uin(6); + +% Constants +C_wxy = parameter.C_wxy; +C_wz = parameter.C_wz; +C_mxy = parameter.C_mxy; +C_mz = parameter.C_mz; + +% temporarily used vector +absoluteVelocity = sqrt(u^2 + v^2 + w^2); +absoluteAngularVelocity = sqrt(p^2 + q^2 + r^2); + +% system outputs +% calculate drag force +y(1) = C_wxy* absoluteVelocity*u; +y(2) = C_wxy* absoluteVelocity*v; +y(3) = C_wz * absoluteVelocity*w; + +% calculate draq torque +y(4) = C_mxy* absoluteAngularVelocity*p; +y(5) = C_mxy* absoluteAngularVelocity*q; +y(6) = C_mz * absoluteAngularVelocity*r; diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/quadrotorPropulsion.m b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/quadrotorPropulsion.m new file mode 100644 index 0000000..f90509d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/matlab/quadrotorPropulsion.m @@ -0,0 +1,98 @@ +function [y,xpred] = quadrotorPropulsion(xin, uin, parameter, dt) +%#eml + +assert(isa(xin,'double')); +assert(all(size(xin) == [4 1])); + +assert(isa(uin,'double')); +assert(all(size(uin) == [10 1])); + +assert(isa(parameter,'struct')); +assert(isa(parameter.k_m,'double')); +assert(isa(parameter.k_t,'double')); + +assert(isa(parameter.CT2s,'double')); +assert(isa(parameter.CT1s,'double')); +assert(isa(parameter.CT0s,'double')); + +assert(isa(parameter.Psi,'double')); +assert(isa(parameter.J_M,'double')); +assert(isa(parameter.R_A,'double')); + +assert(isa(parameter.alpha_m,'double')); +assert(isa(parameter.beta_m,'double')); + +assert(isa(parameter.l_m,'double')); + +assert(isa(dt,'double')); +assert(all(size(dt) == 1)); + +eml.cstructname(parameter,'PropulsionParameters'); + +% initialize vectors +xpred = xin; % motorspeed +v_1 = zeros(4,1); +y = zeros(14,1); +F_m = zeros(4,1); +U = zeros(4,1); +M_e = zeros(4,1); +I = zeros(4,1); +F = zeros(3,1); + +% Input variables +u = uin(1); +v = uin(2); +w = uin(3); +p = uin(4); +q = uin(5); +r = uin(6); +U(1) = uin(7); +U(2) = uin(8); +U(3) = uin(9); +U(4) = uin(10); + +% Constants +CT0s = parameter.CT0s; +CT1s = parameter.CT1s; +CT2s = parameter.CT2s; +k_t = parameter.k_t; +l_m = parameter.l_m; +Psi = parameter.Psi; + +v_1(1) = - w + l_m*q; +v_1(2) = - w - l_m*p; +v_1(3) = - w - l_m*q; +v_1(4) = - w + l_m*p; + +% calculate thrust for all 4 rotors +for i = 1:4 + % if the flow speed at infinity is negative + if v_1(i) < 0 + F_m(i) = CT2s*v_1(i).^2 + CT1s*v_1(i).*xin(i) + CT0s*xin(i).^2; + % if the flow speed at infinity is positive + else + F_m(i) = -CT2s*v_1(i).^2 + CT1s*v_1(i).*xin(i) + CT0s*xin(i).^2; + end + % sum up all rotor forces + F(3) = F(3) + F_m(i) ; + + [M_e(i),I(i),xpred(i)] = motorspeed(xin(i), [U(i) F_m(i)], parameter, dt); +end + +% System output, i.e. force and torque of quadrotor +y(1) = F(1); +y(2) = F(2); +y(3) = F(3); + +% torque for rotating quadrocopter around x-axis is the mechanical torque +y(4) = (F_m(4)-F_m(2))*l_m; +% torque for rotating quadrocopter around y-axis is the mechanical torque +y(5) = (F_m(1)-F_m(3))*l_m; +% torque for rotating quadrocopter around z-axis is the electrical torque +y(6) = (-M_e(1)-M_e(3)+M_e(2)+M_e(4)); + +% motor speeds (rad/s) +y(7:10) = xpred(1:4); + +% motor current (A) +y(11:14) = I(1:4); % M_e(1:4) / Psi; diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/package.xml new file mode 100644 index 0000000..e38afd3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/package.xml @@ -0,0 +1,34 @@ + + hector_quadrotor_model + 0.3.5 + hector_quadrotor_model provides libraries that model several aspects of quadrotor dynamics. + Johannes Meyer + + BSD + + http://ros.org/wiki/hector_quadrotor_model + https://github.com/tu-darmstadt-ros-pkg/hector_quadrotor/issues + + Johannes Meyer + Alexander Sendobry + + + catkin + + + geometry_msgs + hector_uav_msgs + eigen + roscpp + cmake_modules + boost + + + geometry_msgs + hector_uav_msgs + roscpp + boost + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/param/quadrotor_aerodynamics.yaml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/param/quadrotor_aerodynamics.yaml new file mode 100644 index 0000000..3c4e3cf --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/param/quadrotor_aerodynamics.yaml @@ -0,0 +1,5 @@ +quadrotor_aerodynamics: + C_wxy: 0.12 + C_wz: 0.1 + C_mxy: 0.074156208000000 + C_mz: 0.050643264000000 \ No newline at end of file diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/param/robbe_2827-34_epp1045.yaml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/param/robbe_2827-34_epp1045.yaml new file mode 100644 index 0000000..7799bcf --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/param/robbe_2827-34_epp1045.yaml @@ -0,0 +1,15 @@ +quadrotor_propulsion: + Psi: 0.007242179827506 + J_M: 2.573048063300000e-5 + R_A: 0.201084219222241 + k_t: 0.015336864714397 + k_m: -7.011631909766668e-5 + alpha_m: 0.104863758313889 + beta_m: 0.549262344777900 + + #CT2s: -1.3077e-2 + CT2s: 0.0 + CT1s: -2.5224e-4 + CT0s: 1.538190483976698e-5 + + l_m: 0.275 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/param/robbe_2827-34_epp1245.yaml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/param/robbe_2827-34_epp1245.yaml new file mode 100644 index 0000000..fd6fcc0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/param/robbe_2827-34_epp1245.yaml @@ -0,0 +1,12 @@ +quadrotor_propulsion: + Psi: 0.007242179827506 + J_M: 4.142069415e-05 + R_A: 0.201084219222241 + k_t: 0.01732804081 + + #CT2s: -2.3491553043010e-2 + CT2s: 0.0 + CT1s: -4.531245193522030e-04 + CT0s: 2.744543453e-05 + + l_m: 0.275 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/src/matlab_helpers.h b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/src/matlab_helpers.h new file mode 100644 index 0000000..bcd0faa --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/src/matlab_helpers.h @@ -0,0 +1,97 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#ifndef HECTOR_QUADROTOR_MODEL_MATLAB_HELPERS_H +#define HECTOR_QUADROTOR_MODEL_MATLAB_HELPERS_H + +#include +#include + +typedef double real_T; +typedef uint32_t int32_T; +typedef bool boolean_T; + +static const real_T rtInf = std::numeric_limits::infinity(); +static inline boolean_T rtIsInf(real_T value) +{ + return std::isinf(value); +} + +static const real_T rtNaN = std::numeric_limits::quiet_NaN(); +static inline boolean_T rtIsNaN(real_T value) +{ + return std::isnan(value); +} + +static real_T rt_powd_snf(real_T u0, real_T u1) +{ + real_T y; + real_T d0; + real_T d1; + if (rtIsNaN(u0) || rtIsNaN(u1)) { + y = rtNaN; + } else { + d0 = fabs(u0); + d1 = fabs(u1); + if (rtIsInf(u1)) { + if (d0 == 1.0) { + y = rtNaN; + } else if (d0 > 1.0) { + if (u1 > 0.0) { + y = rtInf; + } else { + y = 0.0; + } + } else if (u1 > 0.0) { + y = 0.0; + } else { + y = rtInf; + } + } else if (d1 == 0.0) { + y = 1.0; + } else if (d1 == 1.0) { + if (u1 > 0.0) { + y = u0; + } else { + y = 1.0 / u0; + } + } else if (u1 == 2.0) { + y = u0 * u0; + } else if ((u1 == 0.5) && (u0 >= 0.0)) { + y = sqrt(u0); + } else if ((u0 < 0.0) && (u1 > floor(u1))) { + y = rtNaN; + } else { + y = pow(u0, u1); + } + } + + return y; +} + +#endif // HECTOR_QUADROTOR_MODEL_MATLAB_HELPERS_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/src/quadrotor_aerodynamics.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/src/quadrotor_aerodynamics.cpp new file mode 100644 index 0000000..51a71b8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/src/quadrotor_aerodynamics.cpp @@ -0,0 +1,254 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include +#include + +#include +#include + +//extern "C" { +// #include "quadrotorDrag/quadrotorDrag.h" +// #include "quadrotorDrag/quadrotorDrag_initialize.h" +//} + +#include +#include + +#include "matlab_helpers.h" + +namespace hector_quadrotor_model { + +struct DragParameters +{ + real_T C_wxy; + real_T C_wz; + real_T C_mxy; + real_T C_mz; + + DragParameters() + : C_wxy(0.0) + , C_wz(0.0) + , C_mxy(0.0) + , C_mz(0.0) + {} +}; + +// extern void quadrotorDrag(const real_T uin[6], const DragParameters parameter, real_T dt, real_T y[6]); +struct QuadrotorAerodynamics::DragModel { + DragParameters parameters_; + boost::array u; + boost::array y; +}; + +QuadrotorAerodynamics::QuadrotorAerodynamics() +{ + // initialize drag model + // quadrotorDrag_initialize(); + drag_model_ = new DragModel; +} + +QuadrotorAerodynamics::~QuadrotorAerodynamics() +{ + delete drag_model_; +} + +/* + * quadrotorDrag.c + * + * Code generation for function 'quadrotorDrag' + * + * C source code generated on: Sun Nov 3 13:34:38 2013 + * + */ + +/* Include files */ +//#include "rt_nonfinite.h" +//#include "quadrotorDrag.h" + +/* Type Definitions */ + +/* Named Constants */ + +/* Variable Declarations */ + +/* Variable Definitions */ + +/* Function Definitions */ +void quadrotorDrag(const real_T uin[6], const DragParameters parameter, real_T + dt, real_T y[6]) +{ + int32_T i; + real_T absoluteVelocity; + real_T absoluteAngularVelocity; + + /* initialize vectors */ + for (i = 0; i < 6; i++) { + y[i] = 0.0; + } + + /* Input variables */ + /* Constants */ + /* temporarily used vector */ + absoluteVelocity = sqrt((rt_powd_snf(uin[0], 2.0) + rt_powd_snf(uin[1], 2.0)) + + rt_powd_snf(uin[2], 2.0)); + absoluteAngularVelocity = sqrt((rt_powd_snf(uin[3], 2.0) + rt_powd_snf(uin[4], + 2.0)) + rt_powd_snf(uin[5], 2.0)); + + /* system outputs */ + /* calculate drag force */ + y[0] = parameter.C_wxy * absoluteVelocity * uin[0]; + y[1] = parameter.C_wxy * absoluteVelocity * uin[1]; + y[2] = parameter.C_wz * absoluteVelocity * uin[2]; + + /* calculate draq torque */ + y[3] = parameter.C_mxy * absoluteAngularVelocity * uin[3]; + y[4] = parameter.C_mxy * absoluteAngularVelocity * uin[4]; + y[5] = parameter.C_mz * absoluteAngularVelocity * uin[5]; +} + +/* End of code generation (quadrotorDrag.c) */ + +inline void QuadrotorAerodynamics::f(const double uin[10], double dt, double y[14]) const +{ + quadrotorDrag(uin, drag_model_->parameters_, dt, y); +} + +bool QuadrotorAerodynamics::configure(const ros::NodeHandle ¶m) +{ + // get model parameters + if (!param.getParam("C_wxy", drag_model_->parameters_.C_wxy)) return false; + if (!param.getParam("C_wz", drag_model_->parameters_.C_wz)) return false; + if (!param.getParam("C_mxy", drag_model_->parameters_.C_mxy)) return false; + if (!param.getParam("C_mz", drag_model_->parameters_.C_mz)) return false; + +#ifndef NDEBUG + std::cout << "Loaded the following quadrotor drag model parameters from namespace " << param.getNamespace() << ":" << std::endl; + std::cout << "C_wxy = " << drag_model_->parameters_.C_wxy << std::endl; + std::cout << "C_wz = " << drag_model_->parameters_.C_wz << std::endl; + std::cout << "C_mxy = " << drag_model_->parameters_.C_mxy << std::endl; + std::cout << "C_mz = " << drag_model_->parameters_.C_mz << std::endl; +#endif + + reset(); + return true; +} + +void QuadrotorAerodynamics::reset() +{ + boost::mutex::scoped_lock lock(mutex_); + drag_model_->u.assign(0.0); + drag_model_->y.assign(0.0); + + twist_ = geometry_msgs::Twist(); + wind_ = geometry_msgs::Vector3(); + wrench_ = geometry_msgs::Wrench(); +} + +void QuadrotorAerodynamics::setOrientation(const geometry_msgs::Quaternion& orientation) +{ + boost::mutex::scoped_lock lock(mutex_); + orientation_ = orientation; +} + +void QuadrotorAerodynamics::setTwist(const geometry_msgs::Twist& twist) +{ + boost::mutex::scoped_lock lock(mutex_); + twist_ = twist; +} + +void QuadrotorAerodynamics::setBodyTwist(const geometry_msgs::Twist& body_twist) +{ + boost::mutex::scoped_lock lock(mutex_); + Eigen::Quaterniond orientation(orientation_.w, orientation_.x, orientation_.y, orientation_.z); + Eigen::Matrix inverse_rotation_matrix(orientation.inverse().toRotationMatrix()); + + Eigen::Vector3d body_linear(body_twist.linear.x, body_twist.linear.y, body_twist.linear.z); + Eigen::Vector3d world_linear(inverse_rotation_matrix * body_linear); + twist_.linear.x = world_linear.x(); + twist_.linear.y = world_linear.y(); + twist_.linear.z = world_linear.z(); + + Eigen::Vector3d body_angular(body_twist.angular.x, body_twist.angular.y, body_twist.angular.z); + Eigen::Vector3d world_angular(inverse_rotation_matrix * body_angular); + twist_.angular.x = world_angular.x(); + twist_.angular.y = world_angular.y(); + twist_.angular.z = world_angular.z(); +} + +void QuadrotorAerodynamics::setWind(const geometry_msgs::Vector3& wind) +{ + boost::mutex::scoped_lock lock(mutex_); + wind_ = wind; +} + +void QuadrotorAerodynamics::update(double dt) +{ + if (dt <= 0.0) return; + boost::mutex::scoped_lock lock(mutex_); + + // fill input vector u for drag model + drag_model_->u[0] = (twist_.linear.x - wind_.x); + drag_model_->u[1] = -(twist_.linear.y - wind_.y); + drag_model_->u[2] = -(twist_.linear.z - wind_.z); + drag_model_->u[3] = twist_.angular.x; + drag_model_->u[4] = -twist_.angular.y; + drag_model_->u[5] = -twist_.angular.z; + + // We limit the input velocities to +-100. Required for numeric stability in case of collisions, + // where velocities returned by Gazebo can be very high. + limit(drag_model_->u, -100.0, 100.0); + + // convert input to body coordinates + Eigen::Quaterniond orientation(orientation_.w, orientation_.x, orientation_.y, orientation_.z); + Eigen::Matrix rotation_matrix(orientation.toRotationMatrix()); + Eigen::Map linear(&(drag_model_->u[0])); + Eigen::Map angular(&(drag_model_->u[3])); + linear = rotation_matrix * linear; + angular = rotation_matrix * angular; + + ROS_DEBUG_STREAM_NAMED("quadrotor_aerodynamics", "aerodynamics.twist: " << PrintVector(drag_model_->u.begin(), drag_model_->u.begin() + 6)); + checknan(drag_model_->u, "drag model input"); + + // update drag model + f(drag_model_->u.data(), dt, drag_model_->y.data()); + + ROS_DEBUG_STREAM_NAMED("quadrotor_aerodynamics", "aerodynamics.force: " << PrintVector(drag_model_->y.begin() + 0, drag_model_->y.begin() + 3)); + ROS_DEBUG_STREAM_NAMED("quadrotor_aerodynamics", "aerodynamics.torque: " << PrintVector(drag_model_->y.begin() + 3, drag_model_->y.begin() + 6)); + checknan(drag_model_->y, "drag model output"); + + // drag_model_ gives us inverted vectors! + wrench_.force.x = -( drag_model_->y[0]); + wrench_.force.y = -(-drag_model_->y[1]); + wrench_.force.z = -(-drag_model_->y[2]); + wrench_.torque.x = -( drag_model_->y[3]); + wrench_.torque.y = -(-drag_model_->y[4]); + wrench_.torque.z = -(-drag_model_->y[5]); +} + +} // namespace hector_quadrotor_model diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/src/quadrotor_propulsion.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/src/quadrotor_propulsion.cpp new file mode 100644 index 0000000..d582d0d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_model/src/quadrotor_propulsion.cpp @@ -0,0 +1,488 @@ +//================================================================================================= +// Copyright (c) 2013, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include +#include + +#include +#include + +#include + +#include "matlab_helpers.h" + +//extern "C" { +// #include "quadrotorPropulsion/quadrotorPropulsion.h" +// #include "quadrotorPropulsion/quadrotorPropulsion_initialize.h" +//} + +namespace hector_quadrotor_model { + +struct PropulsionParameters +{ + real_T k_m; + real_T k_t; + real_T CT2s; + real_T CT1s; + real_T CT0s; + real_T Psi; + real_T J_M; + real_T R_A; + real_T alpha_m; + real_T beta_m; + real_T l_m; + + PropulsionParameters() + : k_m(0.0) + , k_t(0.0) + , CT2s(0.0) + , CT1s(0.0) + , CT0s(0.0) + , Psi(0.0) + , J_M(std::numeric_limits::infinity()) + , R_A(std::numeric_limits::infinity()) + , alpha_m(0.0) + , beta_m(0.0) + , l_m(0.0) + {} +}; + +struct QuadrotorPropulsion::PropulsionModel { + PropulsionParameters parameters_; + boost::array x; + boost::array x_pred; + boost::array u; + boost::array y; +}; + +QuadrotorPropulsion::QuadrotorPropulsion() +{ + // initialize propulsion model + // quadrotorPropulsion_initialize(); + propulsion_model_ = new PropulsionModel; +} + +QuadrotorPropulsion::~QuadrotorPropulsion() +{ + delete propulsion_model_; +} + +/* + * quadrotorPropulsion.c + * + * Code generation for function 'quadrotorPropulsion' + * + * C source code generated on: Sun Nov 3 13:34:35 2013 + * + */ + +/* Include files */ +//#include "rt_nonfinite.h" +//#include "motorspeed.h" +//#include "quadrotorPropulsion.h" +//#include "quadrotorPropulsion_rtwutil.h" + +/* Type Definitions */ + +/* Named Constants */ + +/* Variable Declarations */ + +/* Variable Definitions */ + +/* Function Declarations */ + +/* Function Definitions */ +void quadrotorPropulsion(const real_T xin[4], const real_T uin[10], const + PropulsionParameters parameter, real_T dt, real_T y[14], real_T xpred[4]) +{ + real_T v_1[4]; + int32_T i; + real_T F_m[4]; + real_T U[4]; + real_T M_e[4]; + real_T I[4]; + real_T F[3]; + real_T b_F_m; + real_T temp; + real_T d0; + + /* initialize vectors */ + for (i = 0; i < 4; i++) { + xpred[i] = xin[i]; + + /* motorspeed */ + v_1[i] = 0.0; + } + + memset(&y[0], 0, 14U * sizeof(real_T)); + for (i = 0; i < 4; i++) { + F_m[i] = 0.0; + U[i] = 0.0; + M_e[i] = 0.0; + I[i] = 0.0; + } + + for (i = 0; i < 3; i++) { + F[i] = 0.0; + } + + /* Input variables */ + U[0] = uin[6]; + U[1] = uin[7]; + U[2] = uin[8]; + U[3] = uin[9]; + + /* Constants */ + v_1[0] = -uin[2] + parameter.l_m * uin[4]; + v_1[1] = -uin[2] - parameter.l_m * uin[3]; + v_1[2] = -uin[2] - parameter.l_m * uin[4]; + v_1[3] = -uin[2] + parameter.l_m * uin[3]; + + /* calculate thrust for all 4 rotors */ + for (i = 0; i < 4; i++) { + /* if the flow speed at infinity is negative */ + if (v_1[i] < 0.0) { + b_F_m = (parameter.CT2s * rt_powd_snf(v_1[i], 2.0) + parameter.CT1s * + v_1[i] * xin[i]) + parameter.CT0s * rt_powd_snf(xin[i], 2.0); + + /* if the flow speed at infinity is positive */ + } else { + b_F_m = (-parameter.CT2s * rt_powd_snf(v_1[i], 2.0) + parameter.CT1s * + v_1[i] * xin[i]) + parameter.CT0s * rt_powd_snf(xin[i], 2.0); + } + + /* sum up all rotor forces */ + /* Identification of Roxxy2827-34 motor with 10x4.5 propeller */ + /* temporarily used Expressions */ + temp = (U[i] * parameter.beta_m - parameter.Psi * xin[i]) / (2.0 * + parameter.R_A); + temp += sqrt(rt_powd_snf(temp, 2.0) + U[i] * parameter.alpha_m / + parameter.R_A); + d0 = parameter.Psi * temp; + + /* electrical torque motor 1-4 */ + /* new version */ + /* old version */ + /* fx = (Psi/R_A*(U-Psi*omega_m) - M_m)/J_M; */ + /* A = -(Psi^2/R_A)/J_M; */ + /* B(1) = Psi/(J_M*R_A); */ + /* B(2) = -1/J_M; */ + /* system outputs. Use euler solver to predict next time step */ + /* predicted motor speed */ + /* electric torque */ + /* y = [M_e I]; */ + /* system jacobian */ + /* A = 1 + dt*A; */ + /* input jacobian */ + /* B = A*B*dt; */ + M_e[i] = d0; + I[i] = temp; + xpred[i] = xin[i] + dt * (1.0 / parameter.J_M * (d0 - (parameter.k_t * b_F_m + + parameter.k_m * xin[i]))); + F_m[i] = b_F_m; + F[2] += b_F_m; + } + + /* System output, i.e. force and torque of quadrotor */ + y[0] = 0.0; + y[1] = 0.0; + y[2] = F[2]; + + /* torque for rotating quadrocopter around x-axis is the mechanical torque */ + y[3] = (F_m[3] - F_m[1]) * parameter.l_m; + + /* torque for rotating quadrocopter around y-axis is the mechanical torque */ + y[4] = (F_m[0] - F_m[2]) * parameter.l_m; + + /* torque for rotating quadrocopter around z-axis is the electrical torque */ + y[5] = ((-M_e[0] - M_e[2]) + M_e[1]) + M_e[3]; + + /* motor speeds (rad/s) */ + for (i = 0; i < 4; i++) { + y[i + 6] = xpred[i]; + } + + /* motor current (A) */ + for (i = 0; i < 4; i++) { + y[i + 10] = I[i]; + } + + /* M_e(1:4) / Psi; */ +} + +/* End of code generation (quadrotorPropulsion.c) */ + +inline void QuadrotorPropulsion::f(const double xin[4], const double uin[10], double dt, double y[14], double xpred[4]) const +{ + quadrotorPropulsion(xin, uin, propulsion_model_->parameters_, dt, y, xpred); +} + +bool QuadrotorPropulsion::configure(const ros::NodeHandle ¶m) +{ + // get model parameters + if (!param.getParam("k_m", propulsion_model_->parameters_.k_m)) return false; + if (!param.getParam("k_t", propulsion_model_->parameters_.k_t)) return false; + if (!param.getParam("CT0s", propulsion_model_->parameters_.CT0s)) return false; + if (!param.getParam("CT1s", propulsion_model_->parameters_.CT1s)) return false; + if (!param.getParam("CT2s", propulsion_model_->parameters_.CT2s)) return false; + if (!param.getParam("J_M", propulsion_model_->parameters_.J_M)) return false; + if (!param.getParam("l_m", propulsion_model_->parameters_.l_m)) return false; + if (!param.getParam("Psi", propulsion_model_->parameters_.Psi)) return false; + if (!param.getParam("R_A", propulsion_model_->parameters_.R_A)) return false; + if (!param.getParam("alpha_m", propulsion_model_->parameters_.alpha_m)) return false; + if (!param.getParam("beta_m", propulsion_model_->parameters_.beta_m)) return false; + +#ifndef NDEBUG + std::cout << "Loaded the following quadrotor propulsion model parameters from namespace " << param.getNamespace() << ":" << std::endl; + std::cout << "k_m = " << propulsion_model_->parameters_.k_m << std::endl; + std::cout << "k_t = " << propulsion_model_->parameters_.k_t << std::endl; + std::cout << "CT2s = " << propulsion_model_->parameters_.CT2s << std::endl; + std::cout << "CT1s = " << propulsion_model_->parameters_.CT1s << std::endl; + std::cout << "CT0s = " << propulsion_model_->parameters_.CT0s << std::endl; + std::cout << "Psi = " << propulsion_model_->parameters_.Psi << std::endl; + std::cout << "J_M = " << propulsion_model_->parameters_.J_M << std::endl; + std::cout << "R_A = " << propulsion_model_->parameters_.R_A << std::endl; + std::cout << "l_m = " << propulsion_model_->parameters_.l_m << std::endl; + std::cout << "alpha_m = " << propulsion_model_->parameters_.alpha_m << std::endl; + std::cout << "beta_m = " << propulsion_model_->parameters_.beta_m << std::endl; +#endif + + initial_voltage_ = 14.8; + param.getParam("supply_voltage", initial_voltage_); + reset(); + + return true; +} + +void QuadrotorPropulsion::reset() +{ + boost::mutex::scoped_lock lock(mutex_); + + propulsion_model_->x.assign(0.0); + propulsion_model_->x_pred.assign(0.0); + propulsion_model_->u.assign(0.0); + propulsion_model_->y.assign(0.0); + + wrench_ = geometry_msgs::Wrench(); + + motor_status_ = hector_uav_msgs::MotorStatus(); + motor_status_.voltage.resize(4); + motor_status_.frequency.resize(4); + motor_status_.current.resize(4); + + supply_ = hector_uav_msgs::Supply(); + supply_.voltage.resize(1); + supply_.voltage[0] = initial_voltage_; + + last_command_time_ = ros::Time(); + + command_queue_ = std::queue(); // .clear(); +} + +void QuadrotorPropulsion::setVoltage(const hector_uav_msgs::MotorPWM& voltage) +{ + boost::mutex::scoped_lock lock(mutex_); + last_command_time_ = voltage.header.stamp; + + if (motor_status_.on && voltage.pwm.size() >= 4) { + propulsion_model_->u[6] = voltage.pwm[0] * supply_.voltage[0] / 255.0; + propulsion_model_->u[7] = voltage.pwm[1] * supply_.voltage[0] / 255.0; + propulsion_model_->u[8] = voltage.pwm[2] * supply_.voltage[0] / 255.0; + propulsion_model_->u[9] = voltage.pwm[3] * supply_.voltage[0] / 255.0; + } else { + propulsion_model_->u[6] = 0.0; + propulsion_model_->u[7] = 0.0; + propulsion_model_->u[8] = 0.0; + propulsion_model_->u[9] = 0.0; + } +} + +void QuadrotorPropulsion::setTwist(const geometry_msgs::Twist &twist) +{ + boost::mutex::scoped_lock lock(mutex_); + propulsion_model_->u[0] = twist.linear.x; + propulsion_model_->u[1] = -twist.linear.y; + propulsion_model_->u[2] = -twist.linear.z; + propulsion_model_->u[3] = twist.angular.x; + propulsion_model_->u[4] = -twist.angular.y; + propulsion_model_->u[5] = -twist.angular.z; + + // We limit the input velocities to +-100. Required for numeric stability in case of collisions, + // where velocities returned by Gazebo can be very high. + limit(boost::iterator_range::iterator>(&(propulsion_model_->u[0]), &(propulsion_model_->u[6])), -100.0, 100.0); +} + +void QuadrotorPropulsion::addCommandToQueue(const hector_uav_msgs::MotorCommandConstPtr& command) +{ + hector_uav_msgs::MotorPWMPtr pwm(new hector_uav_msgs::MotorPWM); + pwm->header = command->header; + pwm->pwm.resize(command->voltage.size()); + for(std::size_t i = 0; i < command->voltage.size(); ++i) { + int temp = round(command->voltage[i] / supply_.voltage[0] * 255.0); + if (temp < 0) + pwm->pwm[i] = 0; + else if (temp > 255) + pwm->pwm[i] = 255; + else + pwm->pwm[i] = temp; + } + addPWMToQueue(pwm); +} + +void QuadrotorPropulsion::addPWMToQueue(const hector_uav_msgs::MotorPWMConstPtr& pwm) +{ + boost::mutex::scoped_lock lock(command_queue_mutex_); + + if (!motor_status_.on) { + ROS_WARN_NAMED("quadrotor_propulsion", "Received new motor command. Enabled motors."); + engage(); + } + + ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "Received motor command valid at " << pwm->header.stamp); + command_queue_.push(pwm); + command_condition_.notify_all(); +} + +bool QuadrotorPropulsion::processQueue(const ros::Time ×tamp, const ros::Duration &tolerance, const ros::Duration &delay, const ros::WallDuration &wait, ros::CallbackQueue *callback_queue) { + boost::mutex::scoped_lock lock(command_queue_mutex_); + bool new_command = false; + + ros::Time min(timestamp), max(timestamp); + try { + min = timestamp - delay - tolerance /* - ros::Duration(dt) */; + } catch (std::runtime_error &e) {} + + try { + max = timestamp - delay + tolerance; + } catch (std::runtime_error &e) {} + + do { + + while(!command_queue_.empty()) { + hector_uav_msgs::MotorPWMConstPtr new_motor_voltage = command_queue_.front(); + ros::Time new_time = new_motor_voltage->header.stamp; + + if (new_time.isZero() || (new_time >= min && new_time <= max)) { + setVoltage(*new_motor_voltage); + command_queue_.pop(); + new_command = true; + + // new motor command is too old: + } else if (new_time < min) { + ROS_DEBUG_NAMED("quadrotor_propulsion", "Command received was %fs too old. Discarding.", (new_time - timestamp).toSec()); + command_queue_.pop(); + + // new motor command is too new: + } else { + break; + } + } + + if (command_queue_.empty() && !new_command) { + if (!motor_status_.on || wait.isZero()) break; + + ROS_DEBUG_NAMED("quadrotor_propulsion", "Waiting for command at simulation step t = %fs... last update was %fs ago", timestamp.toSec(), (timestamp - last_command_time_).toSec()); + if (!callback_queue) { + if (command_condition_.timed_wait(lock, wait.toBoost())) continue; + } else { + lock.unlock(); + callback_queue->callAvailable(wait); + lock.lock(); + if (!command_queue_.empty()) continue; + } + + ROS_ERROR_NAMED("quadrotor_propulsion", "Command timed out. Disabled motors."); + shutdown(); + } + + } while(false); + + if (new_command) { + ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "Using motor command valid at t = " << last_command_time_.toSec() << "s for simulation step at t = " << timestamp.toSec() << "s (dt = " << (timestamp - last_command_time_).toSec() << "s)"); + } + + return new_command; +} + +void QuadrotorPropulsion::update(double dt) +{ + if (dt <= 0.0) return; + + ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "propulsion.twist: " << PrintVector(propulsion_model_->u.begin(), propulsion_model_->u.begin() + 6)); + ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "propulsion.voltage: " << PrintVector(propulsion_model_->u.begin() + 6, propulsion_model_->u.begin() + 10)); + ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "propulsion.x_prior: " << PrintVector(propulsion_model_->x.begin(), propulsion_model_->x.end())); + + checknan(propulsion_model_->u, "propulsion model input"); + checknan(propulsion_model_->x, "propulsion model state"); + + // update propulsion model + f(propulsion_model_->x.data(), propulsion_model_->u.data(), dt, propulsion_model_->y.data(), propulsion_model_->x_pred.data()); + propulsion_model_->x = propulsion_model_->x_pred; + + ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "propulsion.x_post: " << PrintVector(propulsion_model_->x.begin(), propulsion_model_->x.end())); + ROS_DEBUG_STREAM_NAMED("quadrotor_propulsion", "propulsion.force: " << PrintVector(propulsion_model_->y.begin() + 0, propulsion_model_->y.begin() + 3) << " " << + "propulsion.torque: " << PrintVector(propulsion_model_->y.begin() + 3, propulsion_model_->y.begin() + 6)); + + checknan(propulsion_model_->y, "propulsion model output"); + + wrench_.force.x = propulsion_model_->y[0]; + wrench_.force.y = -propulsion_model_->y[1]; + wrench_.force.z = propulsion_model_->y[2]; + wrench_.torque.x = propulsion_model_->y[3]; + wrench_.torque.y = -propulsion_model_->y[4]; + wrench_.torque.z = -propulsion_model_->y[5]; + + motor_status_.voltage[0] = propulsion_model_->u[6]; + motor_status_.voltage[1] = propulsion_model_->u[7]; + motor_status_.voltage[2] = propulsion_model_->u[8]; + motor_status_.voltage[3] = propulsion_model_->u[9]; + + motor_status_.frequency[0] = propulsion_model_->y[6]; + motor_status_.frequency[1] = propulsion_model_->y[7]; + motor_status_.frequency[2] = propulsion_model_->y[8]; + motor_status_.frequency[3] = propulsion_model_->y[9]; + motor_status_.running = motor_status_.frequency[0] > 1.0 && motor_status_.frequency[1] > 1.0 && motor_status_.frequency[2] > 1.0 && motor_status_.frequency[3] > 1.0; + + motor_status_.current[0] = propulsion_model_->y[10]; + motor_status_.current[1] = propulsion_model_->y[11]; + motor_status_.current[2] = propulsion_model_->y[12]; + motor_status_.current[3] = propulsion_model_->y[13]; +} + +void QuadrotorPropulsion::engage() +{ + motor_status_.on = true; +} + +void QuadrotorPropulsion::shutdown() +{ + motor_status_.on = false; +} + +} // namespace hector_quadrotor_model diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/CHANGELOG.rst b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/CHANGELOG.rst new file mode 100644 index 0000000..a7acba8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/CHANGELOG.rst @@ -0,0 +1,37 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package hector_quadrotor_pose_estimation +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.5 (2015-03-28) +------------------ + +0.3.4 (2015-02-22) +------------------ +* added missing install rule for hector_quadrotor_pose_estimation_nodelets.xml + Many thanks to Bernd Kast for pointing me to this issue. +* update raw baro height as position.z component in sensor pose + See https://github.com/tu-darmstadt-ros-pkg/hector_localization/commit/bd334f0e30c42fb5833fa8ffa249dfd737d43ddc. +* updated package for the latest version of hector_pose_estimation + * Geographic reference latitude and longitude set to 49.860246N 8.687077E (Lichtwiese). + * Reenabled auto_elevation, auto_reference and auto_heading parameters for hector_pose_estimation. + hector_pose_estimation will publish the world->nav transform depending on its reference pose. +* added parameter file for hector_quadrotor_pose_estimation for a simulated quadrotor + The parameter file disables the auto_elevation, auto_reference, auto_heading modes of hector_pose_estimation and sets the corresponding values + manually with what is simulated in the gazebo sensor plugins. This simplifies the comparison of estimated poses with ground truth information. +* shutdown the height subscriber (in favor of topic alitimeter) to not have two height updates +* Contributors: Johannes Meyer + +0.3.3 (2014-09-01) +------------------ + +0.3.2 (2014-03-30) +------------------ + +0.3.1 (2013-12-26) +------------------ + +0.3.0 (2013-09-11) +------------------ +* hector_quadrotor_pose_estimation: added cmake target dependency on hector_uav_msgs_generate_messages_cpp +* hector_quadrotor: added package hector_quadrotor_pose_estimation +* Contributors: Johannes Meyer diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/CMakeLists.txt new file mode 100644 index 0000000..a11c4f6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/CMakeLists.txt @@ -0,0 +1,112 @@ +cmake_minimum_required(VERSION 2.8.3) +project(hector_quadrotor_pose_estimation) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS hector_pose_estimation hector_uav_msgs) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +####################################### +## Declare ROS messages and services ## +####################################### + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# hector_uav_msgs +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + INCLUDE_DIRS include + LIBRARIES quadrotor_pose_estimation_nodelet quadrotor_pose_estimation_node + CATKIN_DEPENDS hector_pose_estimation hector_uav_msgs + DEPENDS +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories(include) +include_directories(${catkin_INCLUDE_DIRS}) + +add_library(hector_quadrotor_pose_estimation_node + src/pose_estimation_node.cpp +) +target_link_libraries(hector_quadrotor_pose_estimation_node ${catkin_LIBRARIES}) +add_dependencies(hector_quadrotor_pose_estimation_node hector_uav_msgs_generate_messages_cpp) + +add_library(hector_quadrotor_pose_estimation_nodelet + src/pose_estimation_nodelet.cpp +) +target_link_libraries(hector_quadrotor_pose_estimation_nodelet hector_quadrotor_pose_estimation_node ${catkin_LIBRARIES}) + +add_executable(hector_quadrotor_pose_estimation + src/main.cpp +) +target_link_libraries(hector_quadrotor_pose_estimation hector_quadrotor_pose_estimation_node ${catkin_LIBRARIES}) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executables and/or libraries for installation +install(TARGETS hector_quadrotor_pose_estimation_nodelet hector_quadrotor_pose_estimation_node hector_quadrotor_pose_estimation + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +## Mark cpp header files for installation +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE +) + +## Mark other files for installation (e.g. launch and bag files, etc.) +install(FILES + hector_quadrotor_pose_estimation_nodelets.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +install(DIRECTORY params + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/hector_quadrotor_pose_estimation_nodelets.xml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/hector_quadrotor_pose_estimation_nodelets.xml new file mode 100644 index 0000000..f2b2132 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/hector_quadrotor_pose_estimation_nodelets.xml @@ -0,0 +1,8 @@ + + + + This nodelet implements a pose estimation filter which uses hector_uav_msgs/Altimeter messages as input for barometric height. + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/include/hector_quadrotor_pose_estimation/pose_estimation_node.h b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/include/hector_quadrotor_pose_estimation/pose_estimation_node.h new file mode 100644 index 0000000..b72366c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/include/hector_quadrotor_pose_estimation/pose_estimation_node.h @@ -0,0 +1,55 @@ +//================================================================================================= +// Copyright (c) 2011, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#ifndef HECTOR_QUADROTOR_POSE_ESTIMATION_NODE_H +#define HECTOR_QUADROTOR_POSE_ESTIMATION_NODE_H + +#include +#include + +namespace hector_quadrotor_pose_estimation { + +using namespace hector_pose_estimation; + +class QuadrotorPoseEstimationNode : public PoseEstimationNode { +public: + QuadrotorPoseEstimationNode(const SystemPtr& system = SystemPtr(), const StatePtr& state = StatePtr()); + virtual ~QuadrotorPoseEstimationNode(); + + virtual bool init(); + +protected: + void baroCallback(const hector_uav_msgs::AltimeterConstPtr& altimeter); + +private: + ros::Subscriber baro_subscriber_; +}; + +} // namespace hector_quadrotor_pose_estimation + +#endif // HECTOR_QUADROTOR_POSE_ESTIMATION_NODE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/package.xml new file mode 100644 index 0000000..76f40fd --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/package.xml @@ -0,0 +1,34 @@ + + + hector_quadrotor_pose_estimation + 0.3.5 + + hector_quadrotor_pose_estimation provides a hector_pose_estimation node and nodelet specialized for hector_quadrotor. + + Johannes Meyer + + BSD + + http://ros.org/wiki/hector_quadrotor_pose_estimation + + Johannes Meyer + + + catkin + + + hector_pose_estimation + hector_uav_msgs + + + hector_pose_estimation + hector_uav_msgs + nodelet + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/params/simulation.yaml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/params/simulation.yaml new file mode 100644 index 0000000..044614b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/params/simulation.yaml @@ -0,0 +1,4 @@ +reference_altitude: 0.0 +reference_heading: 0.0 +reference_latitude: 49.860246 +reference_longitude: 8.687077 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/src/main.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/src/main.cpp new file mode 100644 index 0000000..dde98d8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/src/main.cpp @@ -0,0 +1,40 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include + +int main(int argc, char **argv) { + ros::init(argc, argv, "pose_estimation"); + hector_quadrotor_pose_estimation::QuadrotorPoseEstimationNode node; + if (!node.init()) return 1; + + ros::spin(); + + node.cleanup(); + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/src/pose_estimation_node.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/src/pose_estimation_node.cpp new file mode 100644 index 0000000..b249331 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/src/pose_estimation_node.cpp @@ -0,0 +1,60 @@ +//================================================================================================= +// Copyright (c) 2011, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include +#include + +namespace hector_quadrotor_pose_estimation { + +QuadrotorPoseEstimationNode::QuadrotorPoseEstimationNode(const SystemPtr& system, const StatePtr& state) + : PoseEstimationNode(system, state) +{ + pose_estimation_->addMeasurement(new Baro("baro")); +} + +QuadrotorPoseEstimationNode::~QuadrotorPoseEstimationNode() +{ +} + +bool QuadrotorPoseEstimationNode::init() { + if (!PoseEstimationNode::init()) return false; + baro_subscriber_ = getNodeHandle().subscribe("altimeter", 10, &QuadrotorPoseEstimationNode::baroCallback, this); + height_subscriber_.shutdown(); + return true; +} + +void QuadrotorPoseEstimationNode::baroCallback(const hector_uav_msgs::AltimeterConstPtr& altimeter) { + pose_estimation_->getMeasurement("baro")->add(Baro::Update(altimeter->pressure, altimeter->qnh)); + + if (sensor_pose_publisher_) { + boost::shared_ptr baro = boost::static_pointer_cast(pose_estimation_->getMeasurement("baro")); + sensor_pose_.pose.position.z = baro->getModel()->getAltitude(Baro::Update(altimeter->pressure, altimeter->qnh)) - baro->getElevation(); + } +} + +} // namespace hector_quadrotor_pose_estimation diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/src/pose_estimation_nodelet.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/src/pose_estimation_nodelet.cpp new file mode 100644 index 0000000..928132e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_pose_estimation/src/pose_estimation_nodelet.cpp @@ -0,0 +1,58 @@ +//================================================================================================= +// Copyright (c) 2011, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#include +#include + +namespace hector_quadrotor_pose_estimation { + +class QuadrotorPoseEstimationNodelet : public QuadrotorPoseEstimationNode, public nodelet::Nodelet +{ +public: + QuadrotorPoseEstimationNodelet(const SystemPtr& system = SystemPtr()) + : QuadrotorPoseEstimationNode(system) + {} + +private: + void onInit() { + QuadrotorPoseEstimationNode::init(); + } + + void onReset() { + QuadrotorPoseEstimationNode::reset(); + } + + void onCleanup() { + QuadrotorPoseEstimationNode::cleanup(); + } +}; + +} // namespace hector_quadrotor_pose_estimation + +#include +PLUGINLIB_EXPORT_CLASS(hector_quadrotor_pose_estimation::QuadrotorPoseEstimationNodelet, nodelet::Nodelet) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/CHANGELOG.rst b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/CHANGELOG.rst new file mode 100644 index 0000000..404258e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/CHANGELOG.rst @@ -0,0 +1,29 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package hector_quadrotor_teleop +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.5 (2015-03-28) +------------------ + +0.3.4 (2015-02-22) +------------------ +* Add optional parameter to set the joystick device +* Contributors: whoenig + +0.3.3 (2014-09-01) +------------------ +* added run dependency to joy package (joystick drivers) +* Contributors: Johannes Meyer + +0.3.2 (2014-03-30) +------------------ + +0.3.1 (2013-12-26) +------------------ +* added slow button (btn 6 on Logitech Gamepad) +* Contributors: Johannes Meyer + +0.3.0 (2013-09-11) +------------------ +* Catkinized stack hector_quadrotor and integrated hector_quadrotor_demo package from former hector_quadrotor_apps stack +* decreased z_velocity_max to 2.0 m/s in logitech_gamepad.launch diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/CMakeLists.txt new file mode 100644 index 0000000..0d437a2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/CMakeLists.txt @@ -0,0 +1,89 @@ +cmake_minimum_required(VERSION 2.8.3) +project(hector_quadrotor_teleop) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS roscpp sensor_msgs geometry_msgs hector_uav_msgs) +include_directories(include ${catkin_INCLUDE_DIRS}) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + INCLUDE_DIRS + LIBRARIES + CATKIN_DEPENDS roscpp sensor_msgs geometry_msgs hector_uav_msgs + DEPENDS +) + +########### +## Build ## +########### + +## Declare a cpp library +# add_library(@{name} +# src/${PROJECT_NAME}/@name.cpp +# ) + +## Declare a cpp executable +add_executable(quadrotor_teleop src/quadrotor_teleop.cpp) +target_link_libraries(quadrotor_teleop ${catkin_LIBRARIES}) + +## Add cmake target dependencies of the executable/library +## as an example, message headers may need to be generated before nodes +add_dependencies(quadrotor_teleop ${catkin_EXPORTED_TARGETS}) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +install(TARGETS quadrotor_teleop + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +install(DIRECTORY launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/launch/logitech_gamepad.launch b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/launch/logitech_gamepad.launch new file mode 100644 index 0000000..83884da --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/launch/logitech_gamepad.launch @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/launch/xbox_controller.launch b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/launch/xbox_controller.launch new file mode 100644 index 0000000..c6e9348 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/launch/xbox_controller.launch @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/package.xml new file mode 100644 index 0000000..88dfc1c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/package.xml @@ -0,0 +1,33 @@ + + hector_quadrotor_teleop + 0.3.5 + hector_quadrotor_teleop enables quadrotor flying with a joystick by + processing joy/Joy messages and translating them to geometry_msgs/Twist. + Johannes Meyer + + BSD + + http://ros.org/wiki/hector_quadrotor_teleop + https://github.com/tu-darmstadt-ros-pkg/hector_quadrotor/issues + + Johannes Meyer + + + catkin + + + roscpp + sensor_msgs + geometry_msgs + hector_uav_msgs + + + roscpp + sensor_msgs + geometry_msgs + hector_uav_msgs + joy + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/src/quadrotor_teleop.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/src/quadrotor_teleop.cpp new file mode 100644 index 0000000..7d6e02e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_quadrotor_teleop/src/quadrotor_teleop.cpp @@ -0,0 +1,215 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + + +#include +#include +#include +#include +#include +#include + +namespace hector_quadrotor +{ + +class Teleop +{ +private: + ros::NodeHandle node_handle_; + ros::Subscriber joy_subscriber_; + + ros::Publisher velocity_publisher_, attitude_publisher_, yawrate_publisher_, thrust_publisher_; + geometry_msgs::Twist velocity_; + hector_uav_msgs::AttitudeCommand attitude_; + hector_uav_msgs::ThrustCommand thrust_; + hector_uav_msgs::YawrateCommand yawrate_; + + struct Axis + { + int axis; + double max; + }; + + struct Button + { + int button; + }; + + struct + { + Axis x; + Axis y; + Axis z; + Axis yaw; + } axes_; + + struct + { + Button slow; + } buttons_; + + double slow_factor_; + +public: + Teleop() + { + ros::NodeHandle params("~"); + + params.param("x_axis", axes_.x.axis, 4); + params.param("y_axis", axes_.y.axis, 3); + params.param("z_axis", axes_.z.axis, 2); + params.param("yaw_axis", axes_.yaw.axis, 1); + + params.param("yaw_velocity_max", axes_.yaw.max, 90.0 * M_PI / 180.0); + params.param("slow_button", buttons_.slow.button, 1); + params.param("slow_factor", slow_factor_, 0.2); + + std::string control_mode_str; + params.param("control_mode", control_mode_str, "twist"); + + if (control_mode_str == "twist") + { + params.param("x_velocity_max", axes_.x.max, 2.0); + params.param("y_velocity_max", axes_.y.max, 2.0); + params.param("z_velocity_max", axes_.z.max, 2.0); + + joy_subscriber_ = node_handle_.subscribe("joy", 1, boost::bind(&Teleop::joyTwistCallback, this, _1)); + velocity_publisher_ = node_handle_.advertise("cmd_vel", 10); + } + else if (control_mode_str == "attitude") + { + params.param("x_roll_max", axes_.x.max, 0.35); + params.param("y_pitch_max", axes_.y.max, 0.35); + params.param("z_thrust_max", axes_.z.max, 25.0); + joy_subscriber_ = node_handle_.subscribe("joy", 1, boost::bind(&Teleop::joyAttitudeCallback, this, _1)); + attitude_publisher_ = node_handle_.advertise("command/attitude", 10); + yawrate_publisher_ = node_handle_.advertise("command/yawrate", 10); + thrust_publisher_ = node_handle_.advertise("command/thrust", 10); + } + + } + + ~Teleop() + { + stop(); + } + + void joyTwistCallback(const sensor_msgs::JoyConstPtr &joy) + { + velocity_.linear.x = getAxis(joy, axes_.x); + velocity_.linear.y = getAxis(joy, axes_.y); + velocity_.linear.z = getAxis(joy, axes_.z); + velocity_.angular.z = getAxis(joy, axes_.yaw); + if (getButton(joy, buttons_.slow.button)) + { + velocity_.linear.x *= slow_factor_; + velocity_.linear.y *= slow_factor_; + velocity_.linear.z *= slow_factor_; + velocity_.angular.z *= slow_factor_; + } + velocity_publisher_.publish(velocity_); + } + + void joyAttitudeCallback(const sensor_msgs::JoyConstPtr &joy) + { + attitude_.roll = getAxis(joy, axes_.x); + attitude_.pitch = getAxis(joy, axes_.y); + attitude_publisher_.publish(attitude_); + + thrust_.thrust = getAxis(joy, axes_.z); + thrust_publisher_.publish(thrust_); + + yawrate_.turnrate = getAxis(joy, axes_.yaw); + if (getButton(joy, buttons_.slow.button)) + { + yawrate_.turnrate *= slow_factor_; + } + yawrate_publisher_.publish(yawrate_); + } + + sensor_msgs::Joy::_axes_type::value_type getAxis(const sensor_msgs::JoyConstPtr &joy, Axis axis) + { + if (axis.axis == 0) + {return 0;} + sensor_msgs::Joy::_axes_type::value_type sign = 1.0; + if (axis.axis < 0) + { + sign = -1.0; + axis.axis = -axis.axis; + } + if ((size_t) axis.axis > joy->axes.size()) + {return 0;} + return sign * joy->axes[axis.axis - 1] * axis.max; + } + + sensor_msgs::Joy::_buttons_type::value_type getButton(const sensor_msgs::JoyConstPtr &joy, int button) + { + if (button <= 0) + {return 0;} + if ((size_t) button > joy->buttons.size()) + {return 0;} + return joy->buttons[button - 1]; + } + + void stop() + { + if(velocity_publisher_.getNumSubscribers() > 0) + { + velocity_ = geometry_msgs::Twist(); + velocity_publisher_.publish(velocity_); + } + if(attitude_publisher_.getNumSubscribers() > 0) + { + attitude_ = hector_uav_msgs::AttitudeCommand(); + attitude_publisher_.publish(attitude_); + } + if(thrust_publisher_.getNumSubscribers() > 0) + { + thrust_ = hector_uav_msgs::ThrustCommand(); + thrust_publisher_.publish(thrust_); + } + if(yawrate_publisher_.getNumSubscribers() > 0) + { + yawrate_ = hector_uav_msgs::YawrateCommand(); + yawrate_publisher_.publish(yawrate_); + } + + } +}; + +} // namespace hector_quadrotor + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "quadrotor_teleop"); + + hector_quadrotor::Teleop teleop; + ros::spin(); + + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/CHANGELOG.rst b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/CHANGELOG.rst new file mode 100644 index 0000000..1f783b0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/CHANGELOG.rst @@ -0,0 +1,26 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package hector_uav_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.5 (2015-03-28) +------------------ + +0.3.4 (2015-02-22) +------------------ + +0.3.3 (2014-09-01) +------------------ +* updated value type in RawImu message to int16 +* added new ControllerState status constant FLYING +* added CLIMBRATE and TURNRATE constants to ControllerState message +* Contributors: Johannes Meyer + +0.3.2 (2014-03-30) +------------------ + +0.3.1 (2013-12-26) +------------------ + +0.3.0 (2013-09-11) +------------------ +* Catkinized stack hector_quadrotor and integrated hector_quadrotor_demo package from former hector_quadrotor_apps stack diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/CMakeLists.txt new file mode 100644 index 0000000..dd9ac9e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/CMakeLists.txt @@ -0,0 +1,90 @@ +cmake_minimum_required(VERSION 2.8.3) +project(hector_uav_msgs) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED message_generation std_msgs) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +####################################### +## Declare ROS messages and services ## +####################################### + +## Generate messages in the 'msg' folder +add_message_files( + FILES + Altimeter.msg + AttitudeCommand.msg + Compass.msg + ControllerState.msg + HeadingCommand.msg + HeightCommand.msg + MotorCommand.msg + MotorPWM.msg + MotorStatus.msg + PositionXYCommand.msg + RawImu.msg + RawMagnetic.msg + RawRC.msg + RC.msg + RuddersCommand.msg + ServoCommand.msg + Supply.msg + ThrustCommand.msg + VelocityXYCommand.msg + VelocityZCommand.msg + YawrateCommand.msg +) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + std_msgs +) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + INCLUDE_DIRS include +# LIBRARIES hector_uav_msgs + CATKIN_DEPENDS message_runtime std_msgs +# DEPENDS system_lib +) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark cpp header files for installation +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE +) + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/include/hector_uav_msgs/Altimeter/pressure_height.h b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/include/hector_uav_msgs/Altimeter/pressure_height.h new file mode 100644 index 0000000..6958138 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/include/hector_uav_msgs/Altimeter/pressure_height.h @@ -0,0 +1,61 @@ +//================================================================================================= +// Copyright (c) 2013, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#ifndef HECTOR_UAV_MSGS_ALTIMETER_PRESSURE_HEIGHT_H +#define HECTOR_UAV_MSGS_ALTIMETER_PRESSURE_HEIGHT_H + +#include +#include + +namespace hector_uav_msgs { + +static const Altimeter::_qnh_type STANDARD_PRESSURE = 1013.25; + +static inline Altimeter::_altitude_type altitudeFromPressure(Altimeter::_pressure_type pressure, Altimeter::_qnh_type qnh = STANDARD_PRESSURE) { + return 288.15 / 0.0065 * (1.0 - pow(pressure / qnh, 1.0/5.255)); +} + +static inline Altimeter::_pressure_type pressureFromAltitude(Altimeter::_altitude_type altitude, Altimeter::_qnh_type qnh = STANDARD_PRESSURE) { + return qnh * pow(1.0 - (0.0065 * altitude) / 288.15, 5.255); +} + +static inline Altimeter& altitudeFromPressure(Altimeter& altimeter) { + if (altimeter.qnh == 0.0) altimeter.qnh = STANDARD_PRESSURE; + altimeter.altitude = altitudeFromPressure(altimeter.pressure, altimeter.qnh); + return altimeter; +} + +static inline Altimeter& pressureFromAltitude(Altimeter& altimeter) { + if (altimeter.qnh == 0.0) altimeter.qnh = STANDARD_PRESSURE; + altimeter.pressure = pressureFromAltitude(altimeter.altitude, altimeter.qnh); + return altimeter; +} + +} // namespace hector_uav_msgs + +#endif // HECTOR_UAV_MSGS_ALTIMETER_PRESSURE_HEIGHT_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/include/hector_uav_msgs/ControlSource.h b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/include/hector_uav_msgs/ControlSource.h new file mode 100644 index 0000000..bd4db2a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/include/hector_uav_msgs/ControlSource.h @@ -0,0 +1,56 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#ifndef HECTOR_UAV_MSGS_CONTROLSOURCE_H +#define HECTOR_UAV_MSGS_CONTROLSOURCE_H + +namespace hector_uav_msgs +{ + typedef uint8_t ControlSource; + + enum { + CONTROL_AUTONOMOUS = 0, + CONTROL_REMOTE = 1, + CONTROL_JOYSTICK = 2 + }; + + template + static inline InStream& operator>>(InStream& in, ControlSource& value) { + int temp; + in >> temp; + value = static_cast(temp); + return in; + } + + template + static inline OutStream& operator<<(OutStream& out, const ControlSource& value) { + return out << static_cast(value); + } +} + +#endif // HECTOR_UAV_MSGS_CONTROLSOURCE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/include/hector_uav_msgs/RC/functions.h b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/include/hector_uav_msgs/RC/functions.h new file mode 100644 index 0000000..82c0df3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/include/hector_uav_msgs/RC/functions.h @@ -0,0 +1,103 @@ +//================================================================================================= +// Copyright (c) 2012, Johannes Meyer, TU Darmstadt +// All rights reserved. + +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of the Flight Systems and Automatic Control group, +// TU Darmstadt, nor the names of its contributors may be used to +// endorse or promote products derived from this software without +// specific prior written permission. + +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +// ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +// WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +//================================================================================================= + +#ifndef HECTOR_UAV_MSGS_RC_FUNCTIONS_H +#define HECTOR_UAV_MSGS_RC_FUNCTIONS_H + +#include +#include + +namespace hector_uav_msgs { + + static inline const char *getFunctionString(uint8_t function) + { + switch(function) { + case RC::ROLL: return "ROLL"; + case RC::PITCH: return "PITCH"; + case RC::YAW: return "YAW"; + case RC::STEER: return "STEER"; + case RC::HEIGHT: return "HEIGHT"; + case RC::THRUST: return "THRUST"; + case RC::BRAKE: return "BRAKE"; + } + return 0; + } + + static inline bool hasAxis(const RC& rc, RC::_axis_function_type::value_type function) + { + return std::find(rc.axis_function.begin(), rc.axis_function.end(), function) != rc.axis_function.end(); + } + + static inline bool getAxis(const RC& rc, RC::_axis_function_type::value_type function, RC::_axis_type::value_type& value) + { + if (!rc.valid) return false; + const RC::_axis_function_type::const_iterator it = std::find(rc.axis_function.begin(), rc.axis_function.end(), function); + if (it == rc.axis_function.end()) return false; + value = rc.axis.at(it - rc.axis_function.begin()); + return true; + } + + static inline void setAxis(RC& rc, RC::_axis_function_type::value_type function, RC::_axis_type::value_type value) + { + const RC::_axis_function_type::iterator it = std::find(rc.axis_function.begin(), rc.axis_function.end(), function); + if (it == rc.axis_function.end()) { + rc.axis_function.push_back(function); + rc.axis.push_back(value); + } else { + rc.axis.at(it - rc.axis_function.begin()) = value; + } + } + + static inline bool hasSwitch(const RC& rc, RC::_swit_function_type::value_type function) + { + return std::find(rc.swit_function.begin(), rc.swit_function.end(), function) != rc.swit_function.end(); + } + + static inline bool getSwitch(const RC& rc, RC::_swit_function_type::value_type function, RC::_swit_type::value_type& value) + { + if (!rc.valid) return false; + const RC::_swit_function_type::const_iterator it = std::find(rc.swit_function.begin(), rc.swit_function.end(), function); + if (it == rc.swit_function.end()) return false; + value = rc.swit.at(it - rc.swit_function.begin()); + return true; + } + + static inline void setSwitch(RC& rc, RC::_swit_function_type::value_type function, RC::_swit_type::value_type value) + { + const RC::_swit_function_type::iterator it = std::find(rc.swit_function.begin(), rc.swit_function.end(), function); + if (it == rc.swit_function.end()) { + rc.swit_function.push_back(function); + rc.swit.push_back(value); + } else { + rc.swit.at(it - rc.swit_function.begin()) = value; + } + } + +} // namespace hector_uav_msgs + +#endif // HECTOR_UAV_MSGS_RC_FUNCTIONS_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/Altimeter.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/Altimeter.msg new file mode 100644 index 0000000..20b6a3c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/Altimeter.msg @@ -0,0 +1,4 @@ +Header header +float32 altitude +float32 pressure +float32 qnh diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/AttitudeCommand.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/AttitudeCommand.msg new file mode 100644 index 0000000..d63fb89 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/AttitudeCommand.msg @@ -0,0 +1,3 @@ +Header header +float32 roll +float32 pitch diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/Compass.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/Compass.msg new file mode 100644 index 0000000..d2bb3fe --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/Compass.msg @@ -0,0 +1,4 @@ +Header header +float32 magnetic_heading +float32 declination + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/ControllerState.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/ControllerState.msg new file mode 100644 index 0000000..9903ca8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/ControllerState.msg @@ -0,0 +1,17 @@ +Header header +uint8 source + +uint8 mode +uint8 MOTORS = 1 +uint8 ATTITUDE = 2 +uint8 VELOCITY = 4 +uint8 POSITION = 8 +uint8 TURNRATE = 16 +uint8 HEADING = 32 +uint8 CLIMBRATE = 64 +uint8 HEIGHT = 128 + +uint8 state +uint8 MOTORS_RUNNING = 1 +uint8 FLYING = 2 +uint8 AIRBORNE = 4 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/HeadingCommand.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/HeadingCommand.msg new file mode 100644 index 0000000..5ad41a3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/HeadingCommand.msg @@ -0,0 +1,2 @@ +Header header +float32 heading diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/HeightCommand.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/HeightCommand.msg new file mode 100644 index 0000000..0d64519 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/HeightCommand.msg @@ -0,0 +1,2 @@ +Header header +float32 height diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/MotorCommand.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/MotorCommand.msg new file mode 100644 index 0000000..10ed1db --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/MotorCommand.msg @@ -0,0 +1,5 @@ +Header header +float32[] force +float32[] torque +float32[] frequency +float32[] voltage diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/MotorPWM.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/MotorPWM.msg new file mode 100644 index 0000000..d2bf65f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/MotorPWM.msg @@ -0,0 +1,2 @@ +Header header +uint8[] pwm diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/MotorStatus.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/MotorStatus.msg new file mode 100644 index 0000000..9c09473 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/MotorStatus.msg @@ -0,0 +1,7 @@ +Header header +bool on +bool running +float32[] voltage +float32[] frequency +float32[] current + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/PositionXYCommand.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/PositionXYCommand.msg new file mode 100644 index 0000000..de72e09 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/PositionXYCommand.msg @@ -0,0 +1,3 @@ +Header header +float32 x +float32 y diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/RC.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/RC.msg new file mode 100644 index 0000000..8dfdc55 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/RC.msg @@ -0,0 +1,18 @@ +Header header + +uint8 ROLL = 1 +uint8 PITCH = 2 +uint8 YAW = 3 +uint8 STEER = 4 +uint8 HEIGHT = 5 +uint8 THRUST = 6 +uint8 BRAKE = 7 + +uint8 status +bool valid + +float32[] axis +uint8[] axis_function + +int8[] swit +uint8[] swit_function diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/RawImu.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/RawImu.msg new file mode 100644 index 0000000..21c29a2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/RawImu.msg @@ -0,0 +1,3 @@ +Header header +int16[3] angular_velocity +int16[3] linear_acceleration diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/RawMagnetic.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/RawMagnetic.msg new file mode 100644 index 0000000..0a2543c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/RawMagnetic.msg @@ -0,0 +1,2 @@ +Header header +float64[3] channel diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/RawRC.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/RawRC.msg new file mode 100644 index 0000000..52b397c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/RawRC.msg @@ -0,0 +1,3 @@ +Header header +uint8 status +uint16[] channel diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/RuddersCommand.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/RuddersCommand.msg new file mode 100644 index 0000000..24a2773 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/RuddersCommand.msg @@ -0,0 +1,4 @@ +Header header +float32 aileron +float32 elevator +float32 rudder diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/ServoCommand.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/ServoCommand.msg new file mode 100644 index 0000000..91b661c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/ServoCommand.msg @@ -0,0 +1,2 @@ +Header header +uint16[] value diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/Supply.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/Supply.msg new file mode 100644 index 0000000..ca08cd6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/Supply.msg @@ -0,0 +1,3 @@ +Header header +float32[] voltage +float32[] current diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/ThrustCommand.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/ThrustCommand.msg new file mode 100644 index 0000000..fefdb9e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/ThrustCommand.msg @@ -0,0 +1,2 @@ +Header header +float32 thrust diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/VelocityXYCommand.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/VelocityXYCommand.msg new file mode 100644 index 0000000..de72e09 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/VelocityXYCommand.msg @@ -0,0 +1,3 @@ +Header header +float32 x +float32 y diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/VelocityZCommand.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/VelocityZCommand.msg new file mode 100644 index 0000000..0910464 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/VelocityZCommand.msg @@ -0,0 +1,2 @@ +Header header +float32 z diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/YawrateCommand.msg b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/YawrateCommand.msg new file mode 100644 index 0000000..fd2de10 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/msg/YawrateCommand.msg @@ -0,0 +1,2 @@ +Header header +float32 turnrate diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/package.xml new file mode 100644 index 0000000..9042717 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/hector_uav_msgs/package.xml @@ -0,0 +1,27 @@ + + hector_uav_msgs + 0.3.5 + hector_uav_msgs is a message package that contains messages for UAV controller inputs and outputs and some sensor readings not covered by sensor_msgs. + Johannes Meyer + + BSD + + http://ros.org/wiki/hector_uav_msgs + https://github.com/tu-darmstadt-ros-pkg/hector_quadrotor/issues + + Johannes Meyer + + + catkin + + + message_generation + std_msgs + + + message_runtime + std_msgs + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/LICENSE.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/LICENSE.md new file mode 100644 index 0000000..2ef7df8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/LICENSE.md @@ -0,0 +1,30 @@ + +BSD 3-Clause License + +Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/README.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/README.md new file mode 100644 index 0000000..59b42af --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/README.md @@ -0,0 +1,21 @@ +# ROSflight + +This repository contains the ROS stack for interfacing with an autopilot running the ROSflight firmware. For more information on the ROSflight autopilot firmware stack, visit http://rosflight.org. + +The following sections describe each of the packages contained in this stack. + +## rosflight_pkgs + +This is a metapackage for grouping the other packages into a ROS stack. + +## rosflight_msgs + +This package contains the ROSflight message and service definitions. + +## rosflight + +This package contains the `rosflight_io` node, which provides the core functionality for interfacing an onboard computer with the autopilot. This node streams autopilot sensor and status data to the onboard computer, streams control setpoints to the autopilot, and provides an interface for configuring the autopilot. + +## rosflight_utils + +This package contains additional supporting scripts and libraries that are not part of the core ROSflight package functionality. This package also helps support the [ros_plane](https://github.com/byu-magicc/ros_plane) and [ros_copter](https://github.com/byu-magicc/ros_copter) projects. diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/CHANGELOG.rst b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/CHANGELOG.rst new file mode 100644 index 0000000..8007315 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/CHANGELOG.rst @@ -0,0 +1,40 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package rosflight +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.1.3 (2017-06-02) +------------------ +* Temporarily removed magnetometer calibration +* Updated package.xml files +* Renamed sonar/data topic to sonar +* Changed yaml-cpp dependency to a PkgConfig module +* Contributors: Daniel Koch + +0.1.2 (2017-05-24) +------------------ +* Removed OpenMP compile flag for now +* Added missing tf dependency +* Contributors: Daniel Koch + +0.1.1 (2017-05-24) +------------------ +* Added missing dependencies +* Contributors: Daniel Koch + +0.1.0 (2017-05-22) +------------------ +* Added BSD license statements to source files + Closes `#1 `_ +* Added git as build dependency for rosflight +* Fixed system dependencies. Closes `#10 `_. +* cleanup of CMakeLists.txt +* cleanup of CMakeLists.txt +* automatic git submodule cloning +* Replaced outdated package README files with simpler top-level README + The information that used to be in the package README files is now on the ROS wiki (http://wiki.ros.org/rosflight_pkgs, http://wiki.ros.org/rosflight, etc.) + Closes `#7 `_ +* Fixed rosflight_io runtime name +* Created the rosflight_msgs package and updated dependencies +* Restructured rosflight package include structure +* Renamed rosflight_io package to rosflight +* Contributors: Daniel Koch, James Jackson diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/CMakeLists.txt new file mode 100644 index 0000000..34413c2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/CMakeLists.txt @@ -0,0 +1,114 @@ +cmake_minimum_required(VERSION 2.8.3) +project(rosflight) + +set(CMAKE_BUILD_TYPE Release) + +message("CMAKE_C_FLAGS_RELEASE is ${CMAKE_C_FLAGS_RELEASE}") + +set(CMAKE_CXX_FLAGS "-std=c++0x") + +find_package(catkin REQUIRED COMPONENTS + roscpp + geometry_msgs + rosflight_msgs + sensor_msgs + std_msgs + std_srvs + tf + eigen_stl_containers +) +find_package(Boost REQUIRED COMPONENTS system thread) +find_package(Eigen3 REQUIRED) + +find_package(PkgConfig REQUIRED) +pkg_check_modules(YAML_CPP REQUIRED yaml-cpp) + +## Look for and clone MAVLINK if it is missing +if(NOT EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/include/rosflight/mavlink/v1.0/.git") + message(STATUS "MAVLink submodule not found at ${CMAKE_CURRENT_SOURCE_DIR}/include/rosflight/mavlink/v1.0") + execute_process( + COMMAND git submodule update --init --recursive + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} + ) +endif() + +################################### +## catkin specific configuration ## +################################### + +catkin_package( + INCLUDE_DIRS include + LIBRARIES mavrosflight + CATKIN_DEPENDS roscpp geometry_msgs rosflight_msgs sensor_msgs std_msgs tf + DEPENDS Boost EIGEN3 YAML_CPP tf +) + +########### +## Build ## +########### + +include_directories(include) +include_directories( + ${catkin_INCLUDE_DIRS} + ${Boost_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} + ${YAML_CPP_INCLUDEDIR} +) + +# mavrosflight library +add_library(mavrosflight + src/mavrosflight/mavrosflight.cpp + src/mavrosflight/mavlink_comm.cpp + src/mavrosflight/mavlink_serial.cpp + src/mavrosflight/mavlink_udp.cpp + src/mavrosflight/param_manager.cpp + src/mavrosflight/param.cpp + src/mavrosflight/time_manager.cpp +) +add_dependencies(mavrosflight ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(mavrosflight + ${catkin_LIBRARIES} + ${Boost_LIBRARIES} + ${YAML_CPP_LIBRARIES} +) + +# rosflight_io_node +add_executable(rosflight_io + src/rosflight_io_node.cpp + src/rosflight_io.cpp +) +add_dependencies(rosflight_io ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(rosflight_io + mavrosflight + ${catkin_LIBRARIES} + ${Boost_LIBRARES} +) + +add_executable(calibrate_mag + src/mag_cal_node.cpp + src/mag_cal.cpp +) +add_dependencies(calibrate_mag ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +target_link_libraries(calibrate_mag + ${catkin_LIBRARIES} + ${Boost_LIBRARIES} +) + +############# +## Install ## +############# + +# Mark executables and libraries for installation +install(TARGETS mavrosflight rosflight_io + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +# Mark cpp header files for installation +install(DIRECTORY include/rosflight/mavrosflight/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE +) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mag_cal.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mag_cal.h new file mode 100644 index 0000000..096d080 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mag_cal.h @@ -0,0 +1,160 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file mag_cal.h + * \author Jerel Nielsen + * \author Devon Morris + */ + +#ifndef ROSFLIGHT_SENSORS_CALBRATE_MAG_H +#define ROSFLIGHT_SENSORS_CALBRATE_MAG_H + +#include +#include + +#include + +#include + +#include +#include +#include + +#include + +#include +#include + +namespace rosflight +{ + +/** + * \brief CalibrateMag sensor class + */ +class CalibrateMag +{ +public: + + CalibrateMag(); + + void run(); + + /** + * \brief Begin the magnetometer calibration routine + */ + void start_mag_calibration(); + + void do_mag_calibration(); + + /** + * @brief set_refence_magnetic_field_strength + * @param reference_magnetic_field + */ + bool mag_callback(const sensor_msgs::MagneticField::ConstPtr& mag); + + void set_reference_magnetic_field_strength(double reference_magnetic_field); + + /** + * \brief Check if a calibration is in progress + * \return True if a calibration is currently in progress + */ + bool is_calibrating() { return calibrating_; } + + /// The const stuff is to make it read-only + const double a11() const { return A_(0, 0); } + const double a12() const { return A_(0, 1); } + const double a13() const { return A_(0, 2); } + const double a21() const { return A_(1, 0); } + const double a22() const { return A_(1, 1); } + const double a23() const { return A_(1, 2); } + const double a31() const { return A_(2, 0); } + const double a32() const { return A_(2, 1); } + const double a33() const { return A_(2, 2); } + const double bx() const { return b_(0, 0); } + const double by() const { return b_(1, 0); } + const double bz() const { return b_(2, 0); } + +private: + bool set_param(std::string name, double value); + + ros::NodeHandle nh_; + ros::NodeHandle nh_private_; + + message_filters::Subscriber mag_subscriber_; + + ros::ServiceServer mag_cal_srv_; + ros::ServiceClient param_set_client_; + + Eigen::MatrixXd A_, b_; + + double reference_field_strength_; //!< the strength of earth's magnetic field at your location + + bool calibrating_; //!< whether a temperature calibration is in progress + bool first_time_; //!< waiting for first measurement for calibration + double calibration_time_; //!< seconds to record data for temperature compensation + double start_time_; //!< timestamp of first calibration measurement + int ransac_iters_; //!< number of ransac iterations to fit ellipsoid to mag measurements + int measurement_skip_; + int measurement_throttle_; + double inlier_thresh_; //!< threshold to consider measurement an inlier in ellipsoidRANSAC + Eigen::Vector3d measurement_prev_; + EigenSTL::vector_Vector3d measurements_; + + // function to perform RANSAC on ellipsoid data + Eigen::MatrixXd ellipsoidRANSAC(EigenSTL::vector_Vector3d meas, int iters, double inlier_thresh); + + // function to vector from ellipsoid center to surface along input vector + Eigen::Vector3d intersect(Eigen::Vector3d r_m, Eigen::Vector3d r_e, Eigen::MatrixXd Q, Eigen::MatrixXd ub, double k); + + /* + sort eigenvalues and eigenvectors output from Eigen library + */ + void eigSort(Eigen::MatrixXd &w, Eigen::MatrixXd &v); + + /* + This function gets ellipsoid parameters via least squares on ellipsoidal data + according to the paper: Li, Qingde, and John G. Griffiths. "Least squares ellipsoid + specific fitting." Geometric modeling and processing, 2004. proceedings. IEEE, 2004. + */ + Eigen::MatrixXd ellipsoidLS(EigenSTL::vector_Vector3d meas); + + /* + This function compute magnetometer calibration parameters according to Section 5.3 of the + paper: Renaudin, Valérie, Muhammad Haris Afzal, and Gérard Lachapelle. "Complete triaxis + magnetometer calibration in the magnetic domain." Journal of sensors 2010 (2010). + */ + void magCal(Eigen::MatrixXd u, Eigen::MatrixXd &A, Eigen::MatrixXd &bb); +}; + +} // namespace mag_cal + +#endif // MAVROSFLIGHT_SENSORS_MAG_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/checksum.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/checksum.h new file mode 100644 index 0000000..0f30b65 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/checksum.h @@ -0,0 +1,96 @@ +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef _CHECKSUM_H_ +#define _CHECKSUM_H_ + +// Visual Studio versions before 2010 don't have stdint.h, so we just error out. +#if (defined _MSC_VER) && (_MSC_VER < 1600) +#error "The C-MAVLink implementation requires Visual Studio 2010 or greater" +#endif + +#include + +/** + * + * CALCULATE THE CHECKSUM + * + */ + +#define X25_INIT_CRC 0xffff +#define X25_VALIDATE_CRC 0xf0b8 + +#ifndef HAVE_CRC_ACCUMULATE +/** + * @brief Accumulate the X.25 CRC by adding one char at a time. + * + * The checksum function adds the hash of one char at a time to the + * 16 bit checksum (uint16_t). + * + * @param data new char to hash + * @param crcAccum the already accumulated checksum + **/ +static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) +{ + /*Accumulate one byte of data into the CRC*/ + uint8_t tmp; + + tmp = data ^ (uint8_t)(*crcAccum &0xff); + tmp ^= (tmp<<4); + *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); +} +#endif + + +/** + * @brief Initiliaze the buffer for the X.25 CRC + * + * @param crcAccum the 16 bit X.25 CRC + */ +static inline void crc_init(uint16_t* crcAccum) +{ + *crcAccum = X25_INIT_CRC; +} + + +/** + * @brief Calculates the X.25 checksum on a byte buffer + * + * @param pBuffer buffer containing the byte array to hash + * @param length length of the byte array + * @return the checksum over the buffer bytes + **/ +static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length) +{ + uint16_t crcTmp; + crc_init(&crcTmp); + while (length--) { + crc_accumulate(*pBuffer++, &crcTmp); + } + return crcTmp; +} + + +/** + * @brief Accumulate the X.25 CRC by adding an array of bytes + * + * The checksum function adds the hash of one char at a time to the + * 16 bit checksum (uint16_t). + * + * @param data new bytes to hash + * @param crcAccum the already accumulated checksum + **/ +static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length) +{ + const uint8_t *p = (const uint8_t *)pBuffer; + while (length--) { + crc_accumulate(*p++, crcAccum); + } +} + +#endif /* _CHECKSUM_H_ */ + +#ifdef __cplusplus +} +#endif diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/common.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/common.h new file mode 100644 index 0000000..ce06f42 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/common.h @@ -0,0 +1,1007 @@ +/** @file + * @brief MAVLink comm protocol generated from common.xml + * @see http://mavlink.org + */ +#ifndef MAVLINK_COMMON_H +#define MAVLINK_COMMON_H + +#ifndef MAVLINK_H + #error Wrong include order: MAVLINK_COMMON.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call. +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 37, 4, 0, 0, 27, 25, 0, 0, 0, 0, 0, 68, 26, 185, 229, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 53, 51, 53, 51, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 44, 64, 84, 9, 254, 16, 12, 36, 44, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 22, 13, 255, 14, 18, 43, 8, 22, 14, 36, 43, 41, 32, 243, 14, 93, 0, 100, 36, 60, 30, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 32, 52, 53, 6, 2, 38, 0, 254, 36, 30, 18, 18, 51, 9, 0} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 78, 196, 0, 0, 15, 3, 0, 0, 0, 0, 0, 153, 183, 51, 59, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 138, 108, 32, 185, 84, 34, 174, 124, 237, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 46, 29, 223, 85, 6, 229, 203, 1, 195, 109, 168, 181, 47, 72, 131, 127, 0, 103, 154, 178, 200, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 163, 105, 0, 0, 0, 0, 0, 0, 0, 0, 0, 90, 104, 85, 95, 130, 184, 0, 8, 204, 49, 170, 44, 83, 46, 0} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ALTITUDE, MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3, MAVLINK_MESSAGE_INFO_FOLLOW_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_LANDING_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS, MAVLINK_MESSAGE_INFO_WIND_COV, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VIBRATION, MAVLINK_MESSAGE_INFO_HOME_POSITION, MAVLINK_MESSAGE_INFO_SET_HOME_POSITION, MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL, MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE, MAVLINK_MESSAGE_INFO_ADSB_VEHICLE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_COMMON + +// ENUM DEFINITIONS + + +/** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */ +#ifndef HAVE_ENUM_MAV_AUTOPILOT +#define HAVE_ENUM_MAV_AUTOPILOT +typedef enum MAV_AUTOPILOT +{ + MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */ + MAV_AUTOPILOT_RESERVED=1, /* Reserved for future use. | */ + MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */ + MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilotMega / ArduCopter, http://diydrones.com | */ + MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */ + MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */ + MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */ + MAV_AUTOPILOT_GENERIC_MISSION_FULL=7, /* Generic autopilot supporting the full mission command set | */ + MAV_AUTOPILOT_INVALID=8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */ + MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */ + MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */ + MAV_AUTOPILOT_FP=11, /* FlexiPilot | */ + MAV_AUTOPILOT_PX4=12, /* PX4 Autopilot - http://pixhawk.ethz.ch/px4/ | */ + MAV_AUTOPILOT_SMACCMPILOT=13, /* SMACCMPilot - http://smaccmpilot.org | */ + MAV_AUTOPILOT_AUTOQUAD=14, /* AutoQuad -- http://autoquad.org | */ + MAV_AUTOPILOT_ARMAZILA=15, /* Armazila -- http://armazila.com | */ + MAV_AUTOPILOT_AEROB=16, /* Aerob -- http://aerob.ru | */ + MAV_AUTOPILOT_ASLUAV=17, /* ASLUAV autopilot -- http://www.asl.ethz.ch | */ + MAV_AUTOPILOT_ENUM_END=18, /* | */ +} MAV_AUTOPILOT; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_TYPE +#define HAVE_ENUM_MAV_TYPE +typedef enum MAV_TYPE +{ + MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */ + MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */ + MAV_TYPE_QUADROTOR=2, /* Quadrotor | */ + MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */ + MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */ + MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */ + MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */ + MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */ + MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */ + MAV_TYPE_ROCKET=9, /* Rocket | */ + MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */ + MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */ + MAV_TYPE_SUBMARINE=12, /* Submarine | */ + MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */ + MAV_TYPE_OCTOROTOR=14, /* Octorotor | */ + MAV_TYPE_TRICOPTER=15, /* Octorotor | */ + MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */ + MAV_TYPE_KITE=17, /* Flapping wing | */ + MAV_TYPE_ONBOARD_CONTROLLER=18, /* Onboard companion controller | */ + MAV_TYPE_VTOL_DUOROTOR=19, /* Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. | */ + MAV_TYPE_VTOL_QUADROTOR=20, /* Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. | */ + MAV_TYPE_VTOL_TILTROTOR=21, /* Tiltrotor VTOL | */ + MAV_TYPE_VTOL_RESERVED2=22, /* VTOL reserved 2 | */ + MAV_TYPE_VTOL_RESERVED3=23, /* VTOL reserved 3 | */ + MAV_TYPE_VTOL_RESERVED4=24, /* VTOL reserved 4 | */ + MAV_TYPE_VTOL_RESERVED5=25, /* VTOL reserved 5 | */ + MAV_TYPE_GIMBAL=26, /* Onboard gimbal | */ + MAV_TYPE_ADSB=27, /* Onboard ADSB peripheral | */ + MAV_TYPE_ENUM_END=28, /* | */ +} MAV_TYPE; +#endif + +/** @brief These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65. */ +#ifndef HAVE_ENUM_FIRMWARE_VERSION_TYPE +#define HAVE_ENUM_FIRMWARE_VERSION_TYPE +typedef enum FIRMWARE_VERSION_TYPE +{ + FIRMWARE_VERSION_TYPE_DEV=0, /* development release | */ + FIRMWARE_VERSION_TYPE_ALPHA=64, /* alpha release | */ + FIRMWARE_VERSION_TYPE_BETA=128, /* beta release | */ + FIRMWARE_VERSION_TYPE_RC=192, /* release candidate | */ + FIRMWARE_VERSION_TYPE_OFFICIAL=255, /* official stable release | */ + FIRMWARE_VERSION_TYPE_ENUM_END=256, /* | */ +} FIRMWARE_VERSION_TYPE; +#endif + +/** @brief These flags encode the MAV mode. */ +#ifndef HAVE_ENUM_MAV_MODE_FLAG +#define HAVE_ENUM_MAV_MODE_FLAG +typedef enum MAV_MODE_FLAG +{ + MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */ + MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */ + MAV_MODE_FLAG_AUTO_ENABLED=4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */ + MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */ + MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */ + MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */ + MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */ + MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */ + MAV_MODE_FLAG_ENUM_END=129, /* | */ +} MAV_MODE_FLAG; +#endif + +/** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */ +#ifndef HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION +#define HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION +typedef enum MAV_MODE_FLAG_DECODE_POSITION +{ + MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */ + MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */ + MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixt bit: 00000100 | */ + MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit: 00001000 | */ + MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */ + MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit: 00100000 | */ + MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */ + MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit: 10000000 | */ + MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /* | */ +} MAV_MODE_FLAG_DECODE_POSITION; +#endif + +/** @brief Override command, pauses current mission execution and moves immediately to a position */ +#ifndef HAVE_ENUM_MAV_GOTO +#define HAVE_ENUM_MAV_GOTO +typedef enum MAV_GOTO +{ + MAV_GOTO_DO_HOLD=0, /* Hold at the current position. | */ + MAV_GOTO_DO_CONTINUE=1, /* Continue with the next item in mission execution. | */ + MAV_GOTO_HOLD_AT_CURRENT_POSITION=2, /* Hold at the current position of the system | */ + MAV_GOTO_HOLD_AT_SPECIFIED_POSITION=3, /* Hold at the position specified in the parameters of the DO_HOLD action | */ + MAV_GOTO_ENUM_END=4, /* | */ +} MAV_GOTO; +#endif + +/** @brief These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it + simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. */ +#ifndef HAVE_ENUM_MAV_MODE +#define HAVE_ENUM_MAV_MODE +typedef enum MAV_MODE +{ + MAV_MODE_PREFLIGHT=0, /* System is not ready to fly, booting, calibrating, etc. No flag is set. | */ + MAV_MODE_MANUAL_DISARMED=64, /* System is allowed to be active, under manual (RC) control, no stabilization | */ + MAV_MODE_TEST_DISARMED=66, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ + MAV_MODE_STABILIZE_DISARMED=80, /* System is allowed to be active, under assisted RC control. | */ + MAV_MODE_GUIDED_DISARMED=88, /* System is allowed to be active, under autonomous control, manual setpoint | */ + MAV_MODE_AUTO_DISARMED=92, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ + MAV_MODE_MANUAL_ARMED=192, /* System is allowed to be active, under manual (RC) control, no stabilization | */ + MAV_MODE_TEST_ARMED=194, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ + MAV_MODE_STABILIZE_ARMED=208, /* System is allowed to be active, under assisted RC control. | */ + MAV_MODE_GUIDED_ARMED=216, /* System is allowed to be active, under autonomous control, manual setpoint | */ + MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ + MAV_MODE_ENUM_END=221, /* | */ +} MAV_MODE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_STATE +#define HAVE_ENUM_MAV_STATE +typedef enum MAV_STATE +{ + MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */ + MAV_STATE_BOOT=1, /* System is booting up. | */ + MAV_STATE_CALIBRATING=2, /* System is calibrating and not flight-ready. | */ + MAV_STATE_STANDBY=3, /* System is grounded and on standby. It can be launched any time. | */ + MAV_STATE_ACTIVE=4, /* System is active and might be already airborne. Motors are engaged. | */ + MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode. It can however still navigate. | */ + MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */ + MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */ + MAV_STATE_ENUM_END=8, /* | */ +} MAV_STATE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_COMPONENT +#define HAVE_ENUM_MAV_COMPONENT +typedef enum MAV_COMPONENT +{ + MAV_COMP_ID_ALL=0, /* | */ + MAV_COMP_ID_CAMERA=100, /* | */ + MAV_COMP_ID_SERVO1=140, /* | */ + MAV_COMP_ID_SERVO2=141, /* | */ + MAV_COMP_ID_SERVO3=142, /* | */ + MAV_COMP_ID_SERVO4=143, /* | */ + MAV_COMP_ID_SERVO5=144, /* | */ + MAV_COMP_ID_SERVO6=145, /* | */ + MAV_COMP_ID_SERVO7=146, /* | */ + MAV_COMP_ID_SERVO8=147, /* | */ + MAV_COMP_ID_SERVO9=148, /* | */ + MAV_COMP_ID_SERVO10=149, /* | */ + MAV_COMP_ID_SERVO11=150, /* | */ + MAV_COMP_ID_SERVO12=151, /* | */ + MAV_COMP_ID_SERVO13=152, /* | */ + MAV_COMP_ID_SERVO14=153, /* | */ + MAV_COMP_ID_GIMBAL=154, /* | */ + MAV_COMP_ID_LOG=155, /* | */ + MAV_COMP_ID_ADSB=156, /* | */ + MAV_COMP_ID_OSD=157, /* On Screen Display (OSD) devices for video links | */ + MAV_COMP_ID_PERIPHERAL=158, /* Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol | */ + MAV_COMP_ID_MAPPER=180, /* | */ + MAV_COMP_ID_MISSIONPLANNER=190, /* | */ + MAV_COMP_ID_PATHPLANNER=195, /* | */ + MAV_COMP_ID_IMU=200, /* | */ + MAV_COMP_ID_IMU_2=201, /* | */ + MAV_COMP_ID_IMU_3=202, /* | */ + MAV_COMP_ID_GPS=220, /* | */ + MAV_COMP_ID_UDP_BRIDGE=240, /* | */ + MAV_COMP_ID_UART_BRIDGE=241, /* | */ + MAV_COMP_ID_SYSTEM_CONTROL=250, /* | */ + MAV_COMPONENT_ENUM_END=251, /* | */ +} MAV_COMPONENT; +#endif + +/** @brief These encode the sensors whose status is sent as part of the SYS_STATUS message. */ +#ifndef HAVE_ENUM_MAV_SYS_STATUS_SENSOR +#define HAVE_ENUM_MAV_SYS_STATUS_SENSOR +typedef enum MAV_SYS_STATUS_SENSOR +{ + MAV_SYS_STATUS_SENSOR_3D_GYRO=1, /* 0x01 3D gyro | */ + MAV_SYS_STATUS_SENSOR_3D_ACCEL=2, /* 0x02 3D accelerometer | */ + MAV_SYS_STATUS_SENSOR_3D_MAG=4, /* 0x04 3D magnetometer | */ + MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE=8, /* 0x08 absolute pressure | */ + MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE=16, /* 0x10 differential pressure | */ + MAV_SYS_STATUS_SENSOR_GPS=32, /* 0x20 GPS | */ + MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW=64, /* 0x40 optical flow | */ + MAV_SYS_STATUS_SENSOR_VISION_POSITION=128, /* 0x80 computer vision position | */ + MAV_SYS_STATUS_SENSOR_LASER_POSITION=256, /* 0x100 laser based position | */ + MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH=512, /* 0x200 external ground truth (Vicon or Leica) | */ + MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL=1024, /* 0x400 3D angular rate control | */ + MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION=2048, /* 0x800 attitude stabilization | */ + MAV_SYS_STATUS_SENSOR_YAW_POSITION=4096, /* 0x1000 yaw position | */ + MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL=8192, /* 0x2000 z/altitude control | */ + MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL=16384, /* 0x4000 x/y position control | */ + MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS=32768, /* 0x8000 motor outputs / control | */ + MAV_SYS_STATUS_SENSOR_RC_RECEIVER=65536, /* 0x10000 rc receiver | */ + MAV_SYS_STATUS_SENSOR_3D_GYRO2=131072, /* 0x20000 2nd 3D gyro | */ + MAV_SYS_STATUS_SENSOR_3D_ACCEL2=262144, /* 0x40000 2nd 3D accelerometer | */ + MAV_SYS_STATUS_SENSOR_3D_MAG2=524288, /* 0x80000 2nd 3D magnetometer | */ + MAV_SYS_STATUS_GEOFENCE=1048576, /* 0x100000 geofence | */ + MAV_SYS_STATUS_AHRS=2097152, /* 0x200000 AHRS subsystem health | */ + MAV_SYS_STATUS_TERRAIN=4194304, /* 0x400000 Terrain subsystem health | */ + MAV_SYS_STATUS_REVERSE_MOTOR=8388608, /* 0x800000 Motors are reversed | */ + MAV_SYS_STATUS_SENSOR_ENUM_END=8388609, /* | */ +} MAV_SYS_STATUS_SENSOR; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_FRAME +#define HAVE_ENUM_MAV_FRAME +typedef enum MAV_FRAME +{ + MAV_FRAME_GLOBAL=0, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | */ + MAV_FRAME_LOCAL_NED=1, /* Local coordinate frame, Z-up (x: north, y: east, z: down). | */ + MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */ + MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */ + MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */ + MAV_FRAME_GLOBAL_INT=5, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL) | */ + MAV_FRAME_GLOBAL_RELATIVE_ALT_INT=6, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. | */ + MAV_FRAME_LOCAL_OFFSET_NED=7, /* Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. | */ + MAV_FRAME_BODY_NED=8, /* Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. | */ + MAV_FRAME_BODY_OFFSET_NED=9, /* Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. | */ + MAV_FRAME_GLOBAL_TERRAIN_ALT=10, /* Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */ + MAV_FRAME_GLOBAL_TERRAIN_ALT_INT=11, /* Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */ + MAV_FRAME_ENUM_END=12, /* | */ +} MAV_FRAME; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE +#define HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE +typedef enum MAVLINK_DATA_STREAM_TYPE +{ + MAVLINK_DATA_STREAM_IMG_JPEG=1, /* | */ + MAVLINK_DATA_STREAM_IMG_BMP=2, /* | */ + MAVLINK_DATA_STREAM_IMG_RAW8U=3, /* | */ + MAVLINK_DATA_STREAM_IMG_RAW32U=4, /* | */ + MAVLINK_DATA_STREAM_IMG_PGM=5, /* | */ + MAVLINK_DATA_STREAM_IMG_PNG=6, /* | */ + MAVLINK_DATA_STREAM_TYPE_ENUM_END=7, /* | */ +} MAVLINK_DATA_STREAM_TYPE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_FENCE_ACTION +#define HAVE_ENUM_FENCE_ACTION +typedef enum FENCE_ACTION +{ + FENCE_ACTION_NONE=0, /* Disable fenced mode | */ + FENCE_ACTION_GUIDED=1, /* Switched to guided mode to return point (fence point 0) | */ + FENCE_ACTION_REPORT=2, /* Report fence breach, but don't take action | */ + FENCE_ACTION_GUIDED_THR_PASS=3, /* Switched to guided mode to return point (fence point 0) with manual throttle control | */ + FENCE_ACTION_ENUM_END=4, /* | */ +} FENCE_ACTION; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_FENCE_BREACH +#define HAVE_ENUM_FENCE_BREACH +typedef enum FENCE_BREACH +{ + FENCE_BREACH_NONE=0, /* No last fence breach | */ + FENCE_BREACH_MINALT=1, /* Breached minimum altitude | */ + FENCE_BREACH_MAXALT=2, /* Breached maximum altitude | */ + FENCE_BREACH_BOUNDARY=3, /* Breached fence boundary | */ + FENCE_BREACH_ENUM_END=4, /* | */ +} FENCE_BREACH; +#endif + +/** @brief Enumeration of possible mount operation modes */ +#ifndef HAVE_ENUM_MAV_MOUNT_MODE +#define HAVE_ENUM_MAV_MOUNT_MODE +typedef enum MAV_MOUNT_MODE +{ + MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization | */ + MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | */ + MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */ + MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */ + MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */ + MAV_MOUNT_MODE_ENUM_END=5, /* | */ +} MAV_MOUNT_MODE; +#endif + +/** @brief Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */ +#ifndef HAVE_ENUM_MAV_CMD +#define HAVE_ENUM_MAV_CMD +typedef enum MAV_CMD +{ + MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_LAND=21, /* Land at location |Abort Alt| Empty| Empty| Desired yaw angle| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LAND_LOCAL=23, /* Land at local position (local frame only) |Landing target number (if available)| Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land| Landing descend rate [ms^-1]| Desired yaw angle [rad]| Y-axis position [m]| X-axis position [m]| Z-axis / ground level position [m]| */ + MAV_CMD_NAV_TAKEOFF_LOCAL=24, /* Takeoff from local position (local frame only) |Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]| Empty| Takeoff ascend rate [ms^-1]| Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these| Y-axis position [m]| X-axis position [m]| Z-axis position [m]| */ + MAV_CMD_NAV_FOLLOW=25, /* Vehicle following, i.e. this waypoint represents the position of a moving vehicle |Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation| Ground speed of vehicle to be followed| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT=30, /* Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. |Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. | Empty| Empty| Empty| Empty| Empty| Desired altitude in meters| */ + MAV_CMD_NAV_LOITER_TO_ALT=31, /* Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. |Heading Required (0 = False)| Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.| Empty| Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location| Latitude| Longitude| Altitude| */ + MAV_CMD_DO_FOLLOW=32, /* Being following a target |System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode| RESERVED| RESERVED| altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home| altitude| RESERVED| TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout| */ + MAV_CMD_DO_FOLLOW_REPOSITION=33, /* Reposition the MAV after a follow target command has been sent |Camera q1 (where 0 is on the ray from the camera to the tracking device)| Camera q2| Camera q3| Camera q4| altitude offset from target (m)| X offset from target (m)| Y offset from target (m)| */ + MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ + MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_VTOL_TAKEOFF=84, /* Takeoff from ground using VTOL mode |Empty| Empty| Empty| Yaw angle in degrees| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_VTOL_LAND=85, /* Land using VTOL mode |Empty| Empty| Empty| Yaw angle in degrees| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_DELAY=93, /* Delay the next navigation command a number of seconds or until a specified time |Delay in seconds (decimal, -1 to enable time-of-day fields)| hour (24h format, UTC, -1 to ignore)| minute (24h format, UTC, -1 to ignore)| second (24h format, UTC)| Empty| Empty| Empty| */ + MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ + MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| absolute or relative [0,1]| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ + MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ + MAV_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_LAND_START=189, /* Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty| */ + MAV_CMD_DO_RALLY_LAND=190, /* Mission command to perform a landing from a rally point. |Break altitude (meters)| Landing speed (m/s)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_GO_AROUND=191, /* Mission command to safely abort an autonmous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPOSITION=192, /* Reposition the vehicle to a specific WGS84 global position. |Ground speed, less than 0 (-1) for default| Bitmask of option flags, see the MAV_DO_REPOSITION_FLAGS enum.| Reserved| Yaw heading, NaN for unchanged. For planes indicates loiter direction (0: clockwise, 1: counter clockwise)| Latitude (deg * 1E7)| Longitude (deg * 1E7)| Altitude (meters)| */ + MAV_CMD_DO_PAUSE_CONTINUE=193, /* If in a GPS controlled position mode, hold the current position or continue. |0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ + MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ + MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */ + MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */ + MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ + MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */ + MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable, 2=disable_floor_only)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| */ + MAV_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_GUIDED_LIMITS=222, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */ + MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */ + MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ + MAV_CMD_PREFLIGHT_UAVCAN=243, /* Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. |1: Trigger actuator ID assignment and direction mapping.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ + MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)| Reserved| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.| Reserved, send 0| Reserved, send 0| Reserved, send 0| Reserved, send 0| Reserved, send 0| */ + MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ + MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ + MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ + MAV_CMD_GET_HOME_POSITION=410, /* Request the home position from the vehicle. |Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ + MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ + MAV_CMD_GET_MESSAGE_INTERVAL=510, /* Request the interval between messages for a particular MAVLink message ID |The MAVLink message ID| */ + MAV_CMD_SET_MESSAGE_INTERVAL=511, /* Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM |The MAVLink message ID| The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.| */ + MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities |1: Request autopilot version| Reserved (all remaining params)| */ + MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence |Duration between two consecutive pictures (in seconds)| Number of images to capture total - 0 for unlimited capture| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */ + MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence |Reserved| Reserved| */ + MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start)| Shutter integration time (in ms)| Reserved| */ + MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture |Camera ID (0 for all cameras), 1 for first, 2 for second, etc.| Frames per second| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */ + MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture |Reserved| Reserved| */ + MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)| Viewing angle vertical of panorama (in degrees)| Speed of the horizontal rotation (in degrees per second)| Speed of the vertical rotation (in degrees per second)| */ + MAV_CMD_DO_VTOL_TRANSITION=3000, /* Request VTOL transition |The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.| */ + MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.| Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Altitude, in meters AMSL| */ + MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ + MAV_CMD_WAYPOINT_USER_1=31000, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_WAYPOINT_USER_2=31001, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_WAYPOINT_USER_3=31002, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_WAYPOINT_USER_4=31003, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_WAYPOINT_USER_5=31004, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_SPATIAL_USER_1=31005, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_SPATIAL_USER_2=31006, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_SPATIAL_USER_3=31007, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_SPATIAL_USER_4=31008, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_SPATIAL_USER_5=31009, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_USER_1=31010, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ + MAV_CMD_USER_2=31011, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ + MAV_CMD_USER_3=31012, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ + MAV_CMD_USER_4=31013, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ + MAV_CMD_USER_5=31014, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ + MAV_CMD_ENUM_END=31015, /* | */ +} MAV_CMD; +#endif + +/** @brief THIS INTERFACE IS DEPRECATED AS OF JULY 2015. Please use MESSAGE_INTERVAL instead. A data stream is not a fixed set of messages, but rather a + recommendation to the autopilot software. Individual autopilots may or may not obey + the recommended messages. */ +#ifndef HAVE_ENUM_MAV_DATA_STREAM +#define HAVE_ENUM_MAV_DATA_STREAM +typedef enum MAV_DATA_STREAM +{ + MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */ + MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */ + MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */ + MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */ + MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */ + MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */ + MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_ENUM_END=13, /* | */ +} MAV_DATA_STREAM; +#endif + +/** @brief The ROI (region of interest) for the vehicle. This can be + be used by the vehicle for camera/vehicle attitude alignment (see + MAV_CMD_NAV_ROI). */ +#ifndef HAVE_ENUM_MAV_ROI +#define HAVE_ENUM_MAV_ROI +typedef enum MAV_ROI +{ + MAV_ROI_NONE=0, /* No region of interest. | */ + MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */ + MAV_ROI_WPINDEX=2, /* Point toward given MISSION. | */ + MAV_ROI_LOCATION=3, /* Point toward fixed location. | */ + MAV_ROI_TARGET=4, /* Point toward of given id. | */ + MAV_ROI_ENUM_END=5, /* | */ +} MAV_ROI; +#endif + +/** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */ +#ifndef HAVE_ENUM_MAV_CMD_ACK +#define HAVE_ENUM_MAV_CMD_ACK +typedef enum MAV_CMD_ACK +{ + MAV_CMD_ACK_OK=1, /* Command / mission item is ok. | */ + MAV_CMD_ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */ + MAV_CMD_ACK_ERR_ACCESS_DENIED=3, /* The system is refusing to accept this command from this source / communication partner. | */ + MAV_CMD_ACK_ERR_NOT_SUPPORTED=4, /* Command or mission item is not supported, other commands would be accepted. | */ + MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, /* The coordinate frame of this command / mission item is not supported. | */ + MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE=6, /* The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | */ + MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE=7, /* The X or latitude value is out of range. | */ + MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */ + MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */ + MAV_CMD_ACK_ENUM_END=10, /* | */ +} MAV_CMD_ACK; +#endif + +/** @brief Specifies the datatype of a MAVLink parameter. */ +#ifndef HAVE_ENUM_MAV_PARAM_TYPE +#define HAVE_ENUM_MAV_PARAM_TYPE +typedef enum MAV_PARAM_TYPE +{ + MAV_PARAM_TYPE_UINT8=1, /* 8-bit unsigned integer | */ + MAV_PARAM_TYPE_INT8=2, /* 8-bit signed integer | */ + MAV_PARAM_TYPE_UINT16=3, /* 16-bit unsigned integer | */ + MAV_PARAM_TYPE_INT16=4, /* 16-bit signed integer | */ + MAV_PARAM_TYPE_UINT32=5, /* 32-bit unsigned integer | */ + MAV_PARAM_TYPE_INT32=6, /* 32-bit signed integer | */ + MAV_PARAM_TYPE_UINT64=7, /* 64-bit unsigned integer | */ + MAV_PARAM_TYPE_INT64=8, /* 64-bit signed integer | */ + MAV_PARAM_TYPE_REAL32=9, /* 32-bit floating-point | */ + MAV_PARAM_TYPE_REAL64=10, /* 64-bit floating-point | */ + MAV_PARAM_TYPE_ENUM_END=11, /* | */ +} MAV_PARAM_TYPE; +#endif + +/** @brief result from a mavlink command */ +#ifndef HAVE_ENUM_MAV_RESULT +#define HAVE_ENUM_MAV_RESULT +typedef enum MAV_RESULT +{ + MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */ + MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */ + MAV_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */ + MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */ + MAV_RESULT_FAILED=4, /* Command executed, but failed | */ + MAV_RESULT_ENUM_END=5, /* | */ +} MAV_RESULT; +#endif + +/** @brief result in a mavlink mission ack */ +#ifndef HAVE_ENUM_MAV_MISSION_RESULT +#define HAVE_ENUM_MAV_MISSION_RESULT +typedef enum MAV_MISSION_RESULT +{ + MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */ + MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */ + MAV_MISSION_UNSUPPORTED_FRAME=2, /* coordinate frame is not supported | */ + MAV_MISSION_UNSUPPORTED=3, /* command is not supported | */ + MAV_MISSION_NO_SPACE=4, /* mission item exceeds storage space | */ + MAV_MISSION_INVALID=5, /* one of the parameters has an invalid value | */ + MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value | */ + MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value | */ + MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value | */ + MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value | */ + MAV_MISSION_INVALID_PARAM5_X=10, /* x/param5 has an invalid value | */ + MAV_MISSION_INVALID_PARAM6_Y=11, /* y/param6 has an invalid value | */ + MAV_MISSION_INVALID_PARAM7=12, /* param7 has an invalid value | */ + MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */ + MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */ + MAV_MISSION_RESULT_ENUM_END=15, /* | */ +} MAV_MISSION_RESULT; +#endif + +/** @brief Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. */ +#ifndef HAVE_ENUM_MAV_SEVERITY +#define HAVE_ENUM_MAV_SEVERITY +typedef enum MAV_SEVERITY +{ + MAV_SEVERITY_EMERGENCY=0, /* System is unusable. This is a "panic" condition. | */ + MAV_SEVERITY_ALERT=1, /* Action should be taken immediately. Indicates error in non-critical systems. | */ + MAV_SEVERITY_CRITICAL=2, /* Action must be taken immediately. Indicates failure in a primary system. | */ + MAV_SEVERITY_ERROR=3, /* Indicates an error in secondary/redundant systems. | */ + MAV_SEVERITY_WARNING=4, /* Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | */ + MAV_SEVERITY_NOTICE=5, /* An unusual event has occured, though not an error condition. This should be investigated for the root cause. | */ + MAV_SEVERITY_INFO=6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */ + MAV_SEVERITY_DEBUG=7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */ + MAV_SEVERITY_ENUM_END=8, /* | */ +} MAV_SEVERITY; +#endif + +/** @brief Power supply status flags (bitmask) */ +#ifndef HAVE_ENUM_MAV_POWER_STATUS +#define HAVE_ENUM_MAV_POWER_STATUS +typedef enum MAV_POWER_STATUS +{ + MAV_POWER_STATUS_BRICK_VALID=1, /* main brick power supply valid | */ + MAV_POWER_STATUS_SERVO_VALID=2, /* main servo power supply valid for FMU | */ + MAV_POWER_STATUS_USB_CONNECTED=4, /* USB power is connected | */ + MAV_POWER_STATUS_PERIPH_OVERCURRENT=8, /* peripheral supply is in over-current state | */ + MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT=16, /* hi-power peripheral supply is in over-current state | */ + MAV_POWER_STATUS_CHANGED=32, /* Power status has changed since boot | */ + MAV_POWER_STATUS_ENUM_END=33, /* | */ +} MAV_POWER_STATUS; +#endif + +/** @brief SERIAL_CONTROL device types */ +#ifndef HAVE_ENUM_SERIAL_CONTROL_DEV +#define HAVE_ENUM_SERIAL_CONTROL_DEV +typedef enum SERIAL_CONTROL_DEV +{ + SERIAL_CONTROL_DEV_TELEM1=0, /* First telemetry port | */ + SERIAL_CONTROL_DEV_TELEM2=1, /* Second telemetry port | */ + SERIAL_CONTROL_DEV_GPS1=2, /* First GPS port | */ + SERIAL_CONTROL_DEV_GPS2=3, /* Second GPS port | */ + SERIAL_CONTROL_DEV_SHELL=10, /* system shell | */ + SERIAL_CONTROL_DEV_ENUM_END=11, /* | */ +} SERIAL_CONTROL_DEV; +#endif + +/** @brief SERIAL_CONTROL flags (bitmask) */ +#ifndef HAVE_ENUM_SERIAL_CONTROL_FLAG +#define HAVE_ENUM_SERIAL_CONTROL_FLAG +typedef enum SERIAL_CONTROL_FLAG +{ + SERIAL_CONTROL_FLAG_REPLY=1, /* Set if this is a reply | */ + SERIAL_CONTROL_FLAG_RESPOND=2, /* Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message | */ + SERIAL_CONTROL_FLAG_EXCLUSIVE=4, /* Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set | */ + SERIAL_CONTROL_FLAG_BLOCKING=8, /* Block on writes to the serial port | */ + SERIAL_CONTROL_FLAG_MULTI=16, /* Send multiple replies until port is drained | */ + SERIAL_CONTROL_FLAG_ENUM_END=17, /* | */ +} SERIAL_CONTROL_FLAG; +#endif + +/** @brief Enumeration of distance sensor types */ +#ifndef HAVE_ENUM_MAV_DISTANCE_SENSOR +#define HAVE_ENUM_MAV_DISTANCE_SENSOR +typedef enum MAV_DISTANCE_SENSOR +{ + MAV_DISTANCE_SENSOR_LASER=0, /* Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units | */ + MAV_DISTANCE_SENSOR_ULTRASOUND=1, /* Ultrasound rangefinder, e.g. MaxBotix units | */ + MAV_DISTANCE_SENSOR_INFRARED=2, /* Infrared rangefinder, e.g. Sharp units | */ + MAV_DISTANCE_SENSOR_ENUM_END=3, /* | */ +} MAV_DISTANCE_SENSOR; +#endif + +/** @brief Enumeration of sensor orientation, according to its rotations */ +#ifndef HAVE_ENUM_MAV_SENSOR_ORIENTATION +#define HAVE_ENUM_MAV_SENSOR_ORIENTATION +typedef enum MAV_SENSOR_ORIENTATION +{ + MAV_SENSOR_ROTATION_NONE=0, /* Roll: 0, Pitch: 0, Yaw: 0 | */ + MAV_SENSOR_ROTATION_YAW_45=1, /* Roll: 0, Pitch: 0, Yaw: 45 | */ + MAV_SENSOR_ROTATION_YAW_90=2, /* Roll: 0, Pitch: 0, Yaw: 90 | */ + MAV_SENSOR_ROTATION_YAW_135=3, /* Roll: 0, Pitch: 0, Yaw: 135 | */ + MAV_SENSOR_ROTATION_YAW_180=4, /* Roll: 0, Pitch: 0, Yaw: 180 | */ + MAV_SENSOR_ROTATION_YAW_225=5, /* Roll: 0, Pitch: 0, Yaw: 225 | */ + MAV_SENSOR_ROTATION_YAW_270=6, /* Roll: 0, Pitch: 0, Yaw: 270 | */ + MAV_SENSOR_ROTATION_YAW_315=7, /* Roll: 0, Pitch: 0, Yaw: 315 | */ + MAV_SENSOR_ROTATION_ROLL_180=8, /* Roll: 180, Pitch: 0, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_180_YAW_45=9, /* Roll: 180, Pitch: 0, Yaw: 45 | */ + MAV_SENSOR_ROTATION_ROLL_180_YAW_90=10, /* Roll: 180, Pitch: 0, Yaw: 90 | */ + MAV_SENSOR_ROTATION_ROLL_180_YAW_135=11, /* Roll: 180, Pitch: 0, Yaw: 135 | */ + MAV_SENSOR_ROTATION_PITCH_180=12, /* Roll: 0, Pitch: 180, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_180_YAW_225=13, /* Roll: 180, Pitch: 0, Yaw: 225 | */ + MAV_SENSOR_ROTATION_ROLL_180_YAW_270=14, /* Roll: 180, Pitch: 0, Yaw: 270 | */ + MAV_SENSOR_ROTATION_ROLL_180_YAW_315=15, /* Roll: 180, Pitch: 0, Yaw: 315 | */ + MAV_SENSOR_ROTATION_ROLL_90=16, /* Roll: 90, Pitch: 0, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_90_YAW_45=17, /* Roll: 90, Pitch: 0, Yaw: 45 | */ + MAV_SENSOR_ROTATION_ROLL_90_YAW_90=18, /* Roll: 90, Pitch: 0, Yaw: 90 | */ + MAV_SENSOR_ROTATION_ROLL_90_YAW_135=19, /* Roll: 90, Pitch: 0, Yaw: 135 | */ + MAV_SENSOR_ROTATION_ROLL_270=20, /* Roll: 270, Pitch: 0, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_270_YAW_45=21, /* Roll: 270, Pitch: 0, Yaw: 45 | */ + MAV_SENSOR_ROTATION_ROLL_270_YAW_90=22, /* Roll: 270, Pitch: 0, Yaw: 90 | */ + MAV_SENSOR_ROTATION_ROLL_270_YAW_135=23, /* Roll: 270, Pitch: 0, Yaw: 135 | */ + MAV_SENSOR_ROTATION_PITCH_90=24, /* Roll: 0, Pitch: 90, Yaw: 0 | */ + MAV_SENSOR_ROTATION_PITCH_270=25, /* Roll: 0, Pitch: 270, Yaw: 0 | */ + MAV_SENSOR_ROTATION_PITCH_180_YAW_90=26, /* Roll: 0, Pitch: 180, Yaw: 90 | */ + MAV_SENSOR_ROTATION_PITCH_180_YAW_270=27, /* Roll: 0, Pitch: 180, Yaw: 270 | */ + MAV_SENSOR_ROTATION_ROLL_90_PITCH_90=28, /* Roll: 90, Pitch: 90, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_180_PITCH_90=29, /* Roll: 180, Pitch: 90, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_270_PITCH_90=30, /* Roll: 270, Pitch: 90, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_90_PITCH_180=31, /* Roll: 90, Pitch: 180, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_270_PITCH_180=32, /* Roll: 270, Pitch: 180, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_90_PITCH_270=33, /* Roll: 90, Pitch: 270, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_180_PITCH_270=34, /* Roll: 180, Pitch: 270, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_270_PITCH_270=35, /* Roll: 270, Pitch: 270, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90=36, /* Roll: 90, Pitch: 180, Yaw: 90 | */ + MAV_SENSOR_ROTATION_ROLL_90_YAW_270=37, /* Roll: 90, Pitch: 0, Yaw: 270 | */ + MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315=38, /* Roll: 315, Pitch: 315, Yaw: 315 | */ + MAV_SENSOR_ORIENTATION_ENUM_END=39, /* | */ +} MAV_SENSOR_ORIENTATION; +#endif + +/** @brief Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability. */ +#ifndef HAVE_ENUM_MAV_PROTOCOL_CAPABILITY +#define HAVE_ENUM_MAV_PROTOCOL_CAPABILITY +typedef enum MAV_PROTOCOL_CAPABILITY +{ + MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT=1, /* Autopilot supports MISSION float message type. | */ + MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT=2, /* Autopilot supports the new param float message type. | */ + MAV_PROTOCOL_CAPABILITY_MISSION_INT=4, /* Autopilot supports MISSION_INT scaled integer message type. | */ + MAV_PROTOCOL_CAPABILITY_COMMAND_INT=8, /* Autopilot supports COMMAND_INT scaled integer message type. | */ + MAV_PROTOCOL_CAPABILITY_PARAM_UNION=16, /* Autopilot supports the new param union message type. | */ + MAV_PROTOCOL_CAPABILITY_FTP=32, /* Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. | */ + MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET=64, /* Autopilot supports commanding attitude offboard. | */ + MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED=128, /* Autopilot supports commanding position and velocity targets in local NED frame. | */ + MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT=256, /* Autopilot supports commanding position and velocity targets in global scaled integers. | */ + MAV_PROTOCOL_CAPABILITY_TERRAIN=512, /* Autopilot supports terrain protocol / data handling. | */ + MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET=1024, /* Autopilot supports direct actuator control. | */ + MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION=2048, /* Autopilot supports the flight termination command. | */ + MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION=4096, /* Autopilot supports onboard compass calibration. | */ + MAV_PROTOCOL_CAPABILITY_ENUM_END=4097, /* | */ +} MAV_PROTOCOL_CAPABILITY; +#endif + +/** @brief Enumeration of estimator types */ +#ifndef HAVE_ENUM_MAV_ESTIMATOR_TYPE +#define HAVE_ENUM_MAV_ESTIMATOR_TYPE +typedef enum MAV_ESTIMATOR_TYPE +{ + MAV_ESTIMATOR_TYPE_NAIVE=1, /* This is a naive estimator without any real covariance feedback. | */ + MAV_ESTIMATOR_TYPE_VISION=2, /* Computer vision based estimate. Might be up to scale. | */ + MAV_ESTIMATOR_TYPE_VIO=3, /* Visual-inertial estimate. | */ + MAV_ESTIMATOR_TYPE_GPS=4, /* Plain GPS estimate. | */ + MAV_ESTIMATOR_TYPE_GPS_INS=5, /* Estimator integrating GPS and inertial sensing. | */ + MAV_ESTIMATOR_TYPE_ENUM_END=6, /* | */ +} MAV_ESTIMATOR_TYPE; +#endif + +/** @brief Enumeration of battery types */ +#ifndef HAVE_ENUM_MAV_BATTERY_TYPE +#define HAVE_ENUM_MAV_BATTERY_TYPE +typedef enum MAV_BATTERY_TYPE +{ + MAV_BATTERY_TYPE_UNKNOWN=0, /* Not specified. | */ + MAV_BATTERY_TYPE_LIPO=1, /* Lithium polymer battery | */ + MAV_BATTERY_TYPE_LIFE=2, /* Lithium-iron-phosphate battery | */ + MAV_BATTERY_TYPE_LION=3, /* Lithium-ION battery | */ + MAV_BATTERY_TYPE_NIMH=4, /* Nickel metal hydride battery | */ + MAV_BATTERY_TYPE_ENUM_END=5, /* | */ +} MAV_BATTERY_TYPE; +#endif + +/** @brief Enumeration of battery functions */ +#ifndef HAVE_ENUM_MAV_BATTERY_FUNCTION +#define HAVE_ENUM_MAV_BATTERY_FUNCTION +typedef enum MAV_BATTERY_FUNCTION +{ + MAV_BATTERY_FUNCTION_UNKNOWN=0, /* Battery function is unknown | */ + MAV_BATTERY_FUNCTION_ALL=1, /* Battery supports all flight systems | */ + MAV_BATTERY_FUNCTION_PROPULSION=2, /* Battery for the propulsion system | */ + MAV_BATTERY_FUNCTION_AVIONICS=3, /* Avionics battery | */ + MAV_BATTERY_TYPE_PAYLOAD=4, /* Payload battery | */ + MAV_BATTERY_FUNCTION_ENUM_END=5, /* | */ +} MAV_BATTERY_FUNCTION; +#endif + +/** @brief Enumeration of VTOL states */ +#ifndef HAVE_ENUM_MAV_VTOL_STATE +#define HAVE_ENUM_MAV_VTOL_STATE +typedef enum MAV_VTOL_STATE +{ + MAV_VTOL_STATE_UNDEFINED=0, /* MAV is not configured as VTOL | */ + MAV_VTOL_STATE_TRANSITION_TO_FW=1, /* VTOL is in transition from multicopter to fixed-wing | */ + MAV_VTOL_STATE_TRANSITION_TO_MC=2, /* VTOL is in transition from fixed-wing to multicopter | */ + MAV_VTOL_STATE_MC=3, /* VTOL is in multicopter state | */ + MAV_VTOL_STATE_FW=4, /* VTOL is in fixed-wing state | */ + MAV_VTOL_STATE_ENUM_END=5, /* | */ +} MAV_VTOL_STATE; +#endif + +/** @brief Enumeration of landed detector states */ +#ifndef HAVE_ENUM_MAV_LANDED_STATE +#define HAVE_ENUM_MAV_LANDED_STATE +typedef enum MAV_LANDED_STATE +{ + MAV_LANDED_STATE_UNDEFINED=0, /* MAV landed state is unknown | */ + MAV_LANDED_STATE_ON_GROUND=1, /* MAV is landed (on ground) | */ + MAV_LANDED_STATE_IN_AIR=2, /* MAV is in air | */ + MAV_LANDED_STATE_ENUM_END=3, /* | */ +} MAV_LANDED_STATE; +#endif + +/** @brief Enumeration of the ADSB altimeter types */ +#ifndef HAVE_ENUM_ADSB_ALTITUDE_TYPE +#define HAVE_ENUM_ADSB_ALTITUDE_TYPE +typedef enum ADSB_ALTITUDE_TYPE +{ + ADSB_ALTITUDE_TYPE_PRESSURE_QNH=0, /* Altitude reported from a Baro source using QNH reference | */ + ADSB_ALTITUDE_TYPE_GEOMETRIC=1, /* Altitude reported from a GNSS source | */ + ADSB_ALTITUDE_TYPE_ENUM_END=2, /* | */ +} ADSB_ALTITUDE_TYPE; +#endif + +/** @brief ADSB classification for the type of vehicle emitting the transponder signal */ +#ifndef HAVE_ENUM_ADSB_EMITTER_TYPE +#define HAVE_ENUM_ADSB_EMITTER_TYPE +typedef enum ADSB_EMITTER_TYPE +{ + ADSB_EMITTER_TYPE_NO_INFO=0, /* | */ + ADSB_EMITTER_TYPE_LIGHT=1, /* | */ + ADSB_EMITTER_TYPE_SMALL=2, /* | */ + ADSB_EMITTER_TYPE_LARGE=3, /* | */ + ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE=4, /* | */ + ADSB_EMITTER_TYPE_HEAVY=5, /* | */ + ADSB_EMITTER_TYPE_HIGHLY_MANUV=6, /* | */ + ADSB_EMITTER_TYPE_ROTOCRAFT=7, /* | */ + ADSB_EMITTER_TYPE_UNASSIGNED=8, /* | */ + ADSB_EMITTER_TYPE_GLIDER=9, /* | */ + ADSB_EMITTER_TYPE_LIGHTER_AIR=10, /* | */ + ADSB_EMITTER_TYPE_PARACHUTE=11, /* | */ + ADSB_EMITTER_TYPE_ULTRA_LIGHT=12, /* | */ + ADSB_EMITTER_TYPE_UNASSIGNED2=13, /* | */ + ADSB_EMITTER_TYPE_UAV=14, /* | */ + ADSB_EMITTER_TYPE_SPACE=15, /* | */ + ADSB_EMITTER_TYPE_UNASSGINED3=16, /* | */ + ADSB_EMITTER_TYPE_EMERGENCY_SURFACE=17, /* | */ + ADSB_EMITTER_TYPE_SERVICE_SURFACE=18, /* | */ + ADSB_EMITTER_TYPE_POINT_OBSTACLE=19, /* | */ + ADSB_EMITTER_TYPE_ENUM_END=20, /* | */ +} ADSB_EMITTER_TYPE; +#endif + +/** @brief These flags indicate status such as data validity of each data source. Set = data valid */ +#ifndef HAVE_ENUM_ADSB_FLAGS +#define HAVE_ENUM_ADSB_FLAGS +typedef enum ADSB_FLAGS +{ + ADSB_FLAGS_VALID_COORDS=1, /* | */ + ADSB_FLAGS_VALID_ALTITUDE=2, /* | */ + ADSB_FLAGS_VALID_HEADING=4, /* | */ + ADSB_FLAGS_VALID_VELOCITY=8, /* | */ + ADSB_FLAGS_VALID_CALLSIGN=16, /* | */ + ADSB_FLAGS_VALID_SQUAWK=32, /* | */ + ADSB_FLAGS_SIMULATED=64, /* | */ + ADSB_FLAGS_ENUM_END=65, /* | */ +} ADSB_FLAGS; +#endif + +/** @brief Bitmask of options for the MAV_CMD_DO_REPOSITION */ +#ifndef HAVE_ENUM_MAV_DO_REPOSITION_FLAGS +#define HAVE_ENUM_MAV_DO_REPOSITION_FLAGS +typedef enum MAV_DO_REPOSITION_FLAGS +{ + MAV_DO_REPOSITION_FLAGS_CHANGE_MODE=1, /* The aircraft should immediately transition into guided. This should not be set for follow me applications | */ + MAV_DO_REPOSITION_FLAGS_ENUM_END=2, /* | */ +} MAV_DO_REPOSITION_FLAGS; +#endif + +/** @brief Flags in EKF_STATUS message */ +#ifndef HAVE_ENUM_ESTIMATOR_STATUS_FLAGS +#define HAVE_ENUM_ESTIMATOR_STATUS_FLAGS +typedef enum ESTIMATOR_STATUS_FLAGS +{ + ESTIMATOR_ATTITUDE=1, /* True if the attitude estimate is good | */ + ESTIMATOR_VELOCITY_HORIZ=2, /* True if the horizontal velocity estimate is good | */ + ESTIMATOR_VELOCITY_VERT=4, /* True if the vertical velocity estimate is good | */ + ESTIMATOR_POS_HORIZ_REL=8, /* True if the horizontal position (relative) estimate is good | */ + ESTIMATOR_POS_HORIZ_ABS=16, /* True if the horizontal position (absolute) estimate is good | */ + ESTIMATOR_POS_VERT_ABS=32, /* True if the vertical position (absolute) estimate is good | */ + ESTIMATOR_POS_VERT_AGL=64, /* True if the vertical position (above ground) estimate is good | */ + ESTIMATOR_CONST_POS_MODE=128, /* True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) | */ + ESTIMATOR_PRED_POS_HORIZ_REL=256, /* True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate | */ + ESTIMATOR_PRED_POS_HORIZ_ABS=512, /* True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate | */ + ESTIMATOR_GPS_GLITCH=1024, /* True if the EKF has detected a GPS glitch | */ + ESTIMATOR_STATUS_FLAGS_ENUM_END=1025, /* | */ +} ESTIMATOR_STATUS_FLAGS; +#endif + + + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_heartbeat.h" +#include "./mavlink_msg_sys_status.h" +#include "./mavlink_msg_system_time.h" +#include "./mavlink_msg_ping.h" +#include "./mavlink_msg_change_operator_control.h" +#include "./mavlink_msg_change_operator_control_ack.h" +#include "./mavlink_msg_auth_key.h" +#include "./mavlink_msg_set_mode.h" +#include "./mavlink_msg_param_request_read.h" +#include "./mavlink_msg_param_request_list.h" +#include "./mavlink_msg_param_value.h" +#include "./mavlink_msg_param_set.h" +#include "./mavlink_msg_gps_raw_int.h" +#include "./mavlink_msg_gps_status.h" +#include "./mavlink_msg_scaled_imu.h" +#include "./mavlink_msg_raw_imu.h" +#include "./mavlink_msg_raw_pressure.h" +#include "./mavlink_msg_scaled_pressure.h" +#include "./mavlink_msg_attitude.h" +#include "./mavlink_msg_attitude_quaternion.h" +#include "./mavlink_msg_local_position_ned.h" +#include "./mavlink_msg_global_position_int.h" +#include "./mavlink_msg_rc_channels_scaled.h" +#include "./mavlink_msg_rc_channels_raw.h" +#include "./mavlink_msg_servo_output_raw.h" +#include "./mavlink_msg_mission_request_partial_list.h" +#include "./mavlink_msg_mission_write_partial_list.h" +#include "./mavlink_msg_mission_item.h" +#include "./mavlink_msg_mission_request.h" +#include "./mavlink_msg_mission_set_current.h" +#include "./mavlink_msg_mission_current.h" +#include "./mavlink_msg_mission_request_list.h" +#include "./mavlink_msg_mission_count.h" +#include "./mavlink_msg_mission_clear_all.h" +#include "./mavlink_msg_mission_item_reached.h" +#include "./mavlink_msg_mission_ack.h" +#include "./mavlink_msg_set_gps_global_origin.h" +#include "./mavlink_msg_gps_global_origin.h" +#include "./mavlink_msg_param_map_rc.h" +#include "./mavlink_msg_mission_request_int.h" +#include "./mavlink_msg_safety_set_allowed_area.h" +#include "./mavlink_msg_safety_allowed_area.h" +#include "./mavlink_msg_attitude_quaternion_cov.h" +#include "./mavlink_msg_nav_controller_output.h" +#include "./mavlink_msg_global_position_int_cov.h" +#include "./mavlink_msg_local_position_ned_cov.h" +#include "./mavlink_msg_rc_channels.h" +#include "./mavlink_msg_request_data_stream.h" +#include "./mavlink_msg_data_stream.h" +#include "./mavlink_msg_manual_control.h" +#include "./mavlink_msg_rc_channels_override.h" +#include "./mavlink_msg_mission_item_int.h" +#include "./mavlink_msg_vfr_hud.h" +#include "./mavlink_msg_command_int.h" +#include "./mavlink_msg_command_long.h" +#include "./mavlink_msg_command_ack.h" +#include "./mavlink_msg_manual_setpoint.h" +#include "./mavlink_msg_set_attitude_target.h" +#include "./mavlink_msg_attitude_target.h" +#include "./mavlink_msg_set_position_target_local_ned.h" +#include "./mavlink_msg_position_target_local_ned.h" +#include "./mavlink_msg_set_position_target_global_int.h" +#include "./mavlink_msg_position_target_global_int.h" +#include "./mavlink_msg_local_position_ned_system_global_offset.h" +#include "./mavlink_msg_hil_state.h" +#include "./mavlink_msg_hil_controls.h" +#include "./mavlink_msg_hil_rc_inputs_raw.h" +#include "./mavlink_msg_optical_flow.h" +#include "./mavlink_msg_global_vision_position_estimate.h" +#include "./mavlink_msg_vision_position_estimate.h" +#include "./mavlink_msg_vision_speed_estimate.h" +#include "./mavlink_msg_vicon_position_estimate.h" +#include "./mavlink_msg_highres_imu.h" +#include "./mavlink_msg_optical_flow_rad.h" +#include "./mavlink_msg_hil_sensor.h" +#include "./mavlink_msg_sim_state.h" +#include "./mavlink_msg_radio_status.h" +#include "./mavlink_msg_file_transfer_protocol.h" +#include "./mavlink_msg_timesync.h" +#include "./mavlink_msg_camera_trigger.h" +#include "./mavlink_msg_hil_gps.h" +#include "./mavlink_msg_hil_optical_flow.h" +#include "./mavlink_msg_hil_state_quaternion.h" +#include "./mavlink_msg_scaled_imu2.h" +#include "./mavlink_msg_log_request_list.h" +#include "./mavlink_msg_log_entry.h" +#include "./mavlink_msg_log_request_data.h" +#include "./mavlink_msg_log_data.h" +#include "./mavlink_msg_log_erase.h" +#include "./mavlink_msg_log_request_end.h" +#include "./mavlink_msg_gps_inject_data.h" +#include "./mavlink_msg_gps2_raw.h" +#include "./mavlink_msg_power_status.h" +#include "./mavlink_msg_serial_control.h" +#include "./mavlink_msg_gps_rtk.h" +#include "./mavlink_msg_gps2_rtk.h" +#include "./mavlink_msg_scaled_imu3.h" +#include "./mavlink_msg_data_transmission_handshake.h" +#include "./mavlink_msg_encapsulated_data.h" +#include "./mavlink_msg_distance_sensor.h" +#include "./mavlink_msg_terrain_request.h" +#include "./mavlink_msg_terrain_data.h" +#include "./mavlink_msg_terrain_check.h" +#include "./mavlink_msg_terrain_report.h" +#include "./mavlink_msg_scaled_pressure2.h" +#include "./mavlink_msg_att_pos_mocap.h" +#include "./mavlink_msg_set_actuator_control_target.h" +#include "./mavlink_msg_actuator_control_target.h" +#include "./mavlink_msg_altitude.h" +#include "./mavlink_msg_resource_request.h" +#include "./mavlink_msg_scaled_pressure3.h" +#include "./mavlink_msg_follow_target.h" +#include "./mavlink_msg_control_system_state.h" +#include "./mavlink_msg_battery_status.h" +#include "./mavlink_msg_autopilot_version.h" +#include "./mavlink_msg_landing_target.h" +#include "./mavlink_msg_estimator_status.h" +#include "./mavlink_msg_wind_cov.h" +#include "./mavlink_msg_vibration.h" +#include "./mavlink_msg_home_position.h" +#include "./mavlink_msg_set_home_position.h" +#include "./mavlink_msg_message_interval.h" +#include "./mavlink_msg_extended_sys_state.h" +#include "./mavlink_msg_adsb_vehicle.h" +#include "./mavlink_msg_v2_extension.h" +#include "./mavlink_msg_memory_vect.h" +#include "./mavlink_msg_debug_vect.h" +#include "./mavlink_msg_named_value_float.h" +#include "./mavlink_msg_named_value_int.h" +#include "./mavlink_msg_statustext.h" +#include "./mavlink_msg_debug.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // MAVLINK_COMMON_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink.h new file mode 100644 index 0000000..f92b2b2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink.h @@ -0,0 +1,27 @@ +/** @file + * @brief MAVLink comm protocol built from common.xml + * @see http://mavlink.org + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#ifndef MAVLINK_STX +#define MAVLINK_STX 254 +#endif + +#ifndef MAVLINK_ENDIAN +#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN +#endif + +#ifndef MAVLINK_ALIGNED_FIELDS +#define MAVLINK_ALIGNED_FIELDS 1 +#endif + +#ifndef MAVLINK_CRC_EXTRA +#define MAVLINK_CRC_EXTRA 1 +#endif + +#include "version.h" +#include "common.h" + +#endif // MAVLINK_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_actuator_control_target.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_actuator_control_target.h new file mode 100644 index 0000000..6b939bd --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_actuator_control_target.h @@ -0,0 +1,249 @@ +// MESSAGE ACTUATOR_CONTROL_TARGET PACKING + +#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET 140 + +typedef struct __mavlink_actuator_control_target_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/ + uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/ +} mavlink_actuator_control_target_t; + +#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN 41 +#define MAVLINK_MSG_ID_140_LEN 41 + +#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC 181 +#define MAVLINK_MSG_ID_140_CRC 181 + +#define MAVLINK_MSG_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS_LEN 8 + +#define MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET { \ + "ACTUATOR_CONTROL_TARGET", \ + 3, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \ + { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \ + { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \ + } \ +} + + +/** + * @brief Pack a actuator_control_target message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t group_mlx, const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_float_array(buf, 8, controls, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#else + mavlink_actuator_control_target_t packet; + packet.time_usec = time_usec; + packet.group_mlx = group_mlx; + mav_array_memcpy(packet.controls, controls, sizeof(float)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif +} + +/** + * @brief Pack a actuator_control_target message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t group_mlx,const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_float_array(buf, 8, controls, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#else + mavlink_actuator_control_target_t packet; + packet.time_usec = time_usec; + packet.group_mlx = group_mlx; + mav_array_memcpy(packet.controls, controls, sizeof(float)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif +} + +/** + * @brief Encode a actuator_control_target struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param actuator_control_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_actuator_control_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target) +{ + return mavlink_msg_actuator_control_target_pack(system_id, component_id, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); +} + +/** + * @brief Encode a actuator_control_target struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param actuator_control_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_actuator_control_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target) +{ + return mavlink_msg_actuator_control_target_pack_chan(system_id, component_id, chan, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); +} + +/** + * @brief Send a actuator_control_target message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_actuator_control_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_float_array(buf, 8, controls, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#else + mavlink_actuator_control_target_t packet; + packet.time_usec = time_usec; + packet.group_mlx = group_mlx; + mav_array_memcpy(packet.controls, controls, sizeof(float)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_actuator_control_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_float_array(buf, 8, controls, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#else + mavlink_actuator_control_target_t *packet = (mavlink_actuator_control_target_t *)msgbuf; + packet->time_usec = time_usec; + packet->group_mlx = group_mlx; + mav_array_memcpy(packet->controls, controls, sizeof(float)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ACTUATOR_CONTROL_TARGET UNPACKING + + +/** + * @brief Get field time_usec from actuator_control_target message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_actuator_control_target_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field group_mlx from actuator_control_target message + * + * @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + */ +static inline uint8_t mavlink_msg_actuator_control_target_get_group_mlx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 40); +} + +/** + * @brief Get field controls from actuator_control_target message + * + * @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + */ +static inline uint16_t mavlink_msg_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls) +{ + return _MAV_RETURN_float_array(msg, controls, 8, 8); +} + +/** + * @brief Decode a actuator_control_target message into a struct + * + * @param msg The message to decode + * @param actuator_control_target C-struct to decode the message contents into + */ +static inline void mavlink_msg_actuator_control_target_decode(const mavlink_message_t* msg, mavlink_actuator_control_target_t* actuator_control_target) +{ +#if MAVLINK_NEED_BYTE_SWAP + actuator_control_target->time_usec = mavlink_msg_actuator_control_target_get_time_usec(msg); + mavlink_msg_actuator_control_target_get_controls(msg, actuator_control_target->controls); + actuator_control_target->group_mlx = mavlink_msg_actuator_control_target_get_group_mlx(msg); +#else + memcpy(actuator_control_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_adsb_vehicle.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_adsb_vehicle.h new file mode 100644 index 0000000..9d1d40b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_adsb_vehicle.h @@ -0,0 +1,489 @@ +// MESSAGE ADSB_VEHICLE PACKING + +#define MAVLINK_MSG_ID_ADSB_VEHICLE 246 + +typedef struct __mavlink_adsb_vehicle_t +{ + uint32_t ICAO_address; /*< ICAO address*/ + int32_t lat; /*< Latitude, expressed as degrees * 1E7*/ + int32_t lon; /*< Longitude, expressed as degrees * 1E7*/ + int32_t altitude; /*< Altitude(ASL) in millimeters*/ + uint16_t heading; /*< Course over ground in centidegrees*/ + uint16_t hor_velocity; /*< The horizontal velocity in centimeters/second*/ + int16_t ver_velocity; /*< The vertical velocity in centimeters/second, positive is up*/ + uint16_t flags; /*< Flags to indicate various statuses including valid data fields*/ + uint16_t squawk; /*< Squawk code*/ + uint8_t altitude_type; /*< Type from ADSB_ALTITUDE_TYPE enum*/ + char callsign[9]; /*< The callsign, 8+null*/ + uint8_t emitter_type; /*< Type from ADSB_EMITTER_TYPE enum*/ + uint8_t tslc; /*< Time since last communication in seconds*/ +} mavlink_adsb_vehicle_t; + +#define MAVLINK_MSG_ID_ADSB_VEHICLE_LEN 38 +#define MAVLINK_MSG_ID_246_LEN 38 + +#define MAVLINK_MSG_ID_ADSB_VEHICLE_CRC 184 +#define MAVLINK_MSG_ID_246_CRC 184 + +#define MAVLINK_MSG_ADSB_VEHICLE_FIELD_CALLSIGN_LEN 9 + +#define MAVLINK_MESSAGE_INFO_ADSB_VEHICLE { \ + "ADSB_VEHICLE", \ + 13, \ + { { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \ + { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \ + { "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \ + { "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \ + { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \ + { "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \ + { "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \ + { "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \ + { "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \ + } \ +} + + +/** + * @brief Pack a adsb_vehicle message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param ICAO_address ICAO address + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param altitude_type Type from ADSB_ALTITUDE_TYPE enum + * @param altitude Altitude(ASL) in millimeters + * @param heading Course over ground in centidegrees + * @param hor_velocity The horizontal velocity in centimeters/second + * @param ver_velocity The vertical velocity in centimeters/second, positive is up + * @param callsign The callsign, 8+null + * @param emitter_type Type from ADSB_EMITTER_TYPE enum + * @param tslc Time since last communication in seconds + * @param flags Flags to indicate various statuses including valid data fields + * @param squawk Squawk code + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_adsb_vehicle_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN]; + _mav_put_uint32_t(buf, 0, ICAO_address); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, altitude); + _mav_put_uint16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, hor_velocity); + _mav_put_int16_t(buf, 20, ver_velocity); + _mav_put_uint16_t(buf, 22, flags); + _mav_put_uint16_t(buf, 24, squawk); + _mav_put_uint8_t(buf, 26, altitude_type); + _mav_put_uint8_t(buf, 36, emitter_type); + _mav_put_uint8_t(buf, 37, tslc); + _mav_put_char_array(buf, 27, callsign, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#else + mavlink_adsb_vehicle_t packet; + packet.ICAO_address = ICAO_address; + packet.lat = lat; + packet.lon = lon; + packet.altitude = altitude; + packet.heading = heading; + packet.hor_velocity = hor_velocity; + packet.ver_velocity = ver_velocity; + packet.flags = flags; + packet.squawk = squawk; + packet.altitude_type = altitude_type; + packet.emitter_type = emitter_type; + packet.tslc = tslc; + mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ADSB_VEHICLE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif +} + +/** + * @brief Pack a adsb_vehicle message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param ICAO_address ICAO address + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param altitude_type Type from ADSB_ALTITUDE_TYPE enum + * @param altitude Altitude(ASL) in millimeters + * @param heading Course over ground in centidegrees + * @param hor_velocity The horizontal velocity in centimeters/second + * @param ver_velocity The vertical velocity in centimeters/second, positive is up + * @param callsign The callsign, 8+null + * @param emitter_type Type from ADSB_EMITTER_TYPE enum + * @param tslc Time since last communication in seconds + * @param flags Flags to indicate various statuses including valid data fields + * @param squawk Squawk code + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_adsb_vehicle_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t ICAO_address,int32_t lat,int32_t lon,uint8_t altitude_type,int32_t altitude,uint16_t heading,uint16_t hor_velocity,int16_t ver_velocity,const char *callsign,uint8_t emitter_type,uint8_t tslc,uint16_t flags,uint16_t squawk) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN]; + _mav_put_uint32_t(buf, 0, ICAO_address); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, altitude); + _mav_put_uint16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, hor_velocity); + _mav_put_int16_t(buf, 20, ver_velocity); + _mav_put_uint16_t(buf, 22, flags); + _mav_put_uint16_t(buf, 24, squawk); + _mav_put_uint8_t(buf, 26, altitude_type); + _mav_put_uint8_t(buf, 36, emitter_type); + _mav_put_uint8_t(buf, 37, tslc); + _mav_put_char_array(buf, 27, callsign, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#else + mavlink_adsb_vehicle_t packet; + packet.ICAO_address = ICAO_address; + packet.lat = lat; + packet.lon = lon; + packet.altitude = altitude; + packet.heading = heading; + packet.hor_velocity = hor_velocity; + packet.ver_velocity = ver_velocity; + packet.flags = flags; + packet.squawk = squawk; + packet.altitude_type = altitude_type; + packet.emitter_type = emitter_type; + packet.tslc = tslc; + mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ADSB_VEHICLE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif +} + +/** + * @brief Encode a adsb_vehicle struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param adsb_vehicle C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_adsb_vehicle_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adsb_vehicle_t* adsb_vehicle) +{ + return mavlink_msg_adsb_vehicle_pack(system_id, component_id, msg, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk); +} + +/** + * @brief Encode a adsb_vehicle struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param adsb_vehicle C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_adsb_vehicle_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adsb_vehicle_t* adsb_vehicle) +{ + return mavlink_msg_adsb_vehicle_pack_chan(system_id, component_id, chan, msg, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk); +} + +/** + * @brief Send a adsb_vehicle message + * @param chan MAVLink channel to send the message + * + * @param ICAO_address ICAO address + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param altitude_type Type from ADSB_ALTITUDE_TYPE enum + * @param altitude Altitude(ASL) in millimeters + * @param heading Course over ground in centidegrees + * @param hor_velocity The horizontal velocity in centimeters/second + * @param ver_velocity The vertical velocity in centimeters/second, positive is up + * @param callsign The callsign, 8+null + * @param emitter_type Type from ADSB_EMITTER_TYPE enum + * @param tslc Time since last communication in seconds + * @param flags Flags to indicate various statuses including valid data fields + * @param squawk Squawk code + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_adsb_vehicle_send(mavlink_channel_t chan, uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN]; + _mav_put_uint32_t(buf, 0, ICAO_address); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, altitude); + _mav_put_uint16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, hor_velocity); + _mav_put_int16_t(buf, 20, ver_velocity); + _mav_put_uint16_t(buf, 22, flags); + _mav_put_uint16_t(buf, 24, squawk); + _mav_put_uint8_t(buf, 26, altitude_type); + _mav_put_uint8_t(buf, 36, emitter_type); + _mav_put_uint8_t(buf, 37, tslc); + _mav_put_char_array(buf, 27, callsign, 9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif +#else + mavlink_adsb_vehicle_t packet; + packet.ICAO_address = ICAO_address; + packet.lat = lat; + packet.lon = lon; + packet.altitude = altitude; + packet.heading = heading; + packet.hor_velocity = hor_velocity; + packet.ver_velocity = ver_velocity; + packet.flags = flags; + packet.squawk = squawk; + packet.altitude_type = altitude_type; + packet.emitter_type = emitter_type; + packet.tslc = tslc; + mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)&packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)&packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ADSB_VEHICLE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_adsb_vehicle_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, ICAO_address); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, altitude); + _mav_put_uint16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, hor_velocity); + _mav_put_int16_t(buf, 20, ver_velocity); + _mav_put_uint16_t(buf, 22, flags); + _mav_put_uint16_t(buf, 24, squawk); + _mav_put_uint8_t(buf, 26, altitude_type); + _mav_put_uint8_t(buf, 36, emitter_type); + _mav_put_uint8_t(buf, 37, tslc); + _mav_put_char_array(buf, 27, callsign, 9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif +#else + mavlink_adsb_vehicle_t *packet = (mavlink_adsb_vehicle_t *)msgbuf; + packet->ICAO_address = ICAO_address; + packet->lat = lat; + packet->lon = lon; + packet->altitude = altitude; + packet->heading = heading; + packet->hor_velocity = hor_velocity; + packet->ver_velocity = ver_velocity; + packet->flags = flags; + packet->squawk = squawk; + packet->altitude_type = altitude_type; + packet->emitter_type = emitter_type; + packet->tslc = tslc; + mav_array_memcpy(packet->callsign, callsign, sizeof(char)*9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ADSB_VEHICLE UNPACKING + + +/** + * @brief Get field ICAO_address from adsb_vehicle message + * + * @return ICAO address + */ +static inline uint32_t mavlink_msg_adsb_vehicle_get_ICAO_address(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field lat from adsb_vehicle message + * + * @return Latitude, expressed as degrees * 1E7 + */ +static inline int32_t mavlink_msg_adsb_vehicle_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field lon from adsb_vehicle message + * + * @return Longitude, expressed as degrees * 1E7 + */ +static inline int32_t mavlink_msg_adsb_vehicle_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field altitude_type from adsb_vehicle message + * + * @return Type from ADSB_ALTITUDE_TYPE enum + */ +static inline uint8_t mavlink_msg_adsb_vehicle_get_altitude_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 26); +} + +/** + * @brief Get field altitude from adsb_vehicle message + * + * @return Altitude(ASL) in millimeters + */ +static inline int32_t mavlink_msg_adsb_vehicle_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field heading from adsb_vehicle message + * + * @return Course over ground in centidegrees + */ +static inline uint16_t mavlink_msg_adsb_vehicle_get_heading(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field hor_velocity from adsb_vehicle message + * + * @return The horizontal velocity in centimeters/second + */ +static inline uint16_t mavlink_msg_adsb_vehicle_get_hor_velocity(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field ver_velocity from adsb_vehicle message + * + * @return The vertical velocity in centimeters/second, positive is up + */ +static inline int16_t mavlink_msg_adsb_vehicle_get_ver_velocity(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field callsign from adsb_vehicle message + * + * @return The callsign, 8+null + */ +static inline uint16_t mavlink_msg_adsb_vehicle_get_callsign(const mavlink_message_t* msg, char *callsign) +{ + return _MAV_RETURN_char_array(msg, callsign, 9, 27); +} + +/** + * @brief Get field emitter_type from adsb_vehicle message + * + * @return Type from ADSB_EMITTER_TYPE enum + */ +static inline uint8_t mavlink_msg_adsb_vehicle_get_emitter_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Get field tslc from adsb_vehicle message + * + * @return Time since last communication in seconds + */ +static inline uint8_t mavlink_msg_adsb_vehicle_get_tslc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 37); +} + +/** + * @brief Get field flags from adsb_vehicle message + * + * @return Flags to indicate various statuses including valid data fields + */ +static inline uint16_t mavlink_msg_adsb_vehicle_get_flags(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field squawk from adsb_vehicle message + * + * @return Squawk code + */ +static inline uint16_t mavlink_msg_adsb_vehicle_get_squawk(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Decode a adsb_vehicle message into a struct + * + * @param msg The message to decode + * @param adsb_vehicle C-struct to decode the message contents into + */ +static inline void mavlink_msg_adsb_vehicle_decode(const mavlink_message_t* msg, mavlink_adsb_vehicle_t* adsb_vehicle) +{ +#if MAVLINK_NEED_BYTE_SWAP + adsb_vehicle->ICAO_address = mavlink_msg_adsb_vehicle_get_ICAO_address(msg); + adsb_vehicle->lat = mavlink_msg_adsb_vehicle_get_lat(msg); + adsb_vehicle->lon = mavlink_msg_adsb_vehicle_get_lon(msg); + adsb_vehicle->altitude = mavlink_msg_adsb_vehicle_get_altitude(msg); + adsb_vehicle->heading = mavlink_msg_adsb_vehicle_get_heading(msg); + adsb_vehicle->hor_velocity = mavlink_msg_adsb_vehicle_get_hor_velocity(msg); + adsb_vehicle->ver_velocity = mavlink_msg_adsb_vehicle_get_ver_velocity(msg); + adsb_vehicle->flags = mavlink_msg_adsb_vehicle_get_flags(msg); + adsb_vehicle->squawk = mavlink_msg_adsb_vehicle_get_squawk(msg); + adsb_vehicle->altitude_type = mavlink_msg_adsb_vehicle_get_altitude_type(msg); + mavlink_msg_adsb_vehicle_get_callsign(msg, adsb_vehicle->callsign); + adsb_vehicle->emitter_type = mavlink_msg_adsb_vehicle_get_emitter_type(msg); + adsb_vehicle->tslc = mavlink_msg_adsb_vehicle_get_tslc(msg); +#else + memcpy(adsb_vehicle, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_altitude.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_altitude.h new file mode 100644 index 0000000..2ed8cb8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_altitude.h @@ -0,0 +1,353 @@ +// MESSAGE ALTITUDE PACKING + +#define MAVLINK_MSG_ID_ALTITUDE 141 + +typedef struct __mavlink_altitude_t +{ + uint64_t time_usec; /*< Timestamp (milliseconds since system boot)*/ + float altitude_monotonic; /*< This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.*/ + float altitude_amsl; /*< This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.*/ + float altitude_local; /*< This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.*/ + float altitude_relative; /*< This is the altitude above the home position. It resets on each change of the current home position.*/ + float altitude_terrain; /*< This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.*/ + float bottom_clearance; /*< This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.*/ +} mavlink_altitude_t; + +#define MAVLINK_MSG_ID_ALTITUDE_LEN 32 +#define MAVLINK_MSG_ID_141_LEN 32 + +#define MAVLINK_MSG_ID_ALTITUDE_CRC 47 +#define MAVLINK_MSG_ID_141_CRC 47 + + + +#define MAVLINK_MESSAGE_INFO_ALTITUDE { \ + "ALTITUDE", \ + 7, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_altitude_t, time_usec) }, \ + { "altitude_monotonic", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_altitude_t, altitude_monotonic) }, \ + { "altitude_amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_altitude_t, altitude_amsl) }, \ + { "altitude_local", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_altitude_t, altitude_local) }, \ + { "altitude_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_altitude_t, altitude_relative) }, \ + { "altitude_terrain", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_altitude_t, altitude_terrain) }, \ + { "bottom_clearance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_altitude_t, bottom_clearance) }, \ + } \ +} + + +/** + * @brief Pack a altitude message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (milliseconds since system boot) + * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. + * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position. + * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ALTITUDE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, altitude_monotonic); + _mav_put_float(buf, 12, altitude_amsl); + _mav_put_float(buf, 16, altitude_local); + _mav_put_float(buf, 20, altitude_relative); + _mav_put_float(buf, 24, altitude_terrain); + _mav_put_float(buf, 28, bottom_clearance); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN); +#else + mavlink_altitude_t packet; + packet.time_usec = time_usec; + packet.altitude_monotonic = altitude_monotonic; + packet.altitude_amsl = altitude_amsl; + packet.altitude_local = altitude_local; + packet.altitude_relative = altitude_relative; + packet.altitude_terrain = altitude_terrain; + packet.bottom_clearance = bottom_clearance; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ALTITUDE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif +} + +/** + * @brief Pack a altitude message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (milliseconds since system boot) + * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. + * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position. + * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float altitude_monotonic,float altitude_amsl,float altitude_local,float altitude_relative,float altitude_terrain,float bottom_clearance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ALTITUDE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, altitude_monotonic); + _mav_put_float(buf, 12, altitude_amsl); + _mav_put_float(buf, 16, altitude_local); + _mav_put_float(buf, 20, altitude_relative); + _mav_put_float(buf, 24, altitude_terrain); + _mav_put_float(buf, 28, bottom_clearance); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN); +#else + mavlink_altitude_t packet; + packet.time_usec = time_usec; + packet.altitude_monotonic = altitude_monotonic; + packet.altitude_amsl = altitude_amsl; + packet.altitude_local = altitude_local; + packet.altitude_relative = altitude_relative; + packet.altitude_terrain = altitude_terrain; + packet.bottom_clearance = bottom_clearance; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ALTITUDE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif +} + +/** + * @brief Encode a altitude struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param altitude C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_altitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_altitude_t* altitude) +{ + return mavlink_msg_altitude_pack(system_id, component_id, msg, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance); +} + +/** + * @brief Encode a altitude struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param altitude C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_altitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_altitude_t* altitude) +{ + return mavlink_msg_altitude_pack_chan(system_id, component_id, chan, msg, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance); +} + +/** + * @brief Send a altitude message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (milliseconds since system boot) + * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. + * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position. + * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_altitude_send(mavlink_channel_t chan, uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ALTITUDE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, altitude_monotonic); + _mav_put_float(buf, 12, altitude_amsl); + _mav_put_float(buf, 16, altitude_local); + _mav_put_float(buf, 20, altitude_relative); + _mav_put_float(buf, 24, altitude_terrain); + _mav_put_float(buf, 28, bottom_clearance); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif +#else + mavlink_altitude_t packet; + packet.time_usec = time_usec; + packet.altitude_monotonic = altitude_monotonic; + packet.altitude_amsl = altitude_amsl; + packet.altitude_local = altitude_local; + packet.altitude_relative = altitude_relative; + packet.altitude_terrain = altitude_terrain; + packet.bottom_clearance = bottom_clearance; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ALTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_altitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, altitude_monotonic); + _mav_put_float(buf, 12, altitude_amsl); + _mav_put_float(buf, 16, altitude_local); + _mav_put_float(buf, 20, altitude_relative); + _mav_put_float(buf, 24, altitude_terrain); + _mav_put_float(buf, 28, bottom_clearance); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif +#else + mavlink_altitude_t *packet = (mavlink_altitude_t *)msgbuf; + packet->time_usec = time_usec; + packet->altitude_monotonic = altitude_monotonic; + packet->altitude_amsl = altitude_amsl; + packet->altitude_local = altitude_local; + packet->altitude_relative = altitude_relative; + packet->altitude_terrain = altitude_terrain; + packet->bottom_clearance = bottom_clearance; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)packet, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)packet, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ALTITUDE UNPACKING + + +/** + * @brief Get field time_usec from altitude message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint64_t mavlink_msg_altitude_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field altitude_monotonic from altitude message + * + * @return This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + */ +static inline float mavlink_msg_altitude_get_altitude_monotonic(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field altitude_amsl from altitude message + * + * @return This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. + */ +static inline float mavlink_msg_altitude_get_altitude_amsl(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field altitude_local from altitude message + * + * @return This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + */ +static inline float mavlink_msg_altitude_get_altitude_local(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field altitude_relative from altitude message + * + * @return This is the altitude above the home position. It resets on each change of the current home position. + */ +static inline float mavlink_msg_altitude_get_altitude_relative(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field altitude_terrain from altitude message + * + * @return This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + */ +static inline float mavlink_msg_altitude_get_altitude_terrain(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field bottom_clearance from altitude message + * + * @return This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + */ +static inline float mavlink_msg_altitude_get_bottom_clearance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a altitude message into a struct + * + * @param msg The message to decode + * @param altitude C-struct to decode the message contents into + */ +static inline void mavlink_msg_altitude_decode(const mavlink_message_t* msg, mavlink_altitude_t* altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP + altitude->time_usec = mavlink_msg_altitude_get_time_usec(msg); + altitude->altitude_monotonic = mavlink_msg_altitude_get_altitude_monotonic(msg); + altitude->altitude_amsl = mavlink_msg_altitude_get_altitude_amsl(msg); + altitude->altitude_local = mavlink_msg_altitude_get_altitude_local(msg); + altitude->altitude_relative = mavlink_msg_altitude_get_altitude_relative(msg); + altitude->altitude_terrain = mavlink_msg_altitude_get_altitude_terrain(msg); + altitude->bottom_clearance = mavlink_msg_altitude_get_bottom_clearance(msg); +#else + memcpy(altitude, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_att_pos_mocap.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_att_pos_mocap.h new file mode 100644 index 0000000..581a243 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_att_pos_mocap.h @@ -0,0 +1,297 @@ +// MESSAGE ATT_POS_MOCAP PACKING + +#define MAVLINK_MSG_ID_ATT_POS_MOCAP 138 + +typedef struct __mavlink_att_pos_mocap_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ + float x; /*< X position in meters (NED)*/ + float y; /*< Y position in meters (NED)*/ + float z; /*< Z position in meters (NED)*/ +} mavlink_att_pos_mocap_t; + +#define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN 36 +#define MAVLINK_MSG_ID_138_LEN 36 + +#define MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC 109 +#define MAVLINK_MSG_ID_138_CRC 109 + +#define MAVLINK_MSG_ATT_POS_MOCAP_FIELD_Q_LEN 4 + +#define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \ + "ATT_POS_MOCAP", \ + 5, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \ + { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \ + } \ +} + + +/** + * @brief Pack a att_pos_mocap message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param x X position in meters (NED) + * @param y Y position in meters (NED) + * @param z Z position in meters (NED) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, const float *q, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, x); + _mav_put_float(buf, 28, y); + _mav_put_float(buf, 32, z); + _mav_put_float_array(buf, 8, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#else + mavlink_att_pos_mocap_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif +} + +/** + * @brief Pack a att_pos_mocap message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param x X position in meters (NED) + * @param y Y position in meters (NED) + * @param z Z position in meters (NED) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_att_pos_mocap_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,const float *q,float x,float y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, x); + _mav_put_float(buf, 28, y); + _mav_put_float(buf, 32, z); + _mav_put_float_array(buf, 8, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#else + mavlink_att_pos_mocap_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif +} + +/** + * @brief Encode a att_pos_mocap struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param att_pos_mocap C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_att_pos_mocap_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap) +{ + return mavlink_msg_att_pos_mocap_pack(system_id, component_id, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z); +} + +/** + * @brief Encode a att_pos_mocap struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param att_pos_mocap C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_att_pos_mocap_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap) +{ + return mavlink_msg_att_pos_mocap_pack_chan(system_id, component_id, chan, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z); +} + +/** + * @brief Send a att_pos_mocap message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param x X position in meters (NED) + * @param y Y position in meters (NED) + * @param z Z position in meters (NED) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_att_pos_mocap_send(mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, x); + _mav_put_float(buf, 28, y); + _mav_put_float(buf, 32, z); + _mav_put_float_array(buf, 8, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif +#else + mavlink_att_pos_mocap_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + mav_array_memcpy(packet.q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)&packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)&packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_att_pos_mocap_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, x); + _mav_put_float(buf, 28, y); + _mav_put_float(buf, 32, z); + _mav_put_float_array(buf, 8, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif +#else + mavlink_att_pos_mocap_t *packet = (mavlink_att_pos_mocap_t *)msgbuf; + packet->time_usec = time_usec; + packet->x = x; + packet->y = y; + packet->z = z; + mav_array_memcpy(packet->q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ATT_POS_MOCAP UNPACKING + + +/** + * @brief Get field time_usec from att_pos_mocap message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_att_pos_mocap_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field q from att_pos_mocap message + * + * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + */ +static inline uint16_t mavlink_msg_att_pos_mocap_get_q(const mavlink_message_t* msg, float *q) +{ + return _MAV_RETURN_float_array(msg, q, 4, 8); +} + +/** + * @brief Get field x from att_pos_mocap message + * + * @return X position in meters (NED) + */ +static inline float mavlink_msg_att_pos_mocap_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field y from att_pos_mocap message + * + * @return Y position in meters (NED) + */ +static inline float mavlink_msg_att_pos_mocap_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field z from att_pos_mocap message + * + * @return Z position in meters (NED) + */ +static inline float mavlink_msg_att_pos_mocap_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Decode a att_pos_mocap message into a struct + * + * @param msg The message to decode + * @param att_pos_mocap C-struct to decode the message contents into + */ +static inline void mavlink_msg_att_pos_mocap_decode(const mavlink_message_t* msg, mavlink_att_pos_mocap_t* att_pos_mocap) +{ +#if MAVLINK_NEED_BYTE_SWAP + att_pos_mocap->time_usec = mavlink_msg_att_pos_mocap_get_time_usec(msg); + mavlink_msg_att_pos_mocap_get_q(msg, att_pos_mocap->q); + att_pos_mocap->x = mavlink_msg_att_pos_mocap_get_x(msg); + att_pos_mocap->y = mavlink_msg_att_pos_mocap_get_y(msg); + att_pos_mocap->z = mavlink_msg_att_pos_mocap_get_z(msg); +#else + memcpy(att_pos_mocap, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_attitude.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_attitude.h new file mode 100644 index 0000000..ca9f5ac --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_attitude.h @@ -0,0 +1,353 @@ +// MESSAGE ATTITUDE PACKING + +#define MAVLINK_MSG_ID_ATTITUDE 30 + +typedef struct __mavlink_attitude_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float roll; /*< Roll angle (rad, -pi..+pi)*/ + float pitch; /*< Pitch angle (rad, -pi..+pi)*/ + float yaw; /*< Yaw angle (rad, -pi..+pi)*/ + float rollspeed; /*< Roll angular speed (rad/s)*/ + float pitchspeed; /*< Pitch angular speed (rad/s)*/ + float yawspeed; /*< Yaw angular speed (rad/s)*/ +} mavlink_attitude_t; + +#define MAVLINK_MSG_ID_ATTITUDE_LEN 28 +#define MAVLINK_MSG_ID_30_LEN 28 + +#define MAVLINK_MSG_ID_ATTITUDE_CRC 39 +#define MAVLINK_MSG_ID_30_CRC 39 + + + +#define MAVLINK_MESSAGE_INFO_ATTITUDE { \ + "ATTITUDE", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \ + } \ +} + + +/** + * @brief Pack a attitude message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param roll Roll angle (rad, -pi..+pi) + * @param pitch Pitch angle (rad, -pi..+pi) + * @param yaw Yaw angle (rad, -pi..+pi) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, rollspeed); + _mav_put_float(buf, 20, pitchspeed); + _mav_put_float(buf, 24, yawspeed); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN); +#else + mavlink_attitude_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif +} + +/** + * @brief Pack a attitude message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param roll Roll angle (rad, -pi..+pi) + * @param pitch Pitch angle (rad, -pi..+pi) + * @param yaw Yaw angle (rad, -pi..+pi) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, rollspeed); + _mav_put_float(buf, 20, pitchspeed); + _mav_put_float(buf, 24, yawspeed); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN); +#else + mavlink_attitude_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif +} + +/** + * @brief Encode a attitude struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param attitude C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude) +{ + return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); +} + +/** + * @brief Encode a attitude struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param attitude C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_t* attitude) +{ + return mavlink_msg_attitude_pack_chan(system_id, component_id, chan, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); +} + +/** + * @brief Send a attitude message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param roll Roll angle (rad, -pi..+pi) + * @param pitch Pitch angle (rad, -pi..+pi) + * @param yaw Yaw angle (rad, -pi..+pi) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, rollspeed); + _mav_put_float(buf, 20, pitchspeed); + _mav_put_float(buf, 24, yawspeed); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif +#else + mavlink_attitude_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_attitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, rollspeed); + _mav_put_float(buf, 20, pitchspeed); + _mav_put_float(buf, 24, yawspeed); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif +#else + mavlink_attitude_t *packet = (mavlink_attitude_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + packet->rollspeed = rollspeed; + packet->pitchspeed = pitchspeed; + packet->yawspeed = yawspeed; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ATTITUDE UNPACKING + + +/** + * @brief Get field time_boot_ms from attitude message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field roll from attitude message + * + * @return Roll angle (rad, -pi..+pi) + */ +static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field pitch from attitude message + * + * @return Pitch angle (rad, -pi..+pi) + */ +static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from attitude message + * + * @return Yaw angle (rad, -pi..+pi) + */ +static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field rollspeed from attitude message + * + * @return Roll angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field pitchspeed from attitude message + * + * @return Pitch angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field yawspeed from attitude message + * + * @return Yaw angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a attitude message into a struct + * + * @param msg The message to decode + * @param attitude C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude) +{ +#if MAVLINK_NEED_BYTE_SWAP + attitude->time_boot_ms = mavlink_msg_attitude_get_time_boot_ms(msg); + attitude->roll = mavlink_msg_attitude_get_roll(msg); + attitude->pitch = mavlink_msg_attitude_get_pitch(msg); + attitude->yaw = mavlink_msg_attitude_get_yaw(msg); + attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg); + attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg); + attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg); +#else + memcpy(attitude, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h new file mode 100644 index 0000000..df362b4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h @@ -0,0 +1,377 @@ +// MESSAGE ATTITUDE_QUATERNION PACKING + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31 + +typedef struct __mavlink_attitude_quaternion_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float q1; /*< Quaternion component 1, w (1 in null-rotation)*/ + float q2; /*< Quaternion component 2, x (0 in null-rotation)*/ + float q3; /*< Quaternion component 3, y (0 in null-rotation)*/ + float q4; /*< Quaternion component 4, z (0 in null-rotation)*/ + float rollspeed; /*< Roll angular speed (rad/s)*/ + float pitchspeed; /*< Pitch angular speed (rad/s)*/ + float yawspeed; /*< Yaw angular speed (rad/s)*/ +} mavlink_attitude_quaternion_t; + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32 +#define MAVLINK_MSG_ID_31_LEN 32 + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246 +#define MAVLINK_MSG_ID_31_CRC 246 + + + +#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \ + "ATTITUDE_QUATERNION", \ + 8, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \ + { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \ + { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \ + { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \ + { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \ + } \ +} + + +/** + * @brief Pack a attitude_quaternion message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q1 Quaternion component 1, w (1 in null-rotation) + * @param q2 Quaternion component 2, x (0 in null-rotation) + * @param q3 Quaternion component 3, y (0 in null-rotation) + * @param q4 Quaternion component 4, z (0 in null-rotation) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, q1); + _mav_put_float(buf, 8, q2); + _mav_put_float(buf, 12, q3); + _mav_put_float(buf, 16, q4); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#else + mavlink_attitude_quaternion_t packet; + packet.time_boot_ms = time_boot_ms; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif +} + +/** + * @brief Pack a attitude_quaternion message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q1 Quaternion component 1, w (1 in null-rotation) + * @param q2 Quaternion component 2, x (0 in null-rotation) + * @param q3 Quaternion component 3, y (0 in null-rotation) + * @param q4 Quaternion component 4, z (0 in null-rotation) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, q1); + _mav_put_float(buf, 8, q2); + _mav_put_float(buf, 12, q3); + _mav_put_float(buf, 16, q4); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#else + mavlink_attitude_quaternion_t packet; + packet.time_boot_ms = time_boot_ms; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif +} + +/** + * @brief Encode a attitude_quaternion struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param attitude_quaternion C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion) +{ + return mavlink_msg_attitude_quaternion_pack(system_id, component_id, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed); +} + +/** + * @brief Encode a attitude_quaternion struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param attitude_quaternion C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion) +{ + return mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, chan, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed); +} + +/** + * @brief Send a attitude_quaternion message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q1 Quaternion component 1, w (1 in null-rotation) + * @param q2 Quaternion component 2, x (0 in null-rotation) + * @param q3 Quaternion component 3, y (0 in null-rotation) + * @param q4 Quaternion component 4, z (0 in null-rotation) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, q1); + _mav_put_float(buf, 8, q2); + _mav_put_float(buf, 12, q3); + _mav_put_float(buf, 16, q4); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif +#else + mavlink_attitude_quaternion_t packet; + packet.time_boot_ms = time_boot_ms; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, q1); + _mav_put_float(buf, 8, q2); + _mav_put_float(buf, 12, q3); + _mav_put_float(buf, 16, q4); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif +#else + mavlink_attitude_quaternion_t *packet = (mavlink_attitude_quaternion_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->q1 = q1; + packet->q2 = q2; + packet->q3 = q3; + packet->q4 = q4; + packet->rollspeed = rollspeed; + packet->pitchspeed = pitchspeed; + packet->yawspeed = yawspeed; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ATTITUDE_QUATERNION UNPACKING + + +/** + * @brief Get field time_boot_ms from attitude_quaternion message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field q1 from attitude_quaternion message + * + * @return Quaternion component 1, w (1 in null-rotation) + */ +static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field q2 from attitude_quaternion message + * + * @return Quaternion component 2, x (0 in null-rotation) + */ +static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field q3 from attitude_quaternion message + * + * @return Quaternion component 3, y (0 in null-rotation) + */ +static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field q4 from attitude_quaternion message + * + * @return Quaternion component 4, z (0 in null-rotation) + */ +static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field rollspeed from attitude_quaternion message + * + * @return Roll angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitchspeed from attitude_quaternion message + * + * @return Pitch angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yawspeed from attitude_quaternion message + * + * @return Yaw angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a attitude_quaternion message into a struct + * + * @param msg The message to decode + * @param attitude_quaternion C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_t* attitude_quaternion) +{ +#if MAVLINK_NEED_BYTE_SWAP + attitude_quaternion->time_boot_ms = mavlink_msg_attitude_quaternion_get_time_boot_ms(msg); + attitude_quaternion->q1 = mavlink_msg_attitude_quaternion_get_q1(msg); + attitude_quaternion->q2 = mavlink_msg_attitude_quaternion_get_q2(msg); + attitude_quaternion->q3 = mavlink_msg_attitude_quaternion_get_q3(msg); + attitude_quaternion->q4 = mavlink_msg_attitude_quaternion_get_q4(msg); + attitude_quaternion->rollspeed = mavlink_msg_attitude_quaternion_get_rollspeed(msg); + attitude_quaternion->pitchspeed = mavlink_msg_attitude_quaternion_get_pitchspeed(msg); + attitude_quaternion->yawspeed = mavlink_msg_attitude_quaternion_get_yawspeed(msg); +#else + memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_attitude_quaternion_cov.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_attitude_quaternion_cov.h new file mode 100644 index 0000000..dc99d9d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_attitude_quaternion_cov.h @@ -0,0 +1,322 @@ +// MESSAGE ATTITUDE_QUATERNION_COV PACKING + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV 61 + +typedef struct __mavlink_attitude_quaternion_cov_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)*/ + float rollspeed; /*< Roll angular speed (rad/s)*/ + float pitchspeed; /*< Pitch angular speed (rad/s)*/ + float yawspeed; /*< Yaw angular speed (rad/s)*/ + float covariance[9]; /*< Attitude covariance*/ +} mavlink_attitude_quaternion_cov_t; + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN 68 +#define MAVLINK_MSG_ID_61_LEN 68 + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC 153 +#define MAVLINK_MSG_ID_61_CRC 153 + +#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_Q_LEN 4 +#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_COVARIANCE_LEN 9 + +#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV { \ + "ATTITUDE_QUATERNION_COV", \ + 6, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_boot_ms) }, \ + { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \ + { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 32, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \ + } \ +} + + +/** + * @brief Pack a attitude_quaternion_cov message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @param covariance Attitude covariance + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_float_array(buf, 4, q, 4); + _mav_put_float_array(buf, 32, covariance, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#else + mavlink_attitude_quaternion_cov_t packet; + packet.time_boot_ms = time_boot_ms; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif +} + +/** + * @brief Pack a attitude_quaternion_cov message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @param covariance Attitude covariance + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,const float *q,float rollspeed,float pitchspeed,float yawspeed,const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_float_array(buf, 4, q, 4); + _mav_put_float_array(buf, 32, covariance, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#else + mavlink_attitude_quaternion_cov_t packet; + packet.time_boot_ms = time_boot_ms; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif +} + +/** + * @brief Encode a attitude_quaternion_cov struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param attitude_quaternion_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) +{ + return mavlink_msg_attitude_quaternion_cov_pack(system_id, component_id, msg, attitude_quaternion_cov->time_boot_ms, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance); +} + +/** + * @brief Encode a attitude_quaternion_cov struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param attitude_quaternion_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) +{ + return mavlink_msg_attitude_quaternion_cov_pack_chan(system_id, component_id, chan, msg, attitude_quaternion_cov->time_boot_ms, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance); +} + +/** + * @brief Send a attitude_quaternion_cov message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @param covariance Attitude covariance + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_quaternion_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_float_array(buf, 4, q, 4); + _mav_put_float_array(buf, 32, covariance, 9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif +#else + mavlink_attitude_quaternion_cov_t packet; + packet.time_boot_ms = time_boot_ms; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_attitude_quaternion_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_float_array(buf, 4, q, 4); + _mav_put_float_array(buf, 32, covariance, 9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif +#else + mavlink_attitude_quaternion_cov_t *packet = (mavlink_attitude_quaternion_cov_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->rollspeed = rollspeed; + packet->pitchspeed = pitchspeed; + packet->yawspeed = yawspeed; + mav_array_memcpy(packet->q, q, sizeof(float)*4); + mav_array_memcpy(packet->covariance, covariance, sizeof(float)*9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ATTITUDE_QUATERNION_COV UNPACKING + + +/** + * @brief Get field time_boot_ms from attitude_quaternion_cov message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_attitude_quaternion_cov_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field q from attitude_quaternion_cov message + * + * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + */ +static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_q(const mavlink_message_t* msg, float *q) +{ + return _MAV_RETURN_float_array(msg, q, 4, 4); +} + +/** + * @brief Get field rollspeed from attitude_quaternion_cov message + * + * @return Roll angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_cov_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitchspeed from attitude_quaternion_cov message + * + * @return Pitch angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_cov_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yawspeed from attitude_quaternion_cov message + * + * @return Yaw angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_cov_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field covariance from attitude_quaternion_cov message + * + * @return Attitude covariance + */ +static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_covariance(const mavlink_message_t* msg, float *covariance) +{ + return _MAV_RETURN_float_array(msg, covariance, 9, 32); +} + +/** + * @brief Decode a attitude_quaternion_cov message into a struct + * + * @param msg The message to decode + * @param attitude_quaternion_cov C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_quaternion_cov_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) +{ +#if MAVLINK_NEED_BYTE_SWAP + attitude_quaternion_cov->time_boot_ms = mavlink_msg_attitude_quaternion_cov_get_time_boot_ms(msg); + mavlink_msg_attitude_quaternion_cov_get_q(msg, attitude_quaternion_cov->q); + attitude_quaternion_cov->rollspeed = mavlink_msg_attitude_quaternion_cov_get_rollspeed(msg); + attitude_quaternion_cov->pitchspeed = mavlink_msg_attitude_quaternion_cov_get_pitchspeed(msg); + attitude_quaternion_cov->yawspeed = mavlink_msg_attitude_quaternion_cov_get_yawspeed(msg); + mavlink_msg_attitude_quaternion_cov_get_covariance(msg, attitude_quaternion_cov->covariance); +#else + memcpy(attitude_quaternion_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_attitude_target.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_attitude_target.h new file mode 100644 index 0000000..5313fb0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_attitude_target.h @@ -0,0 +1,345 @@ +// MESSAGE ATTITUDE_TARGET PACKING + +#define MAVLINK_MSG_ID_ATTITUDE_TARGET 83 + +typedef struct __mavlink_attitude_target_t +{ + uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ + float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ + float body_roll_rate; /*< Body roll rate in radians per second*/ + float body_pitch_rate; /*< Body roll rate in radians per second*/ + float body_yaw_rate; /*< Body roll rate in radians per second*/ + float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/ + uint8_t type_mask; /*< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude*/ +} mavlink_attitude_target_t; + +#define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37 +#define MAVLINK_MSG_ID_83_LEN 37 + +#define MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC 22 +#define MAVLINK_MSG_ID_83_CRC 22 + +#define MAVLINK_MSG_ATTITUDE_TARGET_FIELD_Q_LEN 4 + +#define MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET { \ + "ATTITUDE_TARGET", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \ + { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \ + { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \ + { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \ + { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \ + } \ +} + + +/** + * @brief Pack a attitude_target message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate Body roll rate in radians per second + * @param body_pitch_rate Body roll rate in radians per second + * @param body_yaw_rate Body roll rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, type_mask); + _mav_put_float_array(buf, 4, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#else + mavlink_attitude_target_t packet; + packet.time_boot_ms = time_boot_ms; + packet.body_roll_rate = body_roll_rate; + packet.body_pitch_rate = body_pitch_rate; + packet.body_yaw_rate = body_yaw_rate; + packet.thrust = thrust; + packet.type_mask = type_mask; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif +} + +/** + * @brief Pack a attitude_target message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate Body roll rate in radians per second + * @param body_pitch_rate Body roll rate in radians per second + * @param body_yaw_rate Body roll rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t type_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, type_mask); + _mav_put_float_array(buf, 4, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#else + mavlink_attitude_target_t packet; + packet.time_boot_ms = time_boot_ms; + packet.body_roll_rate = body_roll_rate; + packet.body_pitch_rate = body_pitch_rate; + packet.body_yaw_rate = body_yaw_rate; + packet.thrust = thrust; + packet.type_mask = type_mask; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif +} + +/** + * @brief Encode a attitude_target struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param attitude_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target) +{ + return mavlink_msg_attitude_target_pack(system_id, component_id, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust); +} + +/** + * @brief Encode a attitude_target struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param attitude_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target) +{ + return mavlink_msg_attitude_target_pack_chan(system_id, component_id, chan, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust); +} + +/** + * @brief Send a attitude_target message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate Body roll rate in radians per second + * @param body_pitch_rate Body roll rate in radians per second + * @param body_yaw_rate Body roll rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_target_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, type_mask); + _mav_put_float_array(buf, 4, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif +#else + mavlink_attitude_target_t packet; + packet.time_boot_ms = time_boot_ms; + packet.body_roll_rate = body_roll_rate; + packet.body_pitch_rate = body_pitch_rate; + packet.body_yaw_rate = body_yaw_rate; + packet.thrust = thrust; + packet.type_mask = type_mask; + mav_array_memcpy(packet.q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_attitude_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, type_mask); + _mav_put_float_array(buf, 4, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif +#else + mavlink_attitude_target_t *packet = (mavlink_attitude_target_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->body_roll_rate = body_roll_rate; + packet->body_pitch_rate = body_pitch_rate; + packet->body_yaw_rate = body_yaw_rate; + packet->thrust = thrust; + packet->type_mask = type_mask; + mav_array_memcpy(packet->q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ATTITUDE_TARGET UNPACKING + + +/** + * @brief Get field time_boot_ms from attitude_target message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_attitude_target_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field type_mask from attitude_target message + * + * @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + */ +static inline uint8_t mavlink_msg_attitude_target_get_type_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Get field q from attitude_target message + * + * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + */ +static inline uint16_t mavlink_msg_attitude_target_get_q(const mavlink_message_t* msg, float *q) +{ + return _MAV_RETURN_float_array(msg, q, 4, 4); +} + +/** + * @brief Get field body_roll_rate from attitude_target message + * + * @return Body roll rate in radians per second + */ +static inline float mavlink_msg_attitude_target_get_body_roll_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field body_pitch_rate from attitude_target message + * + * @return Body roll rate in radians per second + */ +static inline float mavlink_msg_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field body_yaw_rate from attitude_target message + * + * @return Body roll rate in radians per second + */ +static inline float mavlink_msg_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field thrust from attitude_target message + * + * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + */ +static inline float mavlink_msg_attitude_target_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Decode a attitude_target message into a struct + * + * @param msg The message to decode + * @param attitude_target C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_target_decode(const mavlink_message_t* msg, mavlink_attitude_target_t* attitude_target) +{ +#if MAVLINK_NEED_BYTE_SWAP + attitude_target->time_boot_ms = mavlink_msg_attitude_target_get_time_boot_ms(msg); + mavlink_msg_attitude_target_get_q(msg, attitude_target->q); + attitude_target->body_roll_rate = mavlink_msg_attitude_target_get_body_roll_rate(msg); + attitude_target->body_pitch_rate = mavlink_msg_attitude_target_get_body_pitch_rate(msg); + attitude_target->body_yaw_rate = mavlink_msg_attitude_target_get_body_yaw_rate(msg); + attitude_target->thrust = mavlink_msg_attitude_target_get_thrust(msg); + attitude_target->type_mask = mavlink_msg_attitude_target_get_type_mask(msg); +#else + memcpy(attitude_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_auth_key.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_auth_key.h new file mode 100644 index 0000000..4c6c114 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_auth_key.h @@ -0,0 +1,209 @@ +// MESSAGE AUTH_KEY PACKING + +#define MAVLINK_MSG_ID_AUTH_KEY 7 + +typedef struct __mavlink_auth_key_t +{ + char key[32]; /*< key*/ +} mavlink_auth_key_t; + +#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32 +#define MAVLINK_MSG_ID_7_LEN 32 + +#define MAVLINK_MSG_ID_AUTH_KEY_CRC 119 +#define MAVLINK_MSG_ID_7_CRC 119 + +#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32 + +#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ + "AUTH_KEY", \ + 1, \ + { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ + } \ +} + + +/** + * @brief Pack a auth_key message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param key key + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *key) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; + + _mav_put_char_array(buf, 0, key, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#else + mavlink_auth_key_t packet; + + mav_array_memcpy(packet.key, key, sizeof(char)*32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif +} + +/** + * @brief Pack a auth_key message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param key key + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *key) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; + + _mav_put_char_array(buf, 0, key, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#else + mavlink_auth_key_t packet; + + mav_array_memcpy(packet.key, key, sizeof(char)*32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif +} + +/** + * @brief Encode a auth_key struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param auth_key C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) +{ + return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key); +} + +/** + * @brief Encode a auth_key struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param auth_key C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_auth_key_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) +{ + return mavlink_msg_auth_key_pack_chan(system_id, component_id, chan, msg, auth_key->key); +} + +/** + * @brief Send a auth_key message + * @param chan MAVLink channel to send the message + * + * @param key key + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; + + _mav_put_char_array(buf, 0, key, 32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif +#else + mavlink_auth_key_t packet; + + mav_array_memcpy(packet.key, key, sizeof(char)*32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_AUTH_KEY_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_auth_key_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *key) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + + _mav_put_char_array(buf, 0, key, 32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif +#else + mavlink_auth_key_t *packet = (mavlink_auth_key_t *)msgbuf; + + mav_array_memcpy(packet->key, key, sizeof(char)*32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE AUTH_KEY UNPACKING + + +/** + * @brief Get field key from auth_key message + * + * @return key + */ +static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key) +{ + return _MAV_RETURN_char_array(msg, key, 32, 0); +} + +/** + * @brief Decode a auth_key message into a struct + * + * @param msg The message to decode + * @param auth_key C-struct to decode the message contents into + */ +static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key) +{ +#if MAVLINK_NEED_BYTE_SWAP + mavlink_msg_auth_key_get_key(msg, auth_key->key); +#else + memcpy(auth_key, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_autopilot_version.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_autopilot_version.h new file mode 100644 index 0000000..7cef9ea --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_autopilot_version.h @@ -0,0 +1,443 @@ +// MESSAGE AUTOPILOT_VERSION PACKING + +#define MAVLINK_MSG_ID_AUTOPILOT_VERSION 148 + +typedef struct __mavlink_autopilot_version_t +{ + uint64_t capabilities; /*< bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)*/ + uint64_t uid; /*< UID if provided by hardware*/ + uint32_t flight_sw_version; /*< Firmware version number*/ + uint32_t middleware_sw_version; /*< Middleware version number*/ + uint32_t os_sw_version; /*< Operating system version number*/ + uint32_t board_version; /*< HW / board version (last 8 bytes should be silicon ID, if any)*/ + uint16_t vendor_id; /*< ID of the board vendor*/ + uint16_t product_id; /*< ID of the product*/ + uint8_t flight_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ + uint8_t middleware_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ + uint8_t os_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ +} mavlink_autopilot_version_t; + +#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 60 +#define MAVLINK_MSG_ID_148_LEN 60 + +#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC 178 +#define MAVLINK_MSG_ID_148_CRC 178 + +#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION_LEN 8 +#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION_LEN 8 +#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION_LEN 8 + +#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \ + "AUTOPILOT_VERSION", \ + 11, \ + { { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \ + { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \ + { "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \ + { "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \ + { "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \ + { "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \ + { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \ + { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \ + { "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \ + { "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \ + { "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \ + } \ +} + + +/** + * @brief Pack a autopilot_version message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) + * @param flight_sw_version Firmware version number + * @param middleware_sw_version Middleware version number + * @param os_sw_version Operating system version number + * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) + * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param vendor_id ID of the board vendor + * @param product_id ID of the product + * @param uid UID if provided by hardware + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN]; + _mav_put_uint64_t(buf, 0, capabilities); + _mav_put_uint64_t(buf, 8, uid); + _mav_put_uint32_t(buf, 16, flight_sw_version); + _mav_put_uint32_t(buf, 20, middleware_sw_version); + _mav_put_uint32_t(buf, 24, os_sw_version); + _mav_put_uint32_t(buf, 28, board_version); + _mav_put_uint16_t(buf, 32, vendor_id); + _mav_put_uint16_t(buf, 34, product_id); + _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); + _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); + _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#else + mavlink_autopilot_version_t packet; + packet.capabilities = capabilities; + packet.uid = uid; + packet.flight_sw_version = flight_sw_version; + packet.middleware_sw_version = middleware_sw_version; + packet.os_sw_version = os_sw_version; + packet.board_version = board_version; + packet.vendor_id = vendor_id; + packet.product_id = product_id; + mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif +} + +/** + * @brief Pack a autopilot_version message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) + * @param flight_sw_version Firmware version number + * @param middleware_sw_version Middleware version number + * @param os_sw_version Operating system version number + * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) + * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param vendor_id ID of the board vendor + * @param product_id ID of the product + * @param uid UID if provided by hardware + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t capabilities,uint32_t flight_sw_version,uint32_t middleware_sw_version,uint32_t os_sw_version,uint32_t board_version,const uint8_t *flight_custom_version,const uint8_t *middleware_custom_version,const uint8_t *os_custom_version,uint16_t vendor_id,uint16_t product_id,uint64_t uid) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN]; + _mav_put_uint64_t(buf, 0, capabilities); + _mav_put_uint64_t(buf, 8, uid); + _mav_put_uint32_t(buf, 16, flight_sw_version); + _mav_put_uint32_t(buf, 20, middleware_sw_version); + _mav_put_uint32_t(buf, 24, os_sw_version); + _mav_put_uint32_t(buf, 28, board_version); + _mav_put_uint16_t(buf, 32, vendor_id); + _mav_put_uint16_t(buf, 34, product_id); + _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); + _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); + _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#else + mavlink_autopilot_version_t packet; + packet.capabilities = capabilities; + packet.uid = uid; + packet.flight_sw_version = flight_sw_version; + packet.middleware_sw_version = middleware_sw_version; + packet.os_sw_version = os_sw_version; + packet.board_version = board_version; + packet.vendor_id = vendor_id; + packet.product_id = product_id; + mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif +} + +/** + * @brief Encode a autopilot_version struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param autopilot_version C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_autopilot_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version) +{ + return mavlink_msg_autopilot_version_pack(system_id, component_id, msg, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid); +} + +/** + * @brief Encode a autopilot_version struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param autopilot_version C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_autopilot_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version) +{ + return mavlink_msg_autopilot_version_pack_chan(system_id, component_id, chan, msg, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid); +} + +/** + * @brief Send a autopilot_version message + * @param chan MAVLink channel to send the message + * + * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) + * @param flight_sw_version Firmware version number + * @param middleware_sw_version Middleware version number + * @param os_sw_version Operating system version number + * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) + * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param vendor_id ID of the board vendor + * @param product_id ID of the product + * @param uid UID if provided by hardware + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_autopilot_version_send(mavlink_channel_t chan, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN]; + _mav_put_uint64_t(buf, 0, capabilities); + _mav_put_uint64_t(buf, 8, uid); + _mav_put_uint32_t(buf, 16, flight_sw_version); + _mav_put_uint32_t(buf, 20, middleware_sw_version); + _mav_put_uint32_t(buf, 24, os_sw_version); + _mav_put_uint32_t(buf, 28, board_version); + _mav_put_uint16_t(buf, 32, vendor_id); + _mav_put_uint16_t(buf, 34, product_id); + _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); + _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); + _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif +#else + mavlink_autopilot_version_t packet; + packet.capabilities = capabilities; + packet.uid = uid; + packet.flight_sw_version = flight_sw_version; + packet.middleware_sw_version = middleware_sw_version; + packet.os_sw_version = os_sw_version; + packet.board_version = board_version; + packet.vendor_id = vendor_id; + packet.product_id = product_id; + mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_autopilot_version_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, capabilities); + _mav_put_uint64_t(buf, 8, uid); + _mav_put_uint32_t(buf, 16, flight_sw_version); + _mav_put_uint32_t(buf, 20, middleware_sw_version); + _mav_put_uint32_t(buf, 24, os_sw_version); + _mav_put_uint32_t(buf, 28, board_version); + _mav_put_uint16_t(buf, 32, vendor_id); + _mav_put_uint16_t(buf, 34, product_id); + _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); + _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); + _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif +#else + mavlink_autopilot_version_t *packet = (mavlink_autopilot_version_t *)msgbuf; + packet->capabilities = capabilities; + packet->uid = uid; + packet->flight_sw_version = flight_sw_version; + packet->middleware_sw_version = middleware_sw_version; + packet->os_sw_version = os_sw_version; + packet->board_version = board_version; + packet->vendor_id = vendor_id; + packet->product_id = product_id; + mav_array_memcpy(packet->flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet->middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet->os_custom_version, os_custom_version, sizeof(uint8_t)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE AUTOPILOT_VERSION UNPACKING + + +/** + * @brief Get field capabilities from autopilot_version message + * + * @return bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) + */ +static inline uint64_t mavlink_msg_autopilot_version_get_capabilities(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field flight_sw_version from autopilot_version message + * + * @return Firmware version number + */ +static inline uint32_t mavlink_msg_autopilot_version_get_flight_sw_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 16); +} + +/** + * @brief Get field middleware_sw_version from autopilot_version message + * + * @return Middleware version number + */ +static inline uint32_t mavlink_msg_autopilot_version_get_middleware_sw_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 20); +} + +/** + * @brief Get field os_sw_version from autopilot_version message + * + * @return Operating system version number + */ +static inline uint32_t mavlink_msg_autopilot_version_get_os_sw_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 24); +} + +/** + * @brief Get field board_version from autopilot_version message + * + * @return HW / board version (last 8 bytes should be silicon ID, if any) + */ +static inline uint32_t mavlink_msg_autopilot_version_get_board_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 28); +} + +/** + * @brief Get field flight_custom_version from autopilot_version message + * + * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + */ +static inline uint16_t mavlink_msg_autopilot_version_get_flight_custom_version(const mavlink_message_t* msg, uint8_t *flight_custom_version) +{ + return _MAV_RETURN_uint8_t_array(msg, flight_custom_version, 8, 36); +} + +/** + * @brief Get field middleware_custom_version from autopilot_version message + * + * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + */ +static inline uint16_t mavlink_msg_autopilot_version_get_middleware_custom_version(const mavlink_message_t* msg, uint8_t *middleware_custom_version) +{ + return _MAV_RETURN_uint8_t_array(msg, middleware_custom_version, 8, 44); +} + +/** + * @brief Get field os_custom_version from autopilot_version message + * + * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + */ +static inline uint16_t mavlink_msg_autopilot_version_get_os_custom_version(const mavlink_message_t* msg, uint8_t *os_custom_version) +{ + return _MAV_RETURN_uint8_t_array(msg, os_custom_version, 8, 52); +} + +/** + * @brief Get field vendor_id from autopilot_version message + * + * @return ID of the board vendor + */ +static inline uint16_t mavlink_msg_autopilot_version_get_vendor_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 32); +} + +/** + * @brief Get field product_id from autopilot_version message + * + * @return ID of the product + */ +static inline uint16_t mavlink_msg_autopilot_version_get_product_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 34); +} + +/** + * @brief Get field uid from autopilot_version message + * + * @return UID if provided by hardware + */ +static inline uint64_t mavlink_msg_autopilot_version_get_uid(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 8); +} + +/** + * @brief Decode a autopilot_version message into a struct + * + * @param msg The message to decode + * @param autopilot_version C-struct to decode the message contents into + */ +static inline void mavlink_msg_autopilot_version_decode(const mavlink_message_t* msg, mavlink_autopilot_version_t* autopilot_version) +{ +#if MAVLINK_NEED_BYTE_SWAP + autopilot_version->capabilities = mavlink_msg_autopilot_version_get_capabilities(msg); + autopilot_version->uid = mavlink_msg_autopilot_version_get_uid(msg); + autopilot_version->flight_sw_version = mavlink_msg_autopilot_version_get_flight_sw_version(msg); + autopilot_version->middleware_sw_version = mavlink_msg_autopilot_version_get_middleware_sw_version(msg); + autopilot_version->os_sw_version = mavlink_msg_autopilot_version_get_os_sw_version(msg); + autopilot_version->board_version = mavlink_msg_autopilot_version_get_board_version(msg); + autopilot_version->vendor_id = mavlink_msg_autopilot_version_get_vendor_id(msg); + autopilot_version->product_id = mavlink_msg_autopilot_version_get_product_id(msg); + mavlink_msg_autopilot_version_get_flight_custom_version(msg, autopilot_version->flight_custom_version); + mavlink_msg_autopilot_version_get_middleware_custom_version(msg, autopilot_version->middleware_custom_version); + mavlink_msg_autopilot_version_get_os_custom_version(msg, autopilot_version->os_custom_version); +#else + memcpy(autopilot_version, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_battery_status.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_battery_status.h new file mode 100644 index 0000000..9311a7d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_battery_status.h @@ -0,0 +1,393 @@ +// MESSAGE BATTERY_STATUS PACKING + +#define MAVLINK_MSG_ID_BATTERY_STATUS 147 + +typedef struct __mavlink_battery_status_t +{ + int32_t current_consumed; /*< Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate*/ + int32_t energy_consumed; /*< Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate*/ + int16_t temperature; /*< Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.*/ + uint16_t voltages[10]; /*< Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value.*/ + int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current*/ + uint8_t id; /*< Battery ID*/ + uint8_t battery_function; /*< Function of the battery*/ + uint8_t type; /*< Type (chemistry) of the battery*/ + int8_t battery_remaining; /*< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery*/ +} mavlink_battery_status_t; + +#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36 +#define MAVLINK_MSG_ID_147_LEN 36 + +#define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 154 +#define MAVLINK_MSG_ID_147_CRC 154 + +#define MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN 10 + +#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \ + "BATTERY_STATUS", \ + 9, \ + { { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \ + { "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \ + { "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \ + { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \ + { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \ + { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \ + { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \ + } \ +} + + +/** + * @brief Pack a battery_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param id Battery ID + * @param battery_function Function of the battery + * @param type Type (chemistry) of the battery + * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. + * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + * @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; + _mav_put_int32_t(buf, 0, current_consumed); + _mav_put_int32_t(buf, 4, energy_consumed); + _mav_put_int16_t(buf, 8, temperature); + _mav_put_int16_t(buf, 30, current_battery); + _mav_put_uint8_t(buf, 32, id); + _mav_put_uint8_t(buf, 33, battery_function); + _mav_put_uint8_t(buf, 34, type); + _mav_put_int8_t(buf, 35, battery_remaining); + _mav_put_uint16_t_array(buf, 10, voltages, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#else + mavlink_battery_status_t packet; + packet.current_consumed = current_consumed; + packet.energy_consumed = energy_consumed; + packet.temperature = temperature; + packet.current_battery = current_battery; + packet.id = id; + packet.battery_function = battery_function; + packet.type = type; + packet.battery_remaining = battery_remaining; + mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif +} + +/** + * @brief Pack a battery_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param id Battery ID + * @param battery_function Function of the battery + * @param type Type (chemistry) of the battery + * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. + * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + * @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t id,uint8_t battery_function,uint8_t type,int16_t temperature,const uint16_t *voltages,int16_t current_battery,int32_t current_consumed,int32_t energy_consumed,int8_t battery_remaining) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; + _mav_put_int32_t(buf, 0, current_consumed); + _mav_put_int32_t(buf, 4, energy_consumed); + _mav_put_int16_t(buf, 8, temperature); + _mav_put_int16_t(buf, 30, current_battery); + _mav_put_uint8_t(buf, 32, id); + _mav_put_uint8_t(buf, 33, battery_function); + _mav_put_uint8_t(buf, 34, type); + _mav_put_int8_t(buf, 35, battery_remaining); + _mav_put_uint16_t_array(buf, 10, voltages, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#else + mavlink_battery_status_t packet; + packet.current_consumed = current_consumed; + packet.energy_consumed = energy_consumed; + packet.temperature = temperature; + packet.current_battery = current_battery; + packet.id = id; + packet.battery_function = battery_function; + packet.type = type; + packet.battery_remaining = battery_remaining; + mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif +} + +/** + * @brief Encode a battery_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param battery_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status) +{ + return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining); +} + +/** + * @brief Encode a battery_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param battery_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status) +{ + return mavlink_msg_battery_status_pack_chan(system_id, component_id, chan, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining); +} + +/** + * @brief Send a battery_status message + * @param chan MAVLink channel to send the message + * + * @param id Battery ID + * @param battery_function Function of the battery + * @param type Type (chemistry) of the battery + * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. + * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + * @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; + _mav_put_int32_t(buf, 0, current_consumed); + _mav_put_int32_t(buf, 4, energy_consumed); + _mav_put_int16_t(buf, 8, temperature); + _mav_put_int16_t(buf, 30, current_battery); + _mav_put_uint8_t(buf, 32, id); + _mav_put_uint8_t(buf, 33, battery_function); + _mav_put_uint8_t(buf, 34, type); + _mav_put_int8_t(buf, 35, battery_remaining); + _mav_put_uint16_t_array(buf, 10, voltages, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif +#else + mavlink_battery_status_t packet; + packet.current_consumed = current_consumed; + packet.energy_consumed = energy_consumed; + packet.temperature = temperature; + packet.current_battery = current_battery; + packet.id = id; + packet.battery_function = battery_function; + packet.type = type; + packet.battery_remaining = battery_remaining; + mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_BATTERY_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, current_consumed); + _mav_put_int32_t(buf, 4, energy_consumed); + _mav_put_int16_t(buf, 8, temperature); + _mav_put_int16_t(buf, 30, current_battery); + _mav_put_uint8_t(buf, 32, id); + _mav_put_uint8_t(buf, 33, battery_function); + _mav_put_uint8_t(buf, 34, type); + _mav_put_int8_t(buf, 35, battery_remaining); + _mav_put_uint16_t_array(buf, 10, voltages, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif +#else + mavlink_battery_status_t *packet = (mavlink_battery_status_t *)msgbuf; + packet->current_consumed = current_consumed; + packet->energy_consumed = energy_consumed; + packet->temperature = temperature; + packet->current_battery = current_battery; + packet->id = id; + packet->battery_function = battery_function; + packet->type = type; + packet->battery_remaining = battery_remaining; + mav_array_memcpy(packet->voltages, voltages, sizeof(uint16_t)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE BATTERY_STATUS UNPACKING + + +/** + * @brief Get field id from battery_status message + * + * @return Battery ID + */ +static inline uint8_t mavlink_msg_battery_status_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field battery_function from battery_status message + * + * @return Function of the battery + */ +static inline uint8_t mavlink_msg_battery_status_get_battery_function(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field type from battery_status message + * + * @return Type (chemistry) of the battery + */ +static inline uint8_t mavlink_msg_battery_status_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field temperature from battery_status message + * + * @return Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. + */ +static inline int16_t mavlink_msg_battery_status_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field voltages from battery_status message + * + * @return Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. + */ +static inline uint16_t mavlink_msg_battery_status_get_voltages(const mavlink_message_t* msg, uint16_t *voltages) +{ + return _MAV_RETURN_uint16_t_array(msg, voltages, 10, 10); +} + +/** + * @brief Get field current_battery from battery_status message + * + * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + */ +static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 30); +} + +/** + * @brief Get field current_consumed from battery_status message + * + * @return Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + */ +static inline int32_t mavlink_msg_battery_status_get_current_consumed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field energy_consumed from battery_status message + * + * @return Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate + */ +static inline int32_t mavlink_msg_battery_status_get_energy_consumed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field battery_remaining from battery_status message + * + * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + */ +static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 35); +} + +/** + * @brief Decode a battery_status message into a struct + * + * @param msg The message to decode + * @param battery_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_battery_status_decode(const mavlink_message_t* msg, mavlink_battery_status_t* battery_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + battery_status->current_consumed = mavlink_msg_battery_status_get_current_consumed(msg); + battery_status->energy_consumed = mavlink_msg_battery_status_get_energy_consumed(msg); + battery_status->temperature = mavlink_msg_battery_status_get_temperature(msg); + mavlink_msg_battery_status_get_voltages(msg, battery_status->voltages); + battery_status->current_battery = mavlink_msg_battery_status_get_current_battery(msg); + battery_status->id = mavlink_msg_battery_status_get_id(msg); + battery_status->battery_function = mavlink_msg_battery_status_get_battery_function(msg); + battery_status->type = mavlink_msg_battery_status_get_type(msg); + battery_status->battery_remaining = mavlink_msg_battery_status_get_battery_remaining(msg); +#else + memcpy(battery_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_camera_trigger.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_camera_trigger.h new file mode 100644 index 0000000..d724d9d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_camera_trigger.h @@ -0,0 +1,233 @@ +// MESSAGE CAMERA_TRIGGER PACKING + +#define MAVLINK_MSG_ID_CAMERA_TRIGGER 112 + +typedef struct __mavlink_camera_trigger_t +{ + uint64_t time_usec; /*< Timestamp for the image frame in microseconds*/ + uint32_t seq; /*< Image frame sequence*/ +} mavlink_camera_trigger_t; + +#define MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN 12 +#define MAVLINK_MSG_ID_112_LEN 12 + +#define MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC 174 +#define MAVLINK_MSG_ID_112_CRC 174 + + + +#define MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER { \ + "CAMERA_TRIGGER", \ + 2, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_trigger_t, time_usec) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_trigger_t, seq) }, \ + } \ +} + + +/** + * @brief Pack a camera_trigger message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp for the image frame in microseconds + * @param seq Image frame sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_camera_trigger_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint32_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#else + mavlink_camera_trigger_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CAMERA_TRIGGER; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif +} + +/** + * @brief Pack a camera_trigger message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp for the image frame in microseconds + * @param seq Image frame sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_camera_trigger_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint32_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#else + mavlink_camera_trigger_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CAMERA_TRIGGER; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif +} + +/** + * @brief Encode a camera_trigger struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param camera_trigger C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_camera_trigger_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_trigger_t* camera_trigger) +{ + return mavlink_msg_camera_trigger_pack(system_id, component_id, msg, camera_trigger->time_usec, camera_trigger->seq); +} + +/** + * @brief Encode a camera_trigger struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param camera_trigger C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_camera_trigger_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_trigger_t* camera_trigger) +{ + return mavlink_msg_camera_trigger_pack_chan(system_id, component_id, chan, msg, camera_trigger->time_usec, camera_trigger->seq); +} + +/** + * @brief Send a camera_trigger message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp for the image frame in microseconds + * @param seq Image frame sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_camera_trigger_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif +#else + mavlink_camera_trigger_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_camera_trigger_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif +#else + mavlink_camera_trigger_t *packet = (mavlink_camera_trigger_t *)msgbuf; + packet->time_usec = time_usec; + packet->seq = seq; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE CAMERA_TRIGGER UNPACKING + + +/** + * @brief Get field time_usec from camera_trigger message + * + * @return Timestamp for the image frame in microseconds + */ +static inline uint64_t mavlink_msg_camera_trigger_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field seq from camera_trigger message + * + * @return Image frame sequence + */ +static inline uint32_t mavlink_msg_camera_trigger_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Decode a camera_trigger message into a struct + * + * @param msg The message to decode + * @param camera_trigger C-struct to decode the message contents into + */ +static inline void mavlink_msg_camera_trigger_decode(const mavlink_message_t* msg, mavlink_camera_trigger_t* camera_trigger) +{ +#if MAVLINK_NEED_BYTE_SWAP + camera_trigger->time_usec = mavlink_msg_camera_trigger_get_time_usec(msg); + camera_trigger->seq = mavlink_msg_camera_trigger_get_seq(msg); +#else + memcpy(camera_trigger, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_change_operator_control.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_change_operator_control.h new file mode 100644 index 0000000..7a86a91 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_change_operator_control.h @@ -0,0 +1,273 @@ +// MESSAGE CHANGE_OPERATOR_CONTROL PACKING + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5 + +typedef struct __mavlink_change_operator_control_t +{ + uint8_t target_system; /*< System the GCS requests control for*/ + uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/ + uint8_t version; /*< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.*/ + char passkey[25]; /*< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"*/ +} mavlink_change_operator_control_t; + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28 +#define MAVLINK_MSG_ID_5_LEN 28 + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC 217 +#define MAVLINK_MSG_ID_5_CRC 217 + +#define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25 + +#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \ + "CHANGE_OPERATOR_CONTROL", \ + 4, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \ + { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \ + { "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \ + { "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \ + } \ +} + + +/** + * @brief Pack a change_operator_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, version); + _mav_put_char_array(buf, 3, passkey, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#else + mavlink_change_operator_control_t packet; + packet.target_system = target_system; + packet.control_request = control_request; + packet.version = version; + mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif +} + +/** + * @brief Pack a change_operator_control message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t control_request,uint8_t version,const char *passkey) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, version); + _mav_put_char_array(buf, 3, passkey, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#else + mavlink_change_operator_control_t packet; + packet.target_system = target_system; + packet.control_request = control_request; + packet.version = version; + mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif +} + +/** + * @brief Encode a change_operator_control struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param change_operator_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control) +{ + return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); +} + +/** + * @brief Encode a change_operator_control struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param change_operator_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_change_operator_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control) +{ + return mavlink_msg_change_operator_control_pack_chan(system_id, component_id, chan, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); +} + +/** + * @brief Send a change_operator_control message + * @param chan MAVLink channel to send the message + * + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, version); + _mav_put_char_array(buf, 3, passkey, 25); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif +#else + mavlink_change_operator_control_t packet; + packet.target_system = target_system; + packet.control_request = control_request; + packet.version = version; + mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_change_operator_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, version); + _mav_put_char_array(buf, 3, passkey, 25); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif +#else + mavlink_change_operator_control_t *packet = (mavlink_change_operator_control_t *)msgbuf; + packet->target_system = target_system; + packet->control_request = control_request; + packet->version = version; + mav_array_memcpy(packet->passkey, passkey, sizeof(char)*25); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING + + +/** + * @brief Get field target_system from change_operator_control message + * + * @return System the GCS requests control for + */ +static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field control_request from change_operator_control message + * + * @return 0: request control of this MAV, 1: Release control of this MAV + */ +static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field version from change_operator_control message + * + * @return 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + */ +static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field passkey from change_operator_control message + * + * @return Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + */ +static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char *passkey) +{ + return _MAV_RETURN_char_array(msg, passkey, 25, 3); +} + +/** + * @brief Decode a change_operator_control message into a struct + * + * @param msg The message to decode + * @param change_operator_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg); + change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg); + change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg); + mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey); +#else + memcpy(change_operator_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h new file mode 100644 index 0000000..309fa04 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h @@ -0,0 +1,257 @@ +// MESSAGE CHANGE_OPERATOR_CONTROL_ACK PACKING + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6 + +typedef struct __mavlink_change_operator_control_ack_t +{ + uint8_t gcs_system_id; /*< ID of the GCS this message */ + uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/ + uint8_t ack; /*< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control*/ +} mavlink_change_operator_control_ack_t; + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3 +#define MAVLINK_MSG_ID_6_LEN 3 + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC 104 +#define MAVLINK_MSG_ID_6_CRC 104 + + + +#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \ + "CHANGE_OPERATOR_CONTROL_ACK", \ + 3, \ + { { "gcs_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \ + { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \ + { "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \ + } \ +} + + +/** + * @brief Pack a change_operator_control_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN]; + _mav_put_uint8_t(buf, 0, gcs_system_id); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, ack); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#else + mavlink_change_operator_control_ack_t packet; + packet.gcs_system_id = gcs_system_id; + packet.control_request = control_request; + packet.ack = ack; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif +} + +/** + * @brief Pack a change_operator_control_ack message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t gcs_system_id,uint8_t control_request,uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN]; + _mav_put_uint8_t(buf, 0, gcs_system_id); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, ack); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#else + mavlink_change_operator_control_ack_t packet; + packet.gcs_system_id = gcs_system_id; + packet.control_request = control_request; + packet.ack = ack; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif +} + +/** + * @brief Encode a change_operator_control_ack struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param change_operator_control_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack) +{ + return mavlink_msg_change_operator_control_ack_pack(system_id, component_id, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); +} + +/** + * @brief Encode a change_operator_control_ack struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param change_operator_control_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack) +{ + return mavlink_msg_change_operator_control_ack_pack_chan(system_id, component_id, chan, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); +} + +/** + * @brief Send a change_operator_control_ack message + * @param chan MAVLink channel to send the message + * + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN]; + _mav_put_uint8_t(buf, 0, gcs_system_id); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, ack); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif +#else + mavlink_change_operator_control_ack_t packet; + packet.gcs_system_id = gcs_system_id; + packet.control_request = control_request; + packet.ack = ack; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_change_operator_control_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, gcs_system_id); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, ack); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif +#else + mavlink_change_operator_control_ack_t *packet = (mavlink_change_operator_control_ack_t *)msgbuf; + packet->gcs_system_id = gcs_system_id; + packet->control_request = control_request; + packet->ack = ack; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE CHANGE_OPERATOR_CONTROL_ACK UNPACKING + + +/** + * @brief Get field gcs_system_id from change_operator_control_ack message + * + * @return ID of the GCS this message + */ +static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field control_request from change_operator_control_ack message + * + * @return 0: request control of this MAV, 1: Release control of this MAV + */ +static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field ack from change_operator_control_ack message + * + * @return 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + */ +static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a change_operator_control_ack message into a struct + * + * @param msg The message to decode + * @param change_operator_control_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_message_t* msg, mavlink_change_operator_control_ack_t* change_operator_control_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + change_operator_control_ack->gcs_system_id = mavlink_msg_change_operator_control_ack_get_gcs_system_id(msg); + change_operator_control_ack->control_request = mavlink_msg_change_operator_control_ack_get_control_request(msg); + change_operator_control_ack->ack = mavlink_msg_change_operator_control_ack_get_ack(msg); +#else + memcpy(change_operator_control_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_command_ack.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_command_ack.h new file mode 100644 index 0000000..2caebb0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_command_ack.h @@ -0,0 +1,233 @@ +// MESSAGE COMMAND_ACK PACKING + +#define MAVLINK_MSG_ID_COMMAND_ACK 77 + +typedef struct __mavlink_command_ack_t +{ + uint16_t command; /*< Command ID, as defined by MAV_CMD enum.*/ + uint8_t result; /*< See MAV_RESULT enum*/ +} mavlink_command_ack_t; + +#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3 +#define MAVLINK_MSG_ID_77_LEN 3 + +#define MAVLINK_MSG_ID_COMMAND_ACK_CRC 143 +#define MAVLINK_MSG_ID_77_CRC 143 + + + +#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \ + "COMMAND_ACK", \ + 2, \ + { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \ + { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \ + } \ +} + + +/** + * @brief Pack a command_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param command Command ID, as defined by MAV_CMD enum. + * @param result See MAV_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t command, uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN]; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, result); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#else + mavlink_command_ack_t packet; + packet.command = command; + packet.result = result; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif +} + +/** + * @brief Pack a command_ack message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param command Command ID, as defined by MAV_CMD enum. + * @param result See MAV_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t command,uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN]; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, result); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#else + mavlink_command_ack_t packet; + packet.command = command; + packet.result = result; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif +} + +/** + * @brief Encode a command_ack struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param command_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack) +{ + return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result); +} + +/** + * @brief Encode a command_ack struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param command_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack) +{ + return mavlink_msg_command_ack_pack_chan(system_id, component_id, chan, msg, command_ack->command, command_ack->result); +} + +/** + * @brief Send a command_ack message + * @param chan MAVLink channel to send the message + * + * @param command Command ID, as defined by MAV_CMD enum. + * @param result See MAV_RESULT enum + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN]; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, result); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif +#else + mavlink_command_ack_t packet; + packet.command = command; + packet.result = result; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_COMMAND_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t command, uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, result); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif +#else + mavlink_command_ack_t *packet = (mavlink_command_ack_t *)msgbuf; + packet->command = command; + packet->result = result; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE COMMAND_ACK UNPACKING + + +/** + * @brief Get field command from command_ack message + * + * @return Command ID, as defined by MAV_CMD enum. + */ +static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field result from command_ack message + * + * @return See MAV_RESULT enum + */ +static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a command_ack message into a struct + * + * @param msg The message to decode + * @param command_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + command_ack->command = mavlink_msg_command_ack_get_command(msg); + command_ack->result = mavlink_msg_command_ack_get_result(msg); +#else + memcpy(command_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_command_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_command_int.h new file mode 100644 index 0000000..9f4e6f9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_command_int.h @@ -0,0 +1,497 @@ +// MESSAGE COMMAND_INT PACKING + +#define MAVLINK_MSG_ID_COMMAND_INT 75 + +typedef struct __mavlink_command_int_t +{ + float param1; /*< PARAM1, see MAV_CMD enum*/ + float param2; /*< PARAM2, see MAV_CMD enum*/ + float param3; /*< PARAM3, see MAV_CMD enum*/ + float param4; /*< PARAM4, see MAV_CMD enum*/ + int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/ + int32_t y; /*< PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7*/ + float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/ + uint16_t command; /*< The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t frame; /*< The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h*/ + uint8_t current; /*< false:0, true:1*/ + uint8_t autocontinue; /*< autocontinue to next wp*/ +} mavlink_command_int_t; + +#define MAVLINK_MSG_ID_COMMAND_INT_LEN 35 +#define MAVLINK_MSG_ID_75_LEN 35 + +#define MAVLINK_MSG_ID_COMMAND_INT_CRC 158 +#define MAVLINK_MSG_ID_75_CRC 158 + + + +#define MAVLINK_MESSAGE_INFO_COMMAND_INT { \ + "COMMAND_INT", \ + 13, \ + { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \ + { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \ + } \ +} + + +/** + * @brief Pack a command_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, frame); + _mav_put_uint8_t(buf, 33, current); + _mav_put_uint8_t(buf, 34, autocontinue); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#else + mavlink_command_int_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif +} + +/** + * @brief Pack a command_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,int32_t x,int32_t y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, frame); + _mav_put_uint8_t(buf, 33, current); + _mav_put_uint8_t(buf, 34, autocontinue); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#else + mavlink_command_int_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif +} + +/** + * @brief Encode a command_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param command_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_int_t* command_int) +{ + return mavlink_msg_command_int_pack(system_id, component_id, msg, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z); +} + +/** + * @brief Encode a command_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param command_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_int_t* command_int) +{ + return mavlink_msg_command_int_pack_chan(system_id, component_id, chan, msg, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z); +} + +/** + * @brief Send a command_int message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_command_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, frame); + _mav_put_uint8_t(buf, 33, current); + _mav_put_uint8_t(buf, 34, autocontinue); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif +#else + mavlink_command_int_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_COMMAND_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_command_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, frame); + _mav_put_uint8_t(buf, 33, current); + _mav_put_uint8_t(buf, 34, autocontinue); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif +#else + mavlink_command_int_t *packet = (mavlink_command_int_t *)msgbuf; + packet->param1 = param1; + packet->param2 = param2; + packet->param3 = param3; + packet->param4 = param4; + packet->x = x; + packet->y = y; + packet->z = z; + packet->command = command; + packet->target_system = target_system; + packet->target_component = target_component; + packet->frame = frame; + packet->current = current; + packet->autocontinue = autocontinue; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)packet, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)packet, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE COMMAND_INT UNPACKING + + +/** + * @brief Get field target_system from command_int message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_command_int_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 30); +} + +/** + * @brief Get field target_component from command_int message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_command_int_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 31); +} + +/** + * @brief Get field frame from command_int message + * + * @return The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h + */ +static inline uint8_t mavlink_msg_command_int_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field command from command_int message + * + * @return The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs + */ +static inline uint16_t mavlink_msg_command_int_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field current from command_int message + * + * @return false:0, true:1 + */ +static inline uint8_t mavlink_msg_command_int_get_current(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field autocontinue from command_int message + * + * @return autocontinue to next wp + */ +static inline uint8_t mavlink_msg_command_int_get_autocontinue(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field param1 from command_int message + * + * @return PARAM1, see MAV_CMD enum + */ +static inline float mavlink_msg_command_int_get_param1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param2 from command_int message + * + * @return PARAM2, see MAV_CMD enum + */ +static inline float mavlink_msg_command_int_get_param2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param3 from command_int message + * + * @return PARAM3, see MAV_CMD enum + */ +static inline float mavlink_msg_command_int_get_param3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param4 from command_int message + * + * @return PARAM4, see MAV_CMD enum + */ +static inline float mavlink_msg_command_int_get_param4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field x from command_int message + * + * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + */ +static inline int32_t mavlink_msg_command_int_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field y from command_int message + * + * @return PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + */ +static inline int32_t mavlink_msg_command_int_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 20); +} + +/** + * @brief Get field z from command_int message + * + * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + */ +static inline float mavlink_msg_command_int_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a command_int message into a struct + * + * @param msg The message to decode + * @param command_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_command_int_decode(const mavlink_message_t* msg, mavlink_command_int_t* command_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + command_int->param1 = mavlink_msg_command_int_get_param1(msg); + command_int->param2 = mavlink_msg_command_int_get_param2(msg); + command_int->param3 = mavlink_msg_command_int_get_param3(msg); + command_int->param4 = mavlink_msg_command_int_get_param4(msg); + command_int->x = mavlink_msg_command_int_get_x(msg); + command_int->y = mavlink_msg_command_int_get_y(msg); + command_int->z = mavlink_msg_command_int_get_z(msg); + command_int->command = mavlink_msg_command_int_get_command(msg); + command_int->target_system = mavlink_msg_command_int_get_target_system(msg); + command_int->target_component = mavlink_msg_command_int_get_target_component(msg); + command_int->frame = mavlink_msg_command_int_get_frame(msg); + command_int->current = mavlink_msg_command_int_get_current(msg); + command_int->autocontinue = mavlink_msg_command_int_get_autocontinue(msg); +#else + memcpy(command_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_command_long.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_command_long.h new file mode 100644 index 0000000..7c7f1c0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_command_long.h @@ -0,0 +1,449 @@ +// MESSAGE COMMAND_LONG PACKING + +#define MAVLINK_MSG_ID_COMMAND_LONG 76 + +typedef struct __mavlink_command_long_t +{ + float param1; /*< Parameter 1, as defined by MAV_CMD enum.*/ + float param2; /*< Parameter 2, as defined by MAV_CMD enum.*/ + float param3; /*< Parameter 3, as defined by MAV_CMD enum.*/ + float param4; /*< Parameter 4, as defined by MAV_CMD enum.*/ + float param5; /*< Parameter 5, as defined by MAV_CMD enum.*/ + float param6; /*< Parameter 6, as defined by MAV_CMD enum.*/ + float param7; /*< Parameter 7, as defined by MAV_CMD enum.*/ + uint16_t command; /*< Command ID, as defined by MAV_CMD enum.*/ + uint8_t target_system; /*< System which should execute the command*/ + uint8_t target_component; /*< Component which should execute the command, 0 for all components*/ + uint8_t confirmation; /*< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)*/ +} mavlink_command_long_t; + +#define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33 +#define MAVLINK_MSG_ID_76_LEN 33 + +#define MAVLINK_MSG_ID_COMMAND_LONG_CRC 152 +#define MAVLINK_MSG_ID_76_CRC 152 + + + +#define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \ + "COMMAND_LONG", \ + 11, \ + { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \ + { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \ + { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \ + { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ + { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ + } \ +} + + +/** + * @brief Pack a command_long message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @param param5 Parameter 5, as defined by MAV_CMD enum. + * @param param6 Parameter 6, as defined by MAV_CMD enum. + * @param param7 Parameter 7, as defined by MAV_CMD enum. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, param5); + _mav_put_float(buf, 20, param6); + _mav_put_float(buf, 24, param7); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, confirmation); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#else + mavlink_command_long_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.param5 = param5; + packet.param6 = param6; + packet.param7 = param7; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.confirmation = confirmation; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif +} + +/** + * @brief Pack a command_long message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @param param5 Parameter 5, as defined by MAV_CMD enum. + * @param param6 Parameter 6, as defined by MAV_CMD enum. + * @param param7 Parameter 7, as defined by MAV_CMD enum. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t command,uint8_t confirmation,float param1,float param2,float param3,float param4,float param5,float param6,float param7) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, param5); + _mav_put_float(buf, 20, param6); + _mav_put_float(buf, 24, param7); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, confirmation); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#else + mavlink_command_long_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.param5 = param5; + packet.param6 = param6; + packet.param7 = param7; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.confirmation = confirmation; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif +} + +/** + * @brief Encode a command_long struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param command_long C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_long_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_long_t* command_long) +{ + return mavlink_msg_command_long_pack(system_id, component_id, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); +} + +/** + * @brief Encode a command_long struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param command_long C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_long_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_long_t* command_long) +{ + return mavlink_msg_command_long_pack_chan(system_id, component_id, chan, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); +} + +/** + * @brief Send a command_long message + * @param chan MAVLink channel to send the message + * + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @param param5 Parameter 5, as defined by MAV_CMD enum. + * @param param6 Parameter 6, as defined by MAV_CMD enum. + * @param param7 Parameter 7, as defined by MAV_CMD enum. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_command_long_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, param5); + _mav_put_float(buf, 20, param6); + _mav_put_float(buf, 24, param7); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, confirmation); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif +#else + mavlink_command_long_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.param5 = param5; + packet.param6 = param6; + packet.param7 = param7; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.confirmation = confirmation; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_COMMAND_LONG_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_command_long_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, param5); + _mav_put_float(buf, 20, param6); + _mav_put_float(buf, 24, param7); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, confirmation); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif +#else + mavlink_command_long_t *packet = (mavlink_command_long_t *)msgbuf; + packet->param1 = param1; + packet->param2 = param2; + packet->param3 = param3; + packet->param4 = param4; + packet->param5 = param5; + packet->param6 = param6; + packet->param7 = param7; + packet->command = command; + packet->target_system = target_system; + packet->target_component = target_component; + packet->confirmation = confirmation; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE COMMAND_LONG UNPACKING + + +/** + * @brief Get field target_system from command_long message + * + * @return System which should execute the command + */ +static inline uint8_t mavlink_msg_command_long_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 30); +} + +/** + * @brief Get field target_component from command_long message + * + * @return Component which should execute the command, 0 for all components + */ +static inline uint8_t mavlink_msg_command_long_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 31); +} + +/** + * @brief Get field command from command_long message + * + * @return Command ID, as defined by MAV_CMD enum. + */ +static inline uint16_t mavlink_msg_command_long_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field confirmation from command_long message + * + * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + */ +static inline uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field param1 from command_long message + * + * @return Parameter 1, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param2 from command_long message + * + * @return Parameter 2, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param3 from command_long message + * + * @return Parameter 3, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param4 from command_long message + * + * @return Parameter 4, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field param5 from command_long message + * + * @return Parameter 5, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field param6 from command_long message + * + * @return Parameter 6, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field param7 from command_long message + * + * @return Parameter 7, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param7(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a command_long message into a struct + * + * @param msg The message to decode + * @param command_long C-struct to decode the message contents into + */ +static inline void mavlink_msg_command_long_decode(const mavlink_message_t* msg, mavlink_command_long_t* command_long) +{ +#if MAVLINK_NEED_BYTE_SWAP + command_long->param1 = mavlink_msg_command_long_get_param1(msg); + command_long->param2 = mavlink_msg_command_long_get_param2(msg); + command_long->param3 = mavlink_msg_command_long_get_param3(msg); + command_long->param4 = mavlink_msg_command_long_get_param4(msg); + command_long->param5 = mavlink_msg_command_long_get_param5(msg); + command_long->param6 = mavlink_msg_command_long_get_param6(msg); + command_long->param7 = mavlink_msg_command_long_get_param7(msg); + command_long->command = mavlink_msg_command_long_get_command(msg); + command_long->target_system = mavlink_msg_command_long_get_target_system(msg); + command_long->target_component = mavlink_msg_command_long_get_target_component(msg); + command_long->confirmation = mavlink_msg_command_long_get_confirmation(msg); +#else + memcpy(command_long, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_control_system_state.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_control_system_state.h new file mode 100644 index 0000000..e06a68f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_control_system_state.h @@ -0,0 +1,587 @@ +// MESSAGE CONTROL_SYSTEM_STATE PACKING + +#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE 146 + +typedef struct __mavlink_control_system_state_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float x_acc; /*< X acceleration in body frame*/ + float y_acc; /*< Y acceleration in body frame*/ + float z_acc; /*< Z acceleration in body frame*/ + float x_vel; /*< X velocity in body frame*/ + float y_vel; /*< Y velocity in body frame*/ + float z_vel; /*< Z velocity in body frame*/ + float x_pos; /*< X position in local frame*/ + float y_pos; /*< Y position in local frame*/ + float z_pos; /*< Z position in local frame*/ + float airspeed; /*< Airspeed, set to -1 if unknown*/ + float vel_variance[3]; /*< Variance of body velocity estimate*/ + float pos_variance[3]; /*< Variance in local position*/ + float q[4]; /*< The attitude, represented as Quaternion*/ + float roll_rate; /*< Angular rate in roll axis*/ + float pitch_rate; /*< Angular rate in pitch axis*/ + float yaw_rate; /*< Angular rate in yaw axis*/ +} mavlink_control_system_state_t; + +#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN 100 +#define MAVLINK_MSG_ID_146_LEN 100 + +#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC 103 +#define MAVLINK_MSG_ID_146_CRC 103 + +#define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_VEL_VARIANCE_LEN 3 +#define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_POS_VARIANCE_LEN 3 +#define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_Q_LEN 4 + +#define MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE { \ + "CONTROL_SYSTEM_STATE", \ + 17, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_control_system_state_t, time_usec) }, \ + { "x_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_control_system_state_t, x_acc) }, \ + { "y_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_control_system_state_t, y_acc) }, \ + { "z_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_control_system_state_t, z_acc) }, \ + { "x_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_control_system_state_t, x_vel) }, \ + { "y_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_control_system_state_t, y_vel) }, \ + { "z_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_control_system_state_t, z_vel) }, \ + { "x_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_control_system_state_t, x_pos) }, \ + { "y_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_control_system_state_t, y_pos) }, \ + { "z_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_control_system_state_t, z_pos) }, \ + { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_control_system_state_t, airspeed) }, \ + { "vel_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 48, offsetof(mavlink_control_system_state_t, vel_variance) }, \ + { "pos_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 60, offsetof(mavlink_control_system_state_t, pos_variance) }, \ + { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 72, offsetof(mavlink_control_system_state_t, q) }, \ + { "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_control_system_state_t, roll_rate) }, \ + { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_control_system_state_t, pitch_rate) }, \ + { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_control_system_state_t, yaw_rate) }, \ + } \ +} + + +/** + * @brief Pack a control_system_state message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param x_acc X acceleration in body frame + * @param y_acc Y acceleration in body frame + * @param z_acc Z acceleration in body frame + * @param x_vel X velocity in body frame + * @param y_vel Y velocity in body frame + * @param z_vel Z velocity in body frame + * @param x_pos X position in local frame + * @param y_pos Y position in local frame + * @param z_pos Z position in local frame + * @param airspeed Airspeed, set to -1 if unknown + * @param vel_variance Variance of body velocity estimate + * @param pos_variance Variance in local position + * @param q The attitude, represented as Quaternion + * @param roll_rate Angular rate in roll axis + * @param pitch_rate Angular rate in pitch axis + * @param yaw_rate Angular rate in yaw axis + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_control_system_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x_acc); + _mav_put_float(buf, 12, y_acc); + _mav_put_float(buf, 16, z_acc); + _mav_put_float(buf, 20, x_vel); + _mav_put_float(buf, 24, y_vel); + _mav_put_float(buf, 28, z_vel); + _mav_put_float(buf, 32, x_pos); + _mav_put_float(buf, 36, y_pos); + _mav_put_float(buf, 40, z_pos); + _mav_put_float(buf, 44, airspeed); + _mav_put_float(buf, 88, roll_rate); + _mav_put_float(buf, 92, pitch_rate); + _mav_put_float(buf, 96, yaw_rate); + _mav_put_float_array(buf, 48, vel_variance, 3); + _mav_put_float_array(buf, 60, pos_variance, 3); + _mav_put_float_array(buf, 72, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#else + mavlink_control_system_state_t packet; + packet.time_usec = time_usec; + packet.x_acc = x_acc; + packet.y_acc = y_acc; + packet.z_acc = z_acc; + packet.x_vel = x_vel; + packet.y_vel = y_vel; + packet.z_vel = z_vel; + packet.x_pos = x_pos; + packet.y_pos = y_pos; + packet.z_pos = z_pos; + packet.airspeed = airspeed; + packet.roll_rate = roll_rate; + packet.pitch_rate = pitch_rate; + packet.yaw_rate = yaw_rate; + mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3); + mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3); + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif +} + +/** + * @brief Pack a control_system_state message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param x_acc X acceleration in body frame + * @param y_acc Y acceleration in body frame + * @param z_acc Z acceleration in body frame + * @param x_vel X velocity in body frame + * @param y_vel Y velocity in body frame + * @param z_vel Z velocity in body frame + * @param x_pos X position in local frame + * @param y_pos Y position in local frame + * @param z_pos Z position in local frame + * @param airspeed Airspeed, set to -1 if unknown + * @param vel_variance Variance of body velocity estimate + * @param pos_variance Variance in local position + * @param q The attitude, represented as Quaternion + * @param roll_rate Angular rate in roll axis + * @param pitch_rate Angular rate in pitch axis + * @param yaw_rate Angular rate in yaw axis + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_control_system_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float x_acc,float y_acc,float z_acc,float x_vel,float y_vel,float z_vel,float x_pos,float y_pos,float z_pos,float airspeed,const float *vel_variance,const float *pos_variance,const float *q,float roll_rate,float pitch_rate,float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x_acc); + _mav_put_float(buf, 12, y_acc); + _mav_put_float(buf, 16, z_acc); + _mav_put_float(buf, 20, x_vel); + _mav_put_float(buf, 24, y_vel); + _mav_put_float(buf, 28, z_vel); + _mav_put_float(buf, 32, x_pos); + _mav_put_float(buf, 36, y_pos); + _mav_put_float(buf, 40, z_pos); + _mav_put_float(buf, 44, airspeed); + _mav_put_float(buf, 88, roll_rate); + _mav_put_float(buf, 92, pitch_rate); + _mav_put_float(buf, 96, yaw_rate); + _mav_put_float_array(buf, 48, vel_variance, 3); + _mav_put_float_array(buf, 60, pos_variance, 3); + _mav_put_float_array(buf, 72, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#else + mavlink_control_system_state_t packet; + packet.time_usec = time_usec; + packet.x_acc = x_acc; + packet.y_acc = y_acc; + packet.z_acc = z_acc; + packet.x_vel = x_vel; + packet.y_vel = y_vel; + packet.z_vel = z_vel; + packet.x_pos = x_pos; + packet.y_pos = y_pos; + packet.z_pos = z_pos; + packet.airspeed = airspeed; + packet.roll_rate = roll_rate; + packet.pitch_rate = pitch_rate; + packet.yaw_rate = yaw_rate; + mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3); + mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3); + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif +} + +/** + * @brief Encode a control_system_state struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param control_system_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_control_system_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_control_system_state_t* control_system_state) +{ + return mavlink_msg_control_system_state_pack(system_id, component_id, msg, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate); +} + +/** + * @brief Encode a control_system_state struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param control_system_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_control_system_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_control_system_state_t* control_system_state) +{ + return mavlink_msg_control_system_state_pack_chan(system_id, component_id, chan, msg, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate); +} + +/** + * @brief Send a control_system_state message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param x_acc X acceleration in body frame + * @param y_acc Y acceleration in body frame + * @param z_acc Z acceleration in body frame + * @param x_vel X velocity in body frame + * @param y_vel Y velocity in body frame + * @param z_vel Z velocity in body frame + * @param x_pos X position in local frame + * @param y_pos Y position in local frame + * @param z_pos Z position in local frame + * @param airspeed Airspeed, set to -1 if unknown + * @param vel_variance Variance of body velocity estimate + * @param pos_variance Variance in local position + * @param q The attitude, represented as Quaternion + * @param roll_rate Angular rate in roll axis + * @param pitch_rate Angular rate in pitch axis + * @param yaw_rate Angular rate in yaw axis + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_control_system_state_send(mavlink_channel_t chan, uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x_acc); + _mav_put_float(buf, 12, y_acc); + _mav_put_float(buf, 16, z_acc); + _mav_put_float(buf, 20, x_vel); + _mav_put_float(buf, 24, y_vel); + _mav_put_float(buf, 28, z_vel); + _mav_put_float(buf, 32, x_pos); + _mav_put_float(buf, 36, y_pos); + _mav_put_float(buf, 40, z_pos); + _mav_put_float(buf, 44, airspeed); + _mav_put_float(buf, 88, roll_rate); + _mav_put_float(buf, 92, pitch_rate); + _mav_put_float(buf, 96, yaw_rate); + _mav_put_float_array(buf, 48, vel_variance, 3); + _mav_put_float_array(buf, 60, pos_variance, 3); + _mav_put_float_array(buf, 72, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif +#else + mavlink_control_system_state_t packet; + packet.time_usec = time_usec; + packet.x_acc = x_acc; + packet.y_acc = y_acc; + packet.z_acc = z_acc; + packet.x_vel = x_vel; + packet.y_vel = y_vel; + packet.z_vel = z_vel; + packet.x_pos = x_pos; + packet.y_pos = y_pos; + packet.z_pos = z_pos; + packet.airspeed = airspeed; + packet.roll_rate = roll_rate; + packet.pitch_rate = pitch_rate; + packet.yaw_rate = yaw_rate; + mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3); + mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3); + mav_array_memcpy(packet.q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)&packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)&packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_control_system_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x_acc); + _mav_put_float(buf, 12, y_acc); + _mav_put_float(buf, 16, z_acc); + _mav_put_float(buf, 20, x_vel); + _mav_put_float(buf, 24, y_vel); + _mav_put_float(buf, 28, z_vel); + _mav_put_float(buf, 32, x_pos); + _mav_put_float(buf, 36, y_pos); + _mav_put_float(buf, 40, z_pos); + _mav_put_float(buf, 44, airspeed); + _mav_put_float(buf, 88, roll_rate); + _mav_put_float(buf, 92, pitch_rate); + _mav_put_float(buf, 96, yaw_rate); + _mav_put_float_array(buf, 48, vel_variance, 3); + _mav_put_float_array(buf, 60, pos_variance, 3); + _mav_put_float_array(buf, 72, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif +#else + mavlink_control_system_state_t *packet = (mavlink_control_system_state_t *)msgbuf; + packet->time_usec = time_usec; + packet->x_acc = x_acc; + packet->y_acc = y_acc; + packet->z_acc = z_acc; + packet->x_vel = x_vel; + packet->y_vel = y_vel; + packet->z_vel = z_vel; + packet->x_pos = x_pos; + packet->y_pos = y_pos; + packet->z_pos = z_pos; + packet->airspeed = airspeed; + packet->roll_rate = roll_rate; + packet->pitch_rate = pitch_rate; + packet->yaw_rate = yaw_rate; + mav_array_memcpy(packet->vel_variance, vel_variance, sizeof(float)*3); + mav_array_memcpy(packet->pos_variance, pos_variance, sizeof(float)*3); + mav_array_memcpy(packet->q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE CONTROL_SYSTEM_STATE UNPACKING + + +/** + * @brief Get field time_usec from control_system_state message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_control_system_state_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x_acc from control_system_state message + * + * @return X acceleration in body frame + */ +static inline float mavlink_msg_control_system_state_get_x_acc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y_acc from control_system_state message + * + * @return Y acceleration in body frame + */ +static inline float mavlink_msg_control_system_state_get_y_acc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z_acc from control_system_state message + * + * @return Z acceleration in body frame + */ +static inline float mavlink_msg_control_system_state_get_z_acc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field x_vel from control_system_state message + * + * @return X velocity in body frame + */ +static inline float mavlink_msg_control_system_state_get_x_vel(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field y_vel from control_system_state message + * + * @return Y velocity in body frame + */ +static inline float mavlink_msg_control_system_state_get_y_vel(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field z_vel from control_system_state message + * + * @return Z velocity in body frame + */ +static inline float mavlink_msg_control_system_state_get_z_vel(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field x_pos from control_system_state message + * + * @return X position in local frame + */ +static inline float mavlink_msg_control_system_state_get_x_pos(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field y_pos from control_system_state message + * + * @return Y position in local frame + */ +static inline float mavlink_msg_control_system_state_get_y_pos(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field z_pos from control_system_state message + * + * @return Z position in local frame + */ +static inline float mavlink_msg_control_system_state_get_z_pos(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field airspeed from control_system_state message + * + * @return Airspeed, set to -1 if unknown + */ +static inline float mavlink_msg_control_system_state_get_airspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field vel_variance from control_system_state message + * + * @return Variance of body velocity estimate + */ +static inline uint16_t mavlink_msg_control_system_state_get_vel_variance(const mavlink_message_t* msg, float *vel_variance) +{ + return _MAV_RETURN_float_array(msg, vel_variance, 3, 48); +} + +/** + * @brief Get field pos_variance from control_system_state message + * + * @return Variance in local position + */ +static inline uint16_t mavlink_msg_control_system_state_get_pos_variance(const mavlink_message_t* msg, float *pos_variance) +{ + return _MAV_RETURN_float_array(msg, pos_variance, 3, 60); +} + +/** + * @brief Get field q from control_system_state message + * + * @return The attitude, represented as Quaternion + */ +static inline uint16_t mavlink_msg_control_system_state_get_q(const mavlink_message_t* msg, float *q) +{ + return _MAV_RETURN_float_array(msg, q, 4, 72); +} + +/** + * @brief Get field roll_rate from control_system_state message + * + * @return Angular rate in roll axis + */ +static inline float mavlink_msg_control_system_state_get_roll_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 88); +} + +/** + * @brief Get field pitch_rate from control_system_state message + * + * @return Angular rate in pitch axis + */ +static inline float mavlink_msg_control_system_state_get_pitch_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 92); +} + +/** + * @brief Get field yaw_rate from control_system_state message + * + * @return Angular rate in yaw axis + */ +static inline float mavlink_msg_control_system_state_get_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 96); +} + +/** + * @brief Decode a control_system_state message into a struct + * + * @param msg The message to decode + * @param control_system_state C-struct to decode the message contents into + */ +static inline void mavlink_msg_control_system_state_decode(const mavlink_message_t* msg, mavlink_control_system_state_t* control_system_state) +{ +#if MAVLINK_NEED_BYTE_SWAP + control_system_state->time_usec = mavlink_msg_control_system_state_get_time_usec(msg); + control_system_state->x_acc = mavlink_msg_control_system_state_get_x_acc(msg); + control_system_state->y_acc = mavlink_msg_control_system_state_get_y_acc(msg); + control_system_state->z_acc = mavlink_msg_control_system_state_get_z_acc(msg); + control_system_state->x_vel = mavlink_msg_control_system_state_get_x_vel(msg); + control_system_state->y_vel = mavlink_msg_control_system_state_get_y_vel(msg); + control_system_state->z_vel = mavlink_msg_control_system_state_get_z_vel(msg); + control_system_state->x_pos = mavlink_msg_control_system_state_get_x_pos(msg); + control_system_state->y_pos = mavlink_msg_control_system_state_get_y_pos(msg); + control_system_state->z_pos = mavlink_msg_control_system_state_get_z_pos(msg); + control_system_state->airspeed = mavlink_msg_control_system_state_get_airspeed(msg); + mavlink_msg_control_system_state_get_vel_variance(msg, control_system_state->vel_variance); + mavlink_msg_control_system_state_get_pos_variance(msg, control_system_state->pos_variance); + mavlink_msg_control_system_state_get_q(msg, control_system_state->q); + control_system_state->roll_rate = mavlink_msg_control_system_state_get_roll_rate(msg); + control_system_state->pitch_rate = mavlink_msg_control_system_state_get_pitch_rate(msg); + control_system_state->yaw_rate = mavlink_msg_control_system_state_get_yaw_rate(msg); +#else + memcpy(control_system_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_data_stream.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_data_stream.h new file mode 100644 index 0000000..0e12a60 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_data_stream.h @@ -0,0 +1,257 @@ +// MESSAGE DATA_STREAM PACKING + +#define MAVLINK_MSG_ID_DATA_STREAM 67 + +typedef struct __mavlink_data_stream_t +{ + uint16_t message_rate; /*< The message rate*/ + uint8_t stream_id; /*< The ID of the requested data stream*/ + uint8_t on_off; /*< 1 stream is enabled, 0 stream is stopped.*/ +} mavlink_data_stream_t; + +#define MAVLINK_MSG_ID_DATA_STREAM_LEN 4 +#define MAVLINK_MSG_ID_67_LEN 4 + +#define MAVLINK_MSG_ID_DATA_STREAM_CRC 21 +#define MAVLINK_MSG_ID_67_CRC 21 + + + +#define MAVLINK_MESSAGE_INFO_DATA_STREAM { \ + "DATA_STREAM", \ + 3, \ + { { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ + { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ + { "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \ + } \ +} + + +/** + * @brief Pack a data_stream message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param stream_id The ID of the requested data stream + * @param message_rate The message rate + * @param on_off 1 stream is enabled, 0 stream is stopped. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t stream_id, uint16_t message_rate, uint8_t on_off) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DATA_STREAM_LEN]; + _mav_put_uint16_t(buf, 0, message_rate); + _mav_put_uint8_t(buf, 2, stream_id); + _mav_put_uint8_t(buf, 3, on_off); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#else + mavlink_data_stream_t packet; + packet.message_rate = message_rate; + packet.stream_id = stream_id; + packet.on_off = on_off; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif +} + +/** + * @brief Pack a data_stream message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param stream_id The ID of the requested data stream + * @param message_rate The message rate + * @param on_off 1 stream is enabled, 0 stream is stopped. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t stream_id,uint16_t message_rate,uint8_t on_off) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DATA_STREAM_LEN]; + _mav_put_uint16_t(buf, 0, message_rate); + _mav_put_uint8_t(buf, 2, stream_id); + _mav_put_uint8_t(buf, 3, on_off); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#else + mavlink_data_stream_t packet; + packet.message_rate = message_rate; + packet.stream_id = stream_id; + packet.on_off = on_off; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif +} + +/** + * @brief Encode a data_stream struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param data_stream C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream) +{ + return mavlink_msg_data_stream_pack(system_id, component_id, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); +} + +/** + * @brief Encode a data_stream struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param data_stream C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream) +{ + return mavlink_msg_data_stream_pack_chan(system_id, component_id, chan, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); +} + +/** + * @brief Send a data_stream message + * @param chan MAVLink channel to send the message + * + * @param stream_id The ID of the requested data stream + * @param message_rate The message rate + * @param on_off 1 stream is enabled, 0 stream is stopped. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_data_stream_send(mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DATA_STREAM_LEN]; + _mav_put_uint16_t(buf, 0, message_rate); + _mav_put_uint8_t(buf, 2, stream_id); + _mav_put_uint8_t(buf, 3, on_off); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif +#else + mavlink_data_stream_t packet; + packet.message_rate = message_rate; + packet.stream_id = stream_id; + packet.on_off = on_off; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_data_stream_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, message_rate); + _mav_put_uint8_t(buf, 2, stream_id); + _mav_put_uint8_t(buf, 3, on_off); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif +#else + mavlink_data_stream_t *packet = (mavlink_data_stream_t *)msgbuf; + packet->message_rate = message_rate; + packet->stream_id = stream_id; + packet->on_off = on_off; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE DATA_STREAM UNPACKING + + +/** + * @brief Get field stream_id from data_stream message + * + * @return The ID of the requested data stream + */ +static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field message_rate from data_stream message + * + * @return The message rate + */ +static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field on_off from data_stream message + * + * @return 1 stream is enabled, 0 stream is stopped. + */ +static inline uint8_t mavlink_msg_data_stream_get_on_off(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Decode a data_stream message into a struct + * + * @param msg The message to decode + * @param data_stream C-struct to decode the message contents into + */ +static inline void mavlink_msg_data_stream_decode(const mavlink_message_t* msg, mavlink_data_stream_t* data_stream) +{ +#if MAVLINK_NEED_BYTE_SWAP + data_stream->message_rate = mavlink_msg_data_stream_get_message_rate(msg); + data_stream->stream_id = mavlink_msg_data_stream_get_stream_id(msg); + data_stream->on_off = mavlink_msg_data_stream_get_on_off(msg); +#else + memcpy(data_stream, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h new file mode 100644 index 0000000..c6b037a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h @@ -0,0 +1,353 @@ +// MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING + +#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 130 + +typedef struct __mavlink_data_transmission_handshake_t +{ + uint32_t size; /*< total data size in bytes (set on ACK only)*/ + uint16_t width; /*< Width of a matrix or image*/ + uint16_t height; /*< Height of a matrix or image*/ + uint16_t packets; /*< number of packets beeing sent (set on ACK only)*/ + uint8_t type; /*< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)*/ + uint8_t payload; /*< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)*/ + uint8_t jpg_quality; /*< JPEG quality out of [1,100]*/ +} mavlink_data_transmission_handshake_t; + +#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 13 +#define MAVLINK_MSG_ID_130_LEN 13 + +#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC 29 +#define MAVLINK_MSG_ID_130_CRC 29 + + + +#define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \ + "DATA_TRANSMISSION_HANDSHAKE", \ + 7, \ + { { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \ + { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \ + { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \ + { "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \ + { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \ + { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \ + } \ +} + + +/** + * @brief Pack a data_transmission_handshake message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + * @param size total data size in bytes (set on ACK only) + * @param width Width of a matrix or image + * @param height Height of a matrix or image + * @param packets number of packets beeing sent (set on ACK only) + * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + * @param jpg_quality JPEG quality out of [1,100] + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN]; + _mav_put_uint32_t(buf, 0, size); + _mav_put_uint16_t(buf, 4, width); + _mav_put_uint16_t(buf, 6, height); + _mav_put_uint16_t(buf, 8, packets); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, payload); + _mav_put_uint8_t(buf, 12, jpg_quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#else + mavlink_data_transmission_handshake_t packet; + packet.size = size; + packet.width = width; + packet.height = height; + packet.packets = packets; + packet.type = type; + packet.payload = payload; + packet.jpg_quality = jpg_quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif +} + +/** + * @brief Pack a data_transmission_handshake message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + * @param size total data size in bytes (set on ACK only) + * @param width Width of a matrix or image + * @param height Height of a matrix or image + * @param packets number of packets beeing sent (set on ACK only) + * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + * @param jpg_quality JPEG quality out of [1,100] + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t type,uint32_t size,uint16_t width,uint16_t height,uint16_t packets,uint8_t payload,uint8_t jpg_quality) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN]; + _mav_put_uint32_t(buf, 0, size); + _mav_put_uint16_t(buf, 4, width); + _mav_put_uint16_t(buf, 6, height); + _mav_put_uint16_t(buf, 8, packets); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, payload); + _mav_put_uint8_t(buf, 12, jpg_quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#else + mavlink_data_transmission_handshake_t packet; + packet.size = size; + packet.width = width; + packet.height = height; + packet.packets = packets; + packet.type = type; + packet.payload = payload; + packet.jpg_quality = jpg_quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif +} + +/** + * @brief Encode a data_transmission_handshake struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param data_transmission_handshake C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake) +{ + return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); +} + +/** + * @brief Encode a data_transmission_handshake struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param data_transmission_handshake C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake) +{ + return mavlink_msg_data_transmission_handshake_pack_chan(system_id, component_id, chan, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); +} + +/** + * @brief Send a data_transmission_handshake message + * @param chan MAVLink channel to send the message + * + * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + * @param size total data size in bytes (set on ACK only) + * @param width Width of a matrix or image + * @param height Height of a matrix or image + * @param packets number of packets beeing sent (set on ACK only) + * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + * @param jpg_quality JPEG quality out of [1,100] + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN]; + _mav_put_uint32_t(buf, 0, size); + _mav_put_uint16_t(buf, 4, width); + _mav_put_uint16_t(buf, 6, height); + _mav_put_uint16_t(buf, 8, packets); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, payload); + _mav_put_uint8_t(buf, 12, jpg_quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif +#else + mavlink_data_transmission_handshake_t packet; + packet.size = size; + packet.width = width; + packet.height = height; + packet.packets = packets; + packet.type = type; + packet.payload = payload; + packet.jpg_quality = jpg_quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_data_transmission_handshake_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, size); + _mav_put_uint16_t(buf, 4, width); + _mav_put_uint16_t(buf, 6, height); + _mav_put_uint16_t(buf, 8, packets); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, payload); + _mav_put_uint8_t(buf, 12, jpg_quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif +#else + mavlink_data_transmission_handshake_t *packet = (mavlink_data_transmission_handshake_t *)msgbuf; + packet->size = size; + packet->width = width; + packet->height = height; + packet->packets = packets; + packet->type = type; + packet->payload = payload; + packet->jpg_quality = jpg_quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE DATA_TRANSMISSION_HANDSHAKE UNPACKING + + +/** + * @brief Get field type from data_transmission_handshake message + * + * @return type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + */ +static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 10); +} + +/** + * @brief Get field size from data_transmission_handshake message + * + * @return total data size in bytes (set on ACK only) + */ +static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field width from data_transmission_handshake message + * + * @return Width of a matrix or image + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_get_width(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field height from data_transmission_handshake message + * + * @return Height of a matrix or image + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_get_height(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field packets from data_transmission_handshake message + * + * @return number of packets beeing sent (set on ACK only) + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field payload from data_transmission_handshake message + * + * @return payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + */ +static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 11); +} + +/** + * @brief Get field jpg_quality from data_transmission_handshake message + * + * @return JPEG quality out of [1,100] + */ +static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Decode a data_transmission_handshake message into a struct + * + * @param msg The message to decode + * @param data_transmission_handshake C-struct to decode the message contents into + */ +static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_message_t* msg, mavlink_data_transmission_handshake_t* data_transmission_handshake) +{ +#if MAVLINK_NEED_BYTE_SWAP + data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg); + data_transmission_handshake->width = mavlink_msg_data_transmission_handshake_get_width(msg); + data_transmission_handshake->height = mavlink_msg_data_transmission_handshake_get_height(msg); + data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg); + data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg); + data_transmission_handshake->payload = mavlink_msg_data_transmission_handshake_get_payload(msg); + data_transmission_handshake->jpg_quality = mavlink_msg_data_transmission_handshake_get_jpg_quality(msg); +#else + memcpy(data_transmission_handshake, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_debug.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_debug.h new file mode 100644 index 0000000..56928ab --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_debug.h @@ -0,0 +1,257 @@ +// MESSAGE DEBUG PACKING + +#define MAVLINK_MSG_ID_DEBUG 254 + +typedef struct __mavlink_debug_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float value; /*< DEBUG value*/ + uint8_t ind; /*< index of debug variable*/ +} mavlink_debug_t; + +#define MAVLINK_MSG_ID_DEBUG_LEN 9 +#define MAVLINK_MSG_ID_254_LEN 9 + +#define MAVLINK_MSG_ID_DEBUG_CRC 46 +#define MAVLINK_MSG_ID_254_CRC 46 + + + +#define MAVLINK_MESSAGE_INFO_DEBUG { \ + "DEBUG", \ + 3, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \ + { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \ + { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \ + } \ +} + + +/** + * @brief Pack a debug message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param ind index of debug variable + * @param value DEBUG value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t ind, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DEBUG_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_uint8_t(buf, 8, ind); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_LEN); +#else + mavlink_debug_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + packet.ind = ind; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_LEN); +#endif +} + +/** + * @brief Pack a debug message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param ind index of debug variable + * @param value DEBUG value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t ind,float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DEBUG_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_uint8_t(buf, 8, ind); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_LEN); +#else + mavlink_debug_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + packet.ind = ind; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_LEN); +#endif +} + +/** + * @brief Encode a debug struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param debug C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug) +{ + return mavlink_msg_debug_pack(system_id, component_id, msg, debug->time_boot_ms, debug->ind, debug->value); +} + +/** + * @brief Encode a debug struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param debug C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_debug_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_t* debug) +{ + return mavlink_msg_debug_pack_chan(system_id, component_id, chan, msg, debug->time_boot_ms, debug->ind, debug->value); +} + +/** + * @brief Send a debug message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param ind index of debug variable + * @param value DEBUG value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DEBUG_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_uint8_t(buf, 8, ind); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN); +#endif +#else + mavlink_debug_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + packet.ind = ind; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_DEBUG_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_debug_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_uint8_t(buf, 8, ind); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN); +#endif +#else + mavlink_debug_t *packet = (mavlink_debug_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->value = value; + packet->ind = ind; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)packet, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)packet, MAVLINK_MSG_ID_DEBUG_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE DEBUG UNPACKING + + +/** + * @brief Get field time_boot_ms from debug message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field ind from debug message + * + * @return index of debug variable + */ +static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field value from debug message + * + * @return DEBUG value + */ +static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Decode a debug message into a struct + * + * @param msg The message to decode + * @param debug C-struct to decode the message contents into + */ +static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug) +{ +#if MAVLINK_NEED_BYTE_SWAP + debug->time_boot_ms = mavlink_msg_debug_get_time_boot_ms(msg); + debug->value = mavlink_msg_debug_get_value(msg); + debug->ind = mavlink_msg_debug_get_ind(msg); +#else + memcpy(debug, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DEBUG_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_debug_vect.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_debug_vect.h new file mode 100644 index 0000000..96ac477 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_debug_vect.h @@ -0,0 +1,297 @@ +// MESSAGE DEBUG_VECT PACKING + +#define MAVLINK_MSG_ID_DEBUG_VECT 250 + +typedef struct __mavlink_debug_vect_t +{ + uint64_t time_usec; /*< Timestamp*/ + float x; /*< x*/ + float y; /*< y*/ + float z; /*< z*/ + char name[10]; /*< Name*/ +} mavlink_debug_vect_t; + +#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30 +#define MAVLINK_MSG_ID_250_LEN 30 + +#define MAVLINK_MSG_ID_DEBUG_VECT_CRC 49 +#define MAVLINK_MSG_ID_250_CRC 49 + +#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10 + +#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \ + "DEBUG_VECT", \ + 5, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \ + } \ +} + + +/** + * @brief Pack a debug_vect message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param name Name + * @param time_usec Timestamp + * @param x x + * @param y y + * @param z z + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *name, uint64_t time_usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_char_array(buf, 20, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#else + mavlink_debug_vect_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif +} + +/** + * @brief Pack a debug_vect message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param name Name + * @param time_usec Timestamp + * @param x x + * @param y y + * @param z z + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *name,uint64_t time_usec,float x,float y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_char_array(buf, 20, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#else + mavlink_debug_vect_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif +} + +/** + * @brief Encode a debug_vect struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param debug_vect C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) +{ + return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); +} + +/** + * @brief Encode a debug_vect struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param debug_vect C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_debug_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) +{ + return mavlink_msg_debug_vect_pack_chan(system_id, component_id, chan, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); +} + +/** + * @brief Send a debug_vect message + * @param chan MAVLink channel to send the message + * + * @param name Name + * @param time_usec Timestamp + * @param x x + * @param y y + * @param z z + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_char_array(buf, 20, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif +#else + mavlink_debug_vect_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + mav_array_memcpy(packet.name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_DEBUG_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_debug_vect_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_char_array(buf, 20, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif +#else + mavlink_debug_vect_t *packet = (mavlink_debug_vect_t *)msgbuf; + packet->time_usec = time_usec; + packet->x = x; + packet->y = y; + packet->z = z; + mav_array_memcpy(packet->name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE DEBUG_VECT UNPACKING + + +/** + * @brief Get field name from debug_vect message + * + * @return Name + */ +static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 10, 20); +} + +/** + * @brief Get field time_usec from debug_vect message + * + * @return Timestamp + */ +static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from debug_vect message + * + * @return x + */ +static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from debug_vect message + * + * @return y + */ +static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from debug_vect message + * + * @return z + */ +static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a debug_vect message into a struct + * + * @param msg The message to decode + * @param debug_vect C-struct to decode the message contents into + */ +static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect) +{ +#if MAVLINK_NEED_BYTE_SWAP + debug_vect->time_usec = mavlink_msg_debug_vect_get_time_usec(msg); + debug_vect->x = mavlink_msg_debug_vect_get_x(msg); + debug_vect->y = mavlink_msg_debug_vect_get_y(msg); + debug_vect->z = mavlink_msg_debug_vect_get_z(msg); + mavlink_msg_debug_vect_get_name(msg, debug_vect->name); +#else + memcpy(debug_vect, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_distance_sensor.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_distance_sensor.h new file mode 100644 index 0000000..dc91ce2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_distance_sensor.h @@ -0,0 +1,377 @@ +// MESSAGE DISTANCE_SENSOR PACKING + +#define MAVLINK_MSG_ID_DISTANCE_SENSOR 132 + +typedef struct __mavlink_distance_sensor_t +{ + uint32_t time_boot_ms; /*< Time since system boot*/ + uint16_t min_distance; /*< Minimum distance the sensor can measure in centimeters*/ + uint16_t max_distance; /*< Maximum distance the sensor can measure in centimeters*/ + uint16_t current_distance; /*< Current distance reading*/ + uint8_t type; /*< Type from MAV_DISTANCE_SENSOR enum.*/ + uint8_t id; /*< Onboard ID of the sensor*/ + uint8_t orientation; /*< Direction the sensor faces from MAV_SENSOR_ORIENTATION enum.*/ + uint8_t covariance; /*< Measurement covariance in centimeters, 0 for unknown / invalid readings*/ +} mavlink_distance_sensor_t; + +#define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14 +#define MAVLINK_MSG_ID_132_LEN 14 + +#define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85 +#define MAVLINK_MSG_ID_132_CRC 85 + + + +#define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \ + "DISTANCE_SENSOR", \ + 8, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \ + { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \ + { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \ + { "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \ + { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \ + { "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \ + { "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \ + } \ +} + + +/** + * @brief Pack a distance_sensor message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Time since system boot + * @param min_distance Minimum distance the sensor can measure in centimeters + * @param max_distance Maximum distance the sensor can measure in centimeters + * @param current_distance Current distance reading + * @param type Type from MAV_DISTANCE_SENSOR enum. + * @param id Onboard ID of the sensor + * @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. + * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, min_distance); + _mav_put_uint16_t(buf, 6, max_distance); + _mav_put_uint16_t(buf, 8, current_distance); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, id); + _mav_put_uint8_t(buf, 12, orientation); + _mav_put_uint8_t(buf, 13, covariance); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#else + mavlink_distance_sensor_t packet; + packet.time_boot_ms = time_boot_ms; + packet.min_distance = min_distance; + packet.max_distance = max_distance; + packet.current_distance = current_distance; + packet.type = type; + packet.id = id; + packet.orientation = orientation; + packet.covariance = covariance; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif +} + +/** + * @brief Pack a distance_sensor message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Time since system boot + * @param min_distance Minimum distance the sensor can measure in centimeters + * @param max_distance Maximum distance the sensor can measure in centimeters + * @param current_distance Current distance reading + * @param type Type from MAV_DISTANCE_SENSOR enum. + * @param id Onboard ID of the sensor + * @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. + * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint16_t min_distance,uint16_t max_distance,uint16_t current_distance,uint8_t type,uint8_t id,uint8_t orientation,uint8_t covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, min_distance); + _mav_put_uint16_t(buf, 6, max_distance); + _mav_put_uint16_t(buf, 8, current_distance); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, id); + _mav_put_uint8_t(buf, 12, orientation); + _mav_put_uint8_t(buf, 13, covariance); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#else + mavlink_distance_sensor_t packet; + packet.time_boot_ms = time_boot_ms; + packet.min_distance = min_distance; + packet.max_distance = max_distance; + packet.current_distance = current_distance; + packet.type = type; + packet.id = id; + packet.orientation = orientation; + packet.covariance = covariance; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif +} + +/** + * @brief Encode a distance_sensor struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param distance_sensor C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_distance_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor) +{ + return mavlink_msg_distance_sensor_pack(system_id, component_id, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance); +} + +/** + * @brief Encode a distance_sensor struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param distance_sensor C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor) +{ + return mavlink_msg_distance_sensor_pack_chan(system_id, component_id, chan, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance); +} + +/** + * @brief Send a distance_sensor message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Time since system boot + * @param min_distance Minimum distance the sensor can measure in centimeters + * @param max_distance Maximum distance the sensor can measure in centimeters + * @param current_distance Current distance reading + * @param type Type from MAV_DISTANCE_SENSOR enum. + * @param id Onboard ID of the sensor + * @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. + * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, min_distance); + _mav_put_uint16_t(buf, 6, max_distance); + _mav_put_uint16_t(buf, 8, current_distance); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, id); + _mav_put_uint8_t(buf, 12, orientation); + _mav_put_uint8_t(buf, 13, covariance); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif +#else + mavlink_distance_sensor_t packet; + packet.time_boot_ms = time_boot_ms; + packet.min_distance = min_distance; + packet.max_distance = max_distance; + packet.current_distance = current_distance; + packet.type = type; + packet.id = id; + packet.orientation = orientation; + packet.covariance = covariance; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, min_distance); + _mav_put_uint16_t(buf, 6, max_distance); + _mav_put_uint16_t(buf, 8, current_distance); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, id); + _mav_put_uint8_t(buf, 12, orientation); + _mav_put_uint8_t(buf, 13, covariance); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif +#else + mavlink_distance_sensor_t *packet = (mavlink_distance_sensor_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->min_distance = min_distance; + packet->max_distance = max_distance; + packet->current_distance = current_distance; + packet->type = type; + packet->id = id; + packet->orientation = orientation; + packet->covariance = covariance; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE DISTANCE_SENSOR UNPACKING + + +/** + * @brief Get field time_boot_ms from distance_sensor message + * + * @return Time since system boot + */ +static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field min_distance from distance_sensor message + * + * @return Minimum distance the sensor can measure in centimeters + */ +static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field max_distance from distance_sensor message + * + * @return Maximum distance the sensor can measure in centimeters + */ +static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field current_distance from distance_sensor message + * + * @return Current distance reading + */ +static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field type from distance_sensor message + * + * @return Type from MAV_DISTANCE_SENSOR enum. + */ +static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 10); +} + +/** + * @brief Get field id from distance_sensor message + * + * @return Onboard ID of the sensor + */ +static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 11); +} + +/** + * @brief Get field orientation from distance_sensor message + * + * @return Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. + */ +static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field covariance from distance_sensor message + * + * @return Measurement covariance in centimeters, 0 for unknown / invalid readings + */ +static inline uint8_t mavlink_msg_distance_sensor_get_covariance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 13); +} + +/** + * @brief Decode a distance_sensor message into a struct + * + * @param msg The message to decode + * @param distance_sensor C-struct to decode the message contents into + */ +static inline void mavlink_msg_distance_sensor_decode(const mavlink_message_t* msg, mavlink_distance_sensor_t* distance_sensor) +{ +#if MAVLINK_NEED_BYTE_SWAP + distance_sensor->time_boot_ms = mavlink_msg_distance_sensor_get_time_boot_ms(msg); + distance_sensor->min_distance = mavlink_msg_distance_sensor_get_min_distance(msg); + distance_sensor->max_distance = mavlink_msg_distance_sensor_get_max_distance(msg); + distance_sensor->current_distance = mavlink_msg_distance_sensor_get_current_distance(msg); + distance_sensor->type = mavlink_msg_distance_sensor_get_type(msg); + distance_sensor->id = mavlink_msg_distance_sensor_get_id(msg); + distance_sensor->orientation = mavlink_msg_distance_sensor_get_orientation(msg); + distance_sensor->covariance = mavlink_msg_distance_sensor_get_covariance(msg); +#else + memcpy(distance_sensor, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h new file mode 100644 index 0000000..216738b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h @@ -0,0 +1,225 @@ +// MESSAGE ENCAPSULATED_DATA PACKING + +#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 131 + +typedef struct __mavlink_encapsulated_data_t +{ + uint16_t seqnr; /*< sequence number (starting with 0 on every transmission)*/ + uint8_t data[253]; /*< image data bytes*/ +} mavlink_encapsulated_data_t; + +#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255 +#define MAVLINK_MSG_ID_131_LEN 255 + +#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC 223 +#define MAVLINK_MSG_ID_131_CRC 223 + +#define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253 + +#define MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA { \ + "ENCAPSULATED_DATA", \ + 2, \ + { { "seqnr", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_encapsulated_data_t, seqnr) }, \ + { "data", NULL, MAVLINK_TYPE_UINT8_T, 253, 2, offsetof(mavlink_encapsulated_data_t, data) }, \ + } \ +} + + +/** + * @brief Pack a encapsulated_data message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param seqnr sequence number (starting with 0 on every transmission) + * @param data image data bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t seqnr, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN]; + _mav_put_uint16_t(buf, 0, seqnr); + _mav_put_uint8_t_array(buf, 2, data, 253); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#else + mavlink_encapsulated_data_t packet; + packet.seqnr = seqnr; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif +} + +/** + * @brief Pack a encapsulated_data message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param seqnr sequence number (starting with 0 on every transmission) + * @param data image data bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t seqnr,const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN]; + _mav_put_uint16_t(buf, 0, seqnr); + _mav_put_uint8_t_array(buf, 2, data, 253); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#else + mavlink_encapsulated_data_t packet; + packet.seqnr = seqnr; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif +} + +/** + * @brief Encode a encapsulated_data struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param encapsulated_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data) +{ + return mavlink_msg_encapsulated_data_pack(system_id, component_id, msg, encapsulated_data->seqnr, encapsulated_data->data); +} + +/** + * @brief Encode a encapsulated_data struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param encapsulated_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_encapsulated_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data) +{ + return mavlink_msg_encapsulated_data_pack_chan(system_id, component_id, chan, msg, encapsulated_data->seqnr, encapsulated_data->data); +} + +/** + * @brief Send a encapsulated_data message + * @param chan MAVLink channel to send the message + * + * @param seqnr sequence number (starting with 0 on every transmission) + * @param data image data bytes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_encapsulated_data_send(mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN]; + _mav_put_uint16_t(buf, 0, seqnr); + _mav_put_uint8_t_array(buf, 2, data, 253); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif +#else + mavlink_encapsulated_data_t packet; + packet.seqnr = seqnr; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_encapsulated_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, seqnr); + _mav_put_uint8_t_array(buf, 2, data, 253); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif +#else + mavlink_encapsulated_data_t *packet = (mavlink_encapsulated_data_t *)msgbuf; + packet->seqnr = seqnr; + mav_array_memcpy(packet->data, data, sizeof(uint8_t)*253); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ENCAPSULATED_DATA UNPACKING + + +/** + * @brief Get field seqnr from encapsulated_data message + * + * @return sequence number (starting with 0 on every transmission) + */ +static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field data from encapsulated_data message + * + * @return image data bytes + */ +static inline uint16_t mavlink_msg_encapsulated_data_get_data(const mavlink_message_t* msg, uint8_t *data) +{ + return _MAV_RETURN_uint8_t_array(msg, data, 253, 2); +} + +/** + * @brief Decode a encapsulated_data message into a struct + * + * @param msg The message to decode + * @param encapsulated_data C-struct to decode the message contents into + */ +static inline void mavlink_msg_encapsulated_data_decode(const mavlink_message_t* msg, mavlink_encapsulated_data_t* encapsulated_data) +{ +#if MAVLINK_NEED_BYTE_SWAP + encapsulated_data->seqnr = mavlink_msg_encapsulated_data_get_seqnr(msg); + mavlink_msg_encapsulated_data_get_data(msg, encapsulated_data->data); +#else + memcpy(encapsulated_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_estimator_status.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_estimator_status.h new file mode 100644 index 0000000..f06d609 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_estimator_status.h @@ -0,0 +1,425 @@ +// MESSAGE ESTIMATOR_STATUS PACKING + +#define MAVLINK_MSG_ID_ESTIMATOR_STATUS 230 + +typedef struct __mavlink_estimator_status_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float vel_ratio; /*< Velocity innovation test ratio*/ + float pos_horiz_ratio; /*< Horizontal position innovation test ratio*/ + float pos_vert_ratio; /*< Vertical position innovation test ratio*/ + float mag_ratio; /*< Magnetometer innovation test ratio*/ + float hagl_ratio; /*< Height above terrain innovation test ratio*/ + float tas_ratio; /*< True airspeed innovation test ratio*/ + float pos_horiz_accuracy; /*< Horizontal position 1-STD accuracy relative to the EKF local origin (m)*/ + float pos_vert_accuracy; /*< Vertical position 1-STD accuracy relative to the EKF local origin (m)*/ + uint16_t flags; /*< Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.*/ +} mavlink_estimator_status_t; + +#define MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN 42 +#define MAVLINK_MSG_ID_230_LEN 42 + +#define MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC 163 +#define MAVLINK_MSG_ID_230_CRC 163 + + + +#define MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS { \ + "ESTIMATOR_STATUS", \ + 10, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_estimator_status_t, time_usec) }, \ + { "vel_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_estimator_status_t, vel_ratio) }, \ + { "pos_horiz_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_estimator_status_t, pos_horiz_ratio) }, \ + { "pos_vert_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_estimator_status_t, pos_vert_ratio) }, \ + { "mag_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_estimator_status_t, mag_ratio) }, \ + { "hagl_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_estimator_status_t, hagl_ratio) }, \ + { "tas_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_estimator_status_t, tas_ratio) }, \ + { "pos_horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_estimator_status_t, pos_horiz_accuracy) }, \ + { "pos_vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_estimator_status_t, pos_vert_accuracy) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \ + } \ +} + + +/** + * @brief Pack a estimator_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. + * @param vel_ratio Velocity innovation test ratio + * @param pos_horiz_ratio Horizontal position innovation test ratio + * @param pos_vert_ratio Vertical position innovation test ratio + * @param mag_ratio Magnetometer innovation test ratio + * @param hagl_ratio Height above terrain innovation test ratio + * @param tas_ratio True airspeed innovation test ratio + * @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m) + * @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_estimator_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint16_t flags, float vel_ratio, float pos_horiz_ratio, float pos_vert_ratio, float mag_ratio, float hagl_ratio, float tas_ratio, float pos_horiz_accuracy, float pos_vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vel_ratio); + _mav_put_float(buf, 12, pos_horiz_ratio); + _mav_put_float(buf, 16, pos_vert_ratio); + _mav_put_float(buf, 20, mag_ratio); + _mav_put_float(buf, 24, hagl_ratio); + _mav_put_float(buf, 28, tas_ratio); + _mav_put_float(buf, 32, pos_horiz_accuracy); + _mav_put_float(buf, 36, pos_vert_accuracy); + _mav_put_uint16_t(buf, 40, flags); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#else + mavlink_estimator_status_t packet; + packet.time_usec = time_usec; + packet.vel_ratio = vel_ratio; + packet.pos_horiz_ratio = pos_horiz_ratio; + packet.pos_vert_ratio = pos_vert_ratio; + packet.mag_ratio = mag_ratio; + packet.hagl_ratio = hagl_ratio; + packet.tas_ratio = tas_ratio; + packet.pos_horiz_accuracy = pos_horiz_accuracy; + packet.pos_vert_accuracy = pos_vert_accuracy; + packet.flags = flags; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ESTIMATOR_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif +} + +/** + * @brief Pack a estimator_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. + * @param vel_ratio Velocity innovation test ratio + * @param pos_horiz_ratio Horizontal position innovation test ratio + * @param pos_vert_ratio Vertical position innovation test ratio + * @param mag_ratio Magnetometer innovation test ratio + * @param hagl_ratio Height above terrain innovation test ratio + * @param tas_ratio True airspeed innovation test ratio + * @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m) + * @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_estimator_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint16_t flags,float vel_ratio,float pos_horiz_ratio,float pos_vert_ratio,float mag_ratio,float hagl_ratio,float tas_ratio,float pos_horiz_accuracy,float pos_vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vel_ratio); + _mav_put_float(buf, 12, pos_horiz_ratio); + _mav_put_float(buf, 16, pos_vert_ratio); + _mav_put_float(buf, 20, mag_ratio); + _mav_put_float(buf, 24, hagl_ratio); + _mav_put_float(buf, 28, tas_ratio); + _mav_put_float(buf, 32, pos_horiz_accuracy); + _mav_put_float(buf, 36, pos_vert_accuracy); + _mav_put_uint16_t(buf, 40, flags); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#else + mavlink_estimator_status_t packet; + packet.time_usec = time_usec; + packet.vel_ratio = vel_ratio; + packet.pos_horiz_ratio = pos_horiz_ratio; + packet.pos_vert_ratio = pos_vert_ratio; + packet.mag_ratio = mag_ratio; + packet.hagl_ratio = hagl_ratio; + packet.tas_ratio = tas_ratio; + packet.pos_horiz_accuracy = pos_horiz_accuracy; + packet.pos_vert_accuracy = pos_vert_accuracy; + packet.flags = flags; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ESTIMATOR_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif +} + +/** + * @brief Encode a estimator_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param estimator_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_estimator_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_estimator_status_t* estimator_status) +{ + return mavlink_msg_estimator_status_pack(system_id, component_id, msg, estimator_status->time_usec, estimator_status->flags, estimator_status->vel_ratio, estimator_status->pos_horiz_ratio, estimator_status->pos_vert_ratio, estimator_status->mag_ratio, estimator_status->hagl_ratio, estimator_status->tas_ratio, estimator_status->pos_horiz_accuracy, estimator_status->pos_vert_accuracy); +} + +/** + * @brief Encode a estimator_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param estimator_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_estimator_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_estimator_status_t* estimator_status) +{ + return mavlink_msg_estimator_status_pack_chan(system_id, component_id, chan, msg, estimator_status->time_usec, estimator_status->flags, estimator_status->vel_ratio, estimator_status->pos_horiz_ratio, estimator_status->pos_vert_ratio, estimator_status->mag_ratio, estimator_status->hagl_ratio, estimator_status->tas_ratio, estimator_status->pos_horiz_accuracy, estimator_status->pos_vert_accuracy); +} + +/** + * @brief Send a estimator_status message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. + * @param vel_ratio Velocity innovation test ratio + * @param pos_horiz_ratio Horizontal position innovation test ratio + * @param pos_vert_ratio Vertical position innovation test ratio + * @param mag_ratio Magnetometer innovation test ratio + * @param hagl_ratio Height above terrain innovation test ratio + * @param tas_ratio True airspeed innovation test ratio + * @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m) + * @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_estimator_status_send(mavlink_channel_t chan, uint64_t time_usec, uint16_t flags, float vel_ratio, float pos_horiz_ratio, float pos_vert_ratio, float mag_ratio, float hagl_ratio, float tas_ratio, float pos_horiz_accuracy, float pos_vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vel_ratio); + _mav_put_float(buf, 12, pos_horiz_ratio); + _mav_put_float(buf, 16, pos_vert_ratio); + _mav_put_float(buf, 20, mag_ratio); + _mav_put_float(buf, 24, hagl_ratio); + _mav_put_float(buf, 28, tas_ratio); + _mav_put_float(buf, 32, pos_horiz_accuracy); + _mav_put_float(buf, 36, pos_vert_accuracy); + _mav_put_uint16_t(buf, 40, flags); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif +#else + mavlink_estimator_status_t packet; + packet.time_usec = time_usec; + packet.vel_ratio = vel_ratio; + packet.pos_horiz_ratio = pos_horiz_ratio; + packet.pos_vert_ratio = pos_vert_ratio; + packet.mag_ratio = mag_ratio; + packet.hagl_ratio = hagl_ratio; + packet.tas_ratio = tas_ratio; + packet.pos_horiz_accuracy = pos_horiz_accuracy; + packet.pos_vert_accuracy = pos_vert_accuracy; + packet.flags = flags; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_estimator_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint16_t flags, float vel_ratio, float pos_horiz_ratio, float pos_vert_ratio, float mag_ratio, float hagl_ratio, float tas_ratio, float pos_horiz_accuracy, float pos_vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vel_ratio); + _mav_put_float(buf, 12, pos_horiz_ratio); + _mav_put_float(buf, 16, pos_vert_ratio); + _mav_put_float(buf, 20, mag_ratio); + _mav_put_float(buf, 24, hagl_ratio); + _mav_put_float(buf, 28, tas_ratio); + _mav_put_float(buf, 32, pos_horiz_accuracy); + _mav_put_float(buf, 36, pos_vert_accuracy); + _mav_put_uint16_t(buf, 40, flags); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif +#else + mavlink_estimator_status_t *packet = (mavlink_estimator_status_t *)msgbuf; + packet->time_usec = time_usec; + packet->vel_ratio = vel_ratio; + packet->pos_horiz_ratio = pos_horiz_ratio; + packet->pos_vert_ratio = pos_vert_ratio; + packet->mag_ratio = mag_ratio; + packet->hagl_ratio = hagl_ratio; + packet->tas_ratio = tas_ratio; + packet->pos_horiz_accuracy = pos_horiz_accuracy; + packet->pos_vert_accuracy = pos_vert_accuracy; + packet->flags = flags; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ESTIMATOR_STATUS UNPACKING + + +/** + * @brief Get field time_usec from estimator_status message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_estimator_status_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field flags from estimator_status message + * + * @return Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. + */ +static inline uint16_t mavlink_msg_estimator_status_get_flags(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 40); +} + +/** + * @brief Get field vel_ratio from estimator_status message + * + * @return Velocity innovation test ratio + */ +static inline float mavlink_msg_estimator_status_get_vel_ratio(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field pos_horiz_ratio from estimator_status message + * + * @return Horizontal position innovation test ratio + */ +static inline float mavlink_msg_estimator_status_get_pos_horiz_ratio(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field pos_vert_ratio from estimator_status message + * + * @return Vertical position innovation test ratio + */ +static inline float mavlink_msg_estimator_status_get_pos_vert_ratio(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field mag_ratio from estimator_status message + * + * @return Magnetometer innovation test ratio + */ +static inline float mavlink_msg_estimator_status_get_mag_ratio(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field hagl_ratio from estimator_status message + * + * @return Height above terrain innovation test ratio + */ +static inline float mavlink_msg_estimator_status_get_hagl_ratio(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field tas_ratio from estimator_status message + * + * @return True airspeed innovation test ratio + */ +static inline float mavlink_msg_estimator_status_get_tas_ratio(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field pos_horiz_accuracy from estimator_status message + * + * @return Horizontal position 1-STD accuracy relative to the EKF local origin (m) + */ +static inline float mavlink_msg_estimator_status_get_pos_horiz_accuracy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field pos_vert_accuracy from estimator_status message + * + * @return Vertical position 1-STD accuracy relative to the EKF local origin (m) + */ +static inline float mavlink_msg_estimator_status_get_pos_vert_accuracy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Decode a estimator_status message into a struct + * + * @param msg The message to decode + * @param estimator_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_estimator_status_decode(const mavlink_message_t* msg, mavlink_estimator_status_t* estimator_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + estimator_status->time_usec = mavlink_msg_estimator_status_get_time_usec(msg); + estimator_status->vel_ratio = mavlink_msg_estimator_status_get_vel_ratio(msg); + estimator_status->pos_horiz_ratio = mavlink_msg_estimator_status_get_pos_horiz_ratio(msg); + estimator_status->pos_vert_ratio = mavlink_msg_estimator_status_get_pos_vert_ratio(msg); + estimator_status->mag_ratio = mavlink_msg_estimator_status_get_mag_ratio(msg); + estimator_status->hagl_ratio = mavlink_msg_estimator_status_get_hagl_ratio(msg); + estimator_status->tas_ratio = mavlink_msg_estimator_status_get_tas_ratio(msg); + estimator_status->pos_horiz_accuracy = mavlink_msg_estimator_status_get_pos_horiz_accuracy(msg); + estimator_status->pos_vert_accuracy = mavlink_msg_estimator_status_get_pos_vert_accuracy(msg); + estimator_status->flags = mavlink_msg_estimator_status_get_flags(msg); +#else + memcpy(estimator_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_extended_sys_state.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_extended_sys_state.h new file mode 100644 index 0000000..b3c4886 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_extended_sys_state.h @@ -0,0 +1,233 @@ +// MESSAGE EXTENDED_SYS_STATE PACKING + +#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE 245 + +typedef struct __mavlink_extended_sys_state_t +{ + uint8_t vtol_state; /*< The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.*/ + uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/ +} mavlink_extended_sys_state_t; + +#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN 2 +#define MAVLINK_MSG_ID_245_LEN 2 + +#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC 130 +#define MAVLINK_MSG_ID_245_CRC 130 + + + +#define MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE { \ + "EXTENDED_SYS_STATE", \ + 2, \ + { { "vtol_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_extended_sys_state_t, vtol_state) }, \ + { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_extended_sys_state_t, landed_state) }, \ + } \ +} + + +/** + * @brief Pack a extended_sys_state message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_extended_sys_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t vtol_state, uint8_t landed_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN]; + _mav_put_uint8_t(buf, 0, vtol_state); + _mav_put_uint8_t(buf, 1, landed_state); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#else + mavlink_extended_sys_state_t packet; + packet.vtol_state = vtol_state; + packet.landed_state = landed_state; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_EXTENDED_SYS_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif +} + +/** + * @brief Pack a extended_sys_state message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_extended_sys_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t vtol_state,uint8_t landed_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN]; + _mav_put_uint8_t(buf, 0, vtol_state); + _mav_put_uint8_t(buf, 1, landed_state); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#else + mavlink_extended_sys_state_t packet; + packet.vtol_state = vtol_state; + packet.landed_state = landed_state; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_EXTENDED_SYS_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif +} + +/** + * @brief Encode a extended_sys_state struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param extended_sys_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_extended_sys_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_extended_sys_state_t* extended_sys_state) +{ + return mavlink_msg_extended_sys_state_pack(system_id, component_id, msg, extended_sys_state->vtol_state, extended_sys_state->landed_state); +} + +/** + * @brief Encode a extended_sys_state struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param extended_sys_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_extended_sys_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_extended_sys_state_t* extended_sys_state) +{ + return mavlink_msg_extended_sys_state_pack_chan(system_id, component_id, chan, msg, extended_sys_state->vtol_state, extended_sys_state->landed_state); +} + +/** + * @brief Send a extended_sys_state message + * @param chan MAVLink channel to send the message + * + * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_extended_sys_state_send(mavlink_channel_t chan, uint8_t vtol_state, uint8_t landed_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN]; + _mav_put_uint8_t(buf, 0, vtol_state); + _mav_put_uint8_t(buf, 1, landed_state); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif +#else + mavlink_extended_sys_state_t packet; + packet.vtol_state = vtol_state; + packet.landed_state = landed_state; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)&packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)&packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_extended_sys_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t vtol_state, uint8_t landed_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, vtol_state); + _mav_put_uint8_t(buf, 1, landed_state); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif +#else + mavlink_extended_sys_state_t *packet = (mavlink_extended_sys_state_t *)msgbuf; + packet->vtol_state = vtol_state; + packet->landed_state = landed_state; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE EXTENDED_SYS_STATE UNPACKING + + +/** + * @brief Get field vtol_state from extended_sys_state message + * + * @return The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + */ +static inline uint8_t mavlink_msg_extended_sys_state_get_vtol_state(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field landed_state from extended_sys_state message + * + * @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + */ +static inline uint8_t mavlink_msg_extended_sys_state_get_landed_state(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a extended_sys_state message into a struct + * + * @param msg The message to decode + * @param extended_sys_state C-struct to decode the message contents into + */ +static inline void mavlink_msg_extended_sys_state_decode(const mavlink_message_t* msg, mavlink_extended_sys_state_t* extended_sys_state) +{ +#if MAVLINK_NEED_BYTE_SWAP + extended_sys_state->vtol_state = mavlink_msg_extended_sys_state_get_vtol_state(msg); + extended_sys_state->landed_state = mavlink_msg_extended_sys_state_get_landed_state(msg); +#else + memcpy(extended_sys_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_file_transfer_protocol.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_file_transfer_protocol.h new file mode 100644 index 0000000..72865a9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_file_transfer_protocol.h @@ -0,0 +1,273 @@ +// MESSAGE FILE_TRANSFER_PROTOCOL PACKING + +#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL 110 + +typedef struct __mavlink_file_transfer_protocol_t +{ + uint8_t target_network; /*< Network ID (0 for broadcast)*/ + uint8_t target_system; /*< System ID (0 for broadcast)*/ + uint8_t target_component; /*< Component ID (0 for broadcast)*/ + uint8_t payload[251]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.*/ +} mavlink_file_transfer_protocol_t; + +#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN 254 +#define MAVLINK_MSG_ID_110_LEN 254 + +#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC 84 +#define MAVLINK_MSG_ID_110_CRC 84 + +#define MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN 251 + +#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL { \ + "FILE_TRANSFER_PROTOCOL", \ + 4, \ + { { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_file_transfer_protocol_t, target_network) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_file_transfer_protocol_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_file_transfer_protocol_t, target_component) }, \ + { "payload", NULL, MAVLINK_TYPE_UINT8_T, 251, 3, offsetof(mavlink_file_transfer_protocol_t, payload) }, \ + } \ +} + + +/** + * @brief Pack a file_transfer_protocol message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_file_transfer_protocol_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN]; + _mav_put_uint8_t(buf, 0, target_network); + _mav_put_uint8_t(buf, 1, target_system); + _mav_put_uint8_t(buf, 2, target_component); + _mav_put_uint8_t_array(buf, 3, payload, 251); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#else + mavlink_file_transfer_protocol_t packet; + packet.target_network = target_network; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif +} + +/** + * @brief Pack a file_transfer_protocol message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_file_transfer_protocol_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_network,uint8_t target_system,uint8_t target_component,const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN]; + _mav_put_uint8_t(buf, 0, target_network); + _mav_put_uint8_t(buf, 1, target_system); + _mav_put_uint8_t(buf, 2, target_component); + _mav_put_uint8_t_array(buf, 3, payload, 251); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#else + mavlink_file_transfer_protocol_t packet; + packet.target_network = target_network; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif +} + +/** + * @brief Encode a file_transfer_protocol struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param file_transfer_protocol C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_file_transfer_protocol_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol) +{ + return mavlink_msg_file_transfer_protocol_pack(system_id, component_id, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload); +} + +/** + * @brief Encode a file_transfer_protocol struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param file_transfer_protocol C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_file_transfer_protocol_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol) +{ + return mavlink_msg_file_transfer_protocol_pack_chan(system_id, component_id, chan, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload); +} + +/** + * @brief Send a file_transfer_protocol message + * @param chan MAVLink channel to send the message + * + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_file_transfer_protocol_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN]; + _mav_put_uint8_t(buf, 0, target_network); + _mav_put_uint8_t(buf, 1, target_system); + _mav_put_uint8_t(buf, 2, target_component); + _mav_put_uint8_t_array(buf, 3, payload, 251); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif +#else + mavlink_file_transfer_protocol_t packet; + packet.target_network = target_network; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_file_transfer_protocol_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_network); + _mav_put_uint8_t(buf, 1, target_system); + _mav_put_uint8_t(buf, 2, target_component); + _mav_put_uint8_t_array(buf, 3, payload, 251); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif +#else + mavlink_file_transfer_protocol_t *packet = (mavlink_file_transfer_protocol_t *)msgbuf; + packet->target_network = target_network; + packet->target_system = target_system; + packet->target_component = target_component; + mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*251); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE FILE_TRANSFER_PROTOCOL UNPACKING + + +/** + * @brief Get field target_network from file_transfer_protocol message + * + * @return Network ID (0 for broadcast) + */ +static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_network(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_system from file_transfer_protocol message + * + * @return System ID (0 for broadcast) + */ +static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field target_component from file_transfer_protocol message + * + * @return Component ID (0 for broadcast) + */ +static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field payload from file_transfer_protocol message + * + * @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + */ +static inline uint16_t mavlink_msg_file_transfer_protocol_get_payload(const mavlink_message_t* msg, uint8_t *payload) +{ + return _MAV_RETURN_uint8_t_array(msg, payload, 251, 3); +} + +/** + * @brief Decode a file_transfer_protocol message into a struct + * + * @param msg The message to decode + * @param file_transfer_protocol C-struct to decode the message contents into + */ +static inline void mavlink_msg_file_transfer_protocol_decode(const mavlink_message_t* msg, mavlink_file_transfer_protocol_t* file_transfer_protocol) +{ +#if MAVLINK_NEED_BYTE_SWAP + file_transfer_protocol->target_network = mavlink_msg_file_transfer_protocol_get_target_network(msg); + file_transfer_protocol->target_system = mavlink_msg_file_transfer_protocol_get_target_system(msg); + file_transfer_protocol->target_component = mavlink_msg_file_transfer_protocol_get_target_component(msg); + mavlink_msg_file_transfer_protocol_get_payload(msg, file_transfer_protocol->payload); +#else + memcpy(file_transfer_protocol, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_follow_target.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_follow_target.h new file mode 100644 index 0000000..24c9ffa --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_follow_target.h @@ -0,0 +1,445 @@ +// MESSAGE FOLLOW_TARGET PACKING + +#define MAVLINK_MSG_ID_FOLLOW_TARGET 144 + +typedef struct __mavlink_follow_target_t +{ + uint64_t timestamp; /*< Timestamp in milliseconds since system boot*/ + uint64_t custom_state; /*< button states or switches of a tracker device*/ + int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ + float alt; /*< AMSL, in meters*/ + float vel[3]; /*< target velocity (0,0,0) for unknown*/ + float acc[3]; /*< linear target acceleration (0,0,0) for unknown*/ + float attitude_q[4]; /*< (1 0 0 0 for unknown)*/ + float rates[3]; /*< (0 0 0 for unknown)*/ + float position_cov[3]; /*< eph epv*/ + uint8_t est_capabilities; /*< bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)*/ +} mavlink_follow_target_t; + +#define MAVLINK_MSG_ID_FOLLOW_TARGET_LEN 93 +#define MAVLINK_MSG_ID_144_LEN 93 + +#define MAVLINK_MSG_ID_FOLLOW_TARGET_CRC 127 +#define MAVLINK_MSG_ID_144_CRC 127 + +#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_VEL_LEN 3 +#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ACC_LEN 3 +#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ATTITUDE_Q_LEN 4 +#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_RATES_LEN 3 +#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_POSITION_COV_LEN 3 + +#define MAVLINK_MESSAGE_INFO_FOLLOW_TARGET { \ + "FOLLOW_TARGET", \ + 11, \ + { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_follow_target_t, timestamp) }, \ + { "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_follow_target_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_follow_target_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_follow_target_t, alt) }, \ + { "vel", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_follow_target_t, vel) }, \ + { "acc", NULL, MAVLINK_TYPE_FLOAT, 3, 40, offsetof(mavlink_follow_target_t, acc) }, \ + { "attitude_q", NULL, MAVLINK_TYPE_FLOAT, 4, 52, offsetof(mavlink_follow_target_t, attitude_q) }, \ + { "rates", NULL, MAVLINK_TYPE_FLOAT, 3, 68, offsetof(mavlink_follow_target_t, rates) }, \ + { "position_cov", NULL, MAVLINK_TYPE_FLOAT, 3, 80, offsetof(mavlink_follow_target_t, position_cov) }, \ + { "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \ + } \ +} + + +/** + * @brief Pack a follow_target message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param timestamp Timestamp in milliseconds since system boot + * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt AMSL, in meters + * @param vel target velocity (0,0,0) for unknown + * @param acc linear target acceleration (0,0,0) for unknown + * @param attitude_q (1 0 0 0 for unknown) + * @param rates (0 0 0 for unknown) + * @param position_cov eph epv + * @param custom_state button states or switches of a tracker device + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_follow_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_FOLLOW_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_uint64_t(buf, 8, custom_state); + _mav_put_int32_t(buf, 16, lat); + _mav_put_int32_t(buf, 20, lon); + _mav_put_float(buf, 24, alt); + _mav_put_uint8_t(buf, 92, est_capabilities); + _mav_put_float_array(buf, 28, vel, 3); + _mav_put_float_array(buf, 40, acc, 3); + _mav_put_float_array(buf, 52, attitude_q, 4); + _mav_put_float_array(buf, 68, rates, 3); + _mav_put_float_array(buf, 80, position_cov, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#else + mavlink_follow_target_t packet; + packet.timestamp = timestamp; + packet.custom_state = custom_state; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.est_capabilities = est_capabilities; + mav_array_memcpy(packet.vel, vel, sizeof(float)*3); + mav_array_memcpy(packet.acc, acc, sizeof(float)*3); + mav_array_memcpy(packet.attitude_q, attitude_q, sizeof(float)*4); + mav_array_memcpy(packet.rates, rates, sizeof(float)*3); + mav_array_memcpy(packet.position_cov, position_cov, sizeof(float)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_FOLLOW_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif +} + +/** + * @brief Pack a follow_target message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param timestamp Timestamp in milliseconds since system boot + * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt AMSL, in meters + * @param vel target velocity (0,0,0) for unknown + * @param acc linear target acceleration (0,0,0) for unknown + * @param attitude_q (1 0 0 0 for unknown) + * @param rates (0 0 0 for unknown) + * @param position_cov eph epv + * @param custom_state button states or switches of a tracker device + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_follow_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t timestamp,uint8_t est_capabilities,int32_t lat,int32_t lon,float alt,const float *vel,const float *acc,const float *attitude_q,const float *rates,const float *position_cov,uint64_t custom_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_FOLLOW_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_uint64_t(buf, 8, custom_state); + _mav_put_int32_t(buf, 16, lat); + _mav_put_int32_t(buf, 20, lon); + _mav_put_float(buf, 24, alt); + _mav_put_uint8_t(buf, 92, est_capabilities); + _mav_put_float_array(buf, 28, vel, 3); + _mav_put_float_array(buf, 40, acc, 3); + _mav_put_float_array(buf, 52, attitude_q, 4); + _mav_put_float_array(buf, 68, rates, 3); + _mav_put_float_array(buf, 80, position_cov, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#else + mavlink_follow_target_t packet; + packet.timestamp = timestamp; + packet.custom_state = custom_state; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.est_capabilities = est_capabilities; + mav_array_memcpy(packet.vel, vel, sizeof(float)*3); + mav_array_memcpy(packet.acc, acc, sizeof(float)*3); + mav_array_memcpy(packet.attitude_q, attitude_q, sizeof(float)*4); + mav_array_memcpy(packet.rates, rates, sizeof(float)*3); + mav_array_memcpy(packet.position_cov, position_cov, sizeof(float)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_FOLLOW_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif +} + +/** + * @brief Encode a follow_target struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param follow_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_follow_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_follow_target_t* follow_target) +{ + return mavlink_msg_follow_target_pack(system_id, component_id, msg, follow_target->timestamp, follow_target->est_capabilities, follow_target->lat, follow_target->lon, follow_target->alt, follow_target->vel, follow_target->acc, follow_target->attitude_q, follow_target->rates, follow_target->position_cov, follow_target->custom_state); +} + +/** + * @brief Encode a follow_target struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param follow_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_follow_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_follow_target_t* follow_target) +{ + return mavlink_msg_follow_target_pack_chan(system_id, component_id, chan, msg, follow_target->timestamp, follow_target->est_capabilities, follow_target->lat, follow_target->lon, follow_target->alt, follow_target->vel, follow_target->acc, follow_target->attitude_q, follow_target->rates, follow_target->position_cov, follow_target->custom_state); +} + +/** + * @brief Send a follow_target message + * @param chan MAVLink channel to send the message + * + * @param timestamp Timestamp in milliseconds since system boot + * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt AMSL, in meters + * @param vel target velocity (0,0,0) for unknown + * @param acc linear target acceleration (0,0,0) for unknown + * @param attitude_q (1 0 0 0 for unknown) + * @param rates (0 0 0 for unknown) + * @param position_cov eph epv + * @param custom_state button states or switches of a tracker device + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_follow_target_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_FOLLOW_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_uint64_t(buf, 8, custom_state); + _mav_put_int32_t(buf, 16, lat); + _mav_put_int32_t(buf, 20, lon); + _mav_put_float(buf, 24, alt); + _mav_put_uint8_t(buf, 92, est_capabilities); + _mav_put_float_array(buf, 28, vel, 3); + _mav_put_float_array(buf, 40, acc, 3); + _mav_put_float_array(buf, 52, attitude_q, 4); + _mav_put_float_array(buf, 68, rates, 3); + _mav_put_float_array(buf, 80, position_cov, 3); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif +#else + mavlink_follow_target_t packet; + packet.timestamp = timestamp; + packet.custom_state = custom_state; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.est_capabilities = est_capabilities; + mav_array_memcpy(packet.vel, vel, sizeof(float)*3); + mav_array_memcpy(packet.acc, acc, sizeof(float)*3); + mav_array_memcpy(packet.attitude_q, attitude_q, sizeof(float)*4); + mav_array_memcpy(packet.rates, rates, sizeof(float)*3); + mav_array_memcpy(packet.position_cov, position_cov, sizeof(float)*3); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)&packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)&packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_FOLLOW_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_follow_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_uint64_t(buf, 8, custom_state); + _mav_put_int32_t(buf, 16, lat); + _mav_put_int32_t(buf, 20, lon); + _mav_put_float(buf, 24, alt); + _mav_put_uint8_t(buf, 92, est_capabilities); + _mav_put_float_array(buf, 28, vel, 3); + _mav_put_float_array(buf, 40, acc, 3); + _mav_put_float_array(buf, 52, attitude_q, 4); + _mav_put_float_array(buf, 68, rates, 3); + _mav_put_float_array(buf, 80, position_cov, 3); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif +#else + mavlink_follow_target_t *packet = (mavlink_follow_target_t *)msgbuf; + packet->timestamp = timestamp; + packet->custom_state = custom_state; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->est_capabilities = est_capabilities; + mav_array_memcpy(packet->vel, vel, sizeof(float)*3); + mav_array_memcpy(packet->acc, acc, sizeof(float)*3); + mav_array_memcpy(packet->attitude_q, attitude_q, sizeof(float)*4); + mav_array_memcpy(packet->rates, rates, sizeof(float)*3); + mav_array_memcpy(packet->position_cov, position_cov, sizeof(float)*3); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE FOLLOW_TARGET UNPACKING + + +/** + * @brief Get field timestamp from follow_target message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint64_t mavlink_msg_follow_target_get_timestamp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field est_capabilities from follow_target message + * + * @return bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + */ +static inline uint8_t mavlink_msg_follow_target_get_est_capabilities(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 92); +} + +/** + * @brief Get field lat from follow_target message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_follow_target_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field lon from follow_target message + * + * @return Longitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_follow_target_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 20); +} + +/** + * @brief Get field alt from follow_target message + * + * @return AMSL, in meters + */ +static inline float mavlink_msg_follow_target_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field vel from follow_target message + * + * @return target velocity (0,0,0) for unknown + */ +static inline uint16_t mavlink_msg_follow_target_get_vel(const mavlink_message_t* msg, float *vel) +{ + return _MAV_RETURN_float_array(msg, vel, 3, 28); +} + +/** + * @brief Get field acc from follow_target message + * + * @return linear target acceleration (0,0,0) for unknown + */ +static inline uint16_t mavlink_msg_follow_target_get_acc(const mavlink_message_t* msg, float *acc) +{ + return _MAV_RETURN_float_array(msg, acc, 3, 40); +} + +/** + * @brief Get field attitude_q from follow_target message + * + * @return (1 0 0 0 for unknown) + */ +static inline uint16_t mavlink_msg_follow_target_get_attitude_q(const mavlink_message_t* msg, float *attitude_q) +{ + return _MAV_RETURN_float_array(msg, attitude_q, 4, 52); +} + +/** + * @brief Get field rates from follow_target message + * + * @return (0 0 0 for unknown) + */ +static inline uint16_t mavlink_msg_follow_target_get_rates(const mavlink_message_t* msg, float *rates) +{ + return _MAV_RETURN_float_array(msg, rates, 3, 68); +} + +/** + * @brief Get field position_cov from follow_target message + * + * @return eph epv + */ +static inline uint16_t mavlink_msg_follow_target_get_position_cov(const mavlink_message_t* msg, float *position_cov) +{ + return _MAV_RETURN_float_array(msg, position_cov, 3, 80); +} + +/** + * @brief Get field custom_state from follow_target message + * + * @return button states or switches of a tracker device + */ +static inline uint64_t mavlink_msg_follow_target_get_custom_state(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 8); +} + +/** + * @brief Decode a follow_target message into a struct + * + * @param msg The message to decode + * @param follow_target C-struct to decode the message contents into + */ +static inline void mavlink_msg_follow_target_decode(const mavlink_message_t* msg, mavlink_follow_target_t* follow_target) +{ +#if MAVLINK_NEED_BYTE_SWAP + follow_target->timestamp = mavlink_msg_follow_target_get_timestamp(msg); + follow_target->custom_state = mavlink_msg_follow_target_get_custom_state(msg); + follow_target->lat = mavlink_msg_follow_target_get_lat(msg); + follow_target->lon = mavlink_msg_follow_target_get_lon(msg); + follow_target->alt = mavlink_msg_follow_target_get_alt(msg); + mavlink_msg_follow_target_get_vel(msg, follow_target->vel); + mavlink_msg_follow_target_get_acc(msg, follow_target->acc); + mavlink_msg_follow_target_get_attitude_q(msg, follow_target->attitude_q); + mavlink_msg_follow_target_get_rates(msg, follow_target->rates); + mavlink_msg_follow_target_get_position_cov(msg, follow_target->position_cov); + follow_target->est_capabilities = mavlink_msg_follow_target_get_est_capabilities(msg); +#else + memcpy(follow_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_global_position_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_global_position_int.h new file mode 100644 index 0000000..35255a2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_global_position_int.h @@ -0,0 +1,401 @@ +// MESSAGE GLOBAL_POSITION_INT PACKING + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33 + +typedef struct __mavlink_global_position_int_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + int32_t lat; /*< Latitude, expressed as degrees * 1E7*/ + int32_t lon; /*< Longitude, expressed as degrees * 1E7*/ + int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)*/ + int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/ + int16_t vx; /*< Ground X Speed (Latitude, positive north), expressed as m/s * 100*/ + int16_t vy; /*< Ground Y Speed (Longitude, positive east), expressed as m/s * 100*/ + int16_t vz; /*< Ground Z Speed (Altitude, positive down), expressed as m/s * 100*/ + uint16_t hdg; /*< Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ +} mavlink_global_position_int_t; + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28 +#define MAVLINK_MSG_ID_33_LEN 28 + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104 +#define MAVLINK_MSG_ID_33_CRC 104 + + + +#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \ + "GLOBAL_POSITION_INT", \ + 9, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \ + { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \ + { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \ + { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \ + } \ +} + + +/** + * @brief Pack a global_position_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100 + * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, alt); + _mav_put_int32_t(buf, 16, relative_alt); + _mav_put_int16_t(buf, 20, vx); + _mav_put_int16_t(buf, 22, vy); + _mav_put_int16_t(buf, 24, vz); + _mav_put_uint16_t(buf, 26, hdg); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#else + mavlink_global_position_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.hdg = hdg; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif +} + +/** + * @brief Pack a global_position_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100 + * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,int16_t vx,int16_t vy,int16_t vz,uint16_t hdg) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, alt); + _mav_put_int32_t(buf, 16, relative_alt); + _mav_put_int16_t(buf, 20, vx); + _mav_put_int16_t(buf, 22, vy); + _mav_put_int16_t(buf, 24, vz); + _mav_put_uint16_t(buf, 26, hdg); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#else + mavlink_global_position_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.hdg = hdg; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif +} + +/** + * @brief Encode a global_position_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param global_position_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int) +{ + return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); +} + +/** + * @brief Encode a global_position_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param global_position_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int) +{ + return mavlink_msg_global_position_int_pack_chan(system_id, component_id, chan, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); +} + +/** + * @brief Send a global_position_int message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100 + * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, alt); + _mav_put_int32_t(buf, 16, relative_alt); + _mav_put_int16_t(buf, 20, vx); + _mav_put_int16_t(buf, 22, vy); + _mav_put_int16_t(buf, 24, vz); + _mav_put_uint16_t(buf, 26, hdg); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif +#else + mavlink_global_position_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.hdg = hdg; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_global_position_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, alt); + _mav_put_int32_t(buf, 16, relative_alt); + _mav_put_int16_t(buf, 20, vx); + _mav_put_int16_t(buf, 22, vy); + _mav_put_int16_t(buf, 24, vz); + _mav_put_uint16_t(buf, 26, hdg); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif +#else + mavlink_global_position_int_t *packet = (mavlink_global_position_int_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->relative_alt = relative_alt; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->hdg = hdg; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GLOBAL_POSITION_INT UNPACKING + + +/** + * @brief Get field time_boot_ms from global_position_int message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field lat from global_position_int message + * + * @return Latitude, expressed as degrees * 1E7 + */ +static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field lon from global_position_int message + * + * @return Longitude, expressed as degrees * 1E7 + */ +static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field alt from global_position_int message + * + * @return Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) + */ +static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field relative_alt from global_position_int message + * + * @return Altitude above ground in meters, expressed as * 1000 (millimeters) + */ +static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field vx from global_position_int message + * + * @return Ground X Speed (Latitude, positive north), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field vy from global_position_int message + * + * @return Ground Y Speed (Longitude, positive east), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field vz from global_position_int message + * + * @return Ground Z Speed (Altitude, positive down), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 24); +} + +/** + * @brief Get field hdg from global_position_int message + * + * @return Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Decode a global_position_int message into a struct + * + * @param msg The message to decode + * @param global_position_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + global_position_int->time_boot_ms = mavlink_msg_global_position_int_get_time_boot_ms(msg); + global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg); + global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg); + global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg); + global_position_int->relative_alt = mavlink_msg_global_position_int_get_relative_alt(msg); + global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg); + global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg); + global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg); + global_position_int->hdg = mavlink_msg_global_position_int_get_hdg(msg); +#else + memcpy(global_position_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_global_position_int_cov.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_global_position_int_cov.h new file mode 100644 index 0000000..49c43c9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_global_position_int_cov.h @@ -0,0 +1,441 @@ +// MESSAGE GLOBAL_POSITION_INT_COV PACKING + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV 63 + +typedef struct __mavlink_global_position_int_cov_t +{ + uint64_t time_utc; /*< Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.*/ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + int32_t lat; /*< Latitude, expressed as degrees * 1E7*/ + int32_t lon; /*< Longitude, expressed as degrees * 1E7*/ + int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), above MSL*/ + int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/ + float vx; /*< Ground X Speed (Latitude), expressed as m/s*/ + float vy; /*< Ground Y Speed (Longitude), expressed as m/s*/ + float vz; /*< Ground Z Speed (Altitude), expressed as m/s*/ + float covariance[36]; /*< Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)*/ + uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/ +} mavlink_global_position_int_cov_t; + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN 185 +#define MAVLINK_MSG_ID_63_LEN 185 + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC 51 +#define MAVLINK_MSG_ID_63_CRC 51 + +#define MAVLINK_MSG_GLOBAL_POSITION_INT_COV_FIELD_COVARIANCE_LEN 36 + +#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \ + "GLOBAL_POSITION_INT_COV", \ + 11, \ + { { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_utc) }, \ + { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, time_boot_ms) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, alt) }, \ + { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_global_position_int_cov_t, vz) }, \ + { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 40, offsetof(mavlink_global_position_int_cov_t, covariance) }, \ + { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 184, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \ + } \ +} + + +/** + * @brief Pack a global_position_int_cov message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s + * @param vy Ground Y Speed (Longitude), expressed as m/s + * @param vz Ground Z Speed (Altitude), expressed as m/s + * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_int_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_int32_t(buf, 12, lat); + _mav_put_int32_t(buf, 16, lon); + _mav_put_int32_t(buf, 20, alt); + _mav_put_int32_t(buf, 24, relative_alt); + _mav_put_float(buf, 28, vx); + _mav_put_float(buf, 32, vy); + _mav_put_float(buf, 36, vz); + _mav_put_uint8_t(buf, 184, estimator_type); + _mav_put_float_array(buf, 40, covariance, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#else + mavlink_global_position_int_cov_t packet; + packet.time_utc = time_utc; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.estimator_type = estimator_type; + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif +} + +/** + * @brief Pack a global_position_int_cov message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s + * @param vy Ground Y Speed (Longitude), expressed as m/s + * @param vz Ground Z Speed (Altitude), expressed as m/s + * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_int_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint64_t time_utc,uint8_t estimator_type,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,float vx,float vy,float vz,const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_int32_t(buf, 12, lat); + _mav_put_int32_t(buf, 16, lon); + _mav_put_int32_t(buf, 20, alt); + _mav_put_int32_t(buf, 24, relative_alt); + _mav_put_float(buf, 28, vx); + _mav_put_float(buf, 32, vy); + _mav_put_float(buf, 36, vz); + _mav_put_uint8_t(buf, 184, estimator_type); + _mav_put_float_array(buf, 40, covariance, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#else + mavlink_global_position_int_cov_t packet; + packet.time_utc = time_utc; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.estimator_type = estimator_type; + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif +} + +/** + * @brief Encode a global_position_int_cov struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param global_position_int_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_int_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov) +{ + return mavlink_msg_global_position_int_cov_pack(system_id, component_id, msg, global_position_int_cov->time_boot_ms, global_position_int_cov->time_utc, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance); +} + +/** + * @brief Encode a global_position_int_cov struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param global_position_int_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_int_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov) +{ + return mavlink_msg_global_position_int_cov_pack_chan(system_id, component_id, chan, msg, global_position_int_cov->time_boot_ms, global_position_int_cov->time_utc, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance); +} + +/** + * @brief Send a global_position_int_cov message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s + * @param vy Ground Y Speed (Longitude), expressed as m/s + * @param vz Ground Z Speed (Altitude), expressed as m/s + * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_position_int_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_int32_t(buf, 12, lat); + _mav_put_int32_t(buf, 16, lon); + _mav_put_int32_t(buf, 20, alt); + _mav_put_int32_t(buf, 24, relative_alt); + _mav_put_float(buf, 28, vx); + _mav_put_float(buf, 32, vy); + _mav_put_float(buf, 36, vz); + _mav_put_uint8_t(buf, 184, estimator_type); + _mav_put_float_array(buf, 40, covariance, 36); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif +#else + mavlink_global_position_int_cov_t packet; + packet.time_utc = time_utc; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.estimator_type = estimator_type; + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_global_position_int_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_int32_t(buf, 12, lat); + _mav_put_int32_t(buf, 16, lon); + _mav_put_int32_t(buf, 20, alt); + _mav_put_int32_t(buf, 24, relative_alt); + _mav_put_float(buf, 28, vx); + _mav_put_float(buf, 32, vy); + _mav_put_float(buf, 36, vz); + _mav_put_uint8_t(buf, 184, estimator_type); + _mav_put_float_array(buf, 40, covariance, 36); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif +#else + mavlink_global_position_int_cov_t *packet = (mavlink_global_position_int_cov_t *)msgbuf; + packet->time_utc = time_utc; + packet->time_boot_ms = time_boot_ms; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->relative_alt = relative_alt; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->estimator_type = estimator_type; + mav_array_memcpy(packet->covariance, covariance, sizeof(float)*36); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GLOBAL_POSITION_INT_COV UNPACKING + + +/** + * @brief Get field time_boot_ms from global_position_int_cov message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_global_position_int_cov_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field time_utc from global_position_int_cov message + * + * @return Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + */ +static inline uint64_t mavlink_msg_global_position_int_cov_get_time_utc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field estimator_type from global_position_int_cov message + * + * @return Class id of the estimator this estimate originated from. + */ +static inline uint8_t mavlink_msg_global_position_int_cov_get_estimator_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 184); +} + +/** + * @brief Get field lat from global_position_int_cov message + * + * @return Latitude, expressed as degrees * 1E7 + */ +static inline int32_t mavlink_msg_global_position_int_cov_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field lon from global_position_int_cov message + * + * @return Longitude, expressed as degrees * 1E7 + */ +static inline int32_t mavlink_msg_global_position_int_cov_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field alt from global_position_int_cov message + * + * @return Altitude in meters, expressed as * 1000 (millimeters), above MSL + */ +static inline int32_t mavlink_msg_global_position_int_cov_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 20); +} + +/** + * @brief Get field relative_alt from global_position_int_cov message + * + * @return Altitude above ground in meters, expressed as * 1000 (millimeters) + */ +static inline int32_t mavlink_msg_global_position_int_cov_get_relative_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 24); +} + +/** + * @brief Get field vx from global_position_int_cov message + * + * @return Ground X Speed (Latitude), expressed as m/s + */ +static inline float mavlink_msg_global_position_int_cov_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field vy from global_position_int_cov message + * + * @return Ground Y Speed (Longitude), expressed as m/s + */ +static inline float mavlink_msg_global_position_int_cov_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field vz from global_position_int_cov message + * + * @return Ground Z Speed (Altitude), expressed as m/s + */ +static inline float mavlink_msg_global_position_int_cov_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field covariance from global_position_int_cov message + * + * @return Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + */ +static inline uint16_t mavlink_msg_global_position_int_cov_get_covariance(const mavlink_message_t* msg, float *covariance) +{ + return _MAV_RETURN_float_array(msg, covariance, 36, 40); +} + +/** + * @brief Decode a global_position_int_cov message into a struct + * + * @param msg The message to decode + * @param global_position_int_cov C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_position_int_cov_decode(const mavlink_message_t* msg, mavlink_global_position_int_cov_t* global_position_int_cov) +{ +#if MAVLINK_NEED_BYTE_SWAP + global_position_int_cov->time_utc = mavlink_msg_global_position_int_cov_get_time_utc(msg); + global_position_int_cov->time_boot_ms = mavlink_msg_global_position_int_cov_get_time_boot_ms(msg); + global_position_int_cov->lat = mavlink_msg_global_position_int_cov_get_lat(msg); + global_position_int_cov->lon = mavlink_msg_global_position_int_cov_get_lon(msg); + global_position_int_cov->alt = mavlink_msg_global_position_int_cov_get_alt(msg); + global_position_int_cov->relative_alt = mavlink_msg_global_position_int_cov_get_relative_alt(msg); + global_position_int_cov->vx = mavlink_msg_global_position_int_cov_get_vx(msg); + global_position_int_cov->vy = mavlink_msg_global_position_int_cov_get_vy(msg); + global_position_int_cov->vz = mavlink_msg_global_position_int_cov_get_vz(msg); + mavlink_msg_global_position_int_cov_get_covariance(msg, global_position_int_cov->covariance); + global_position_int_cov->estimator_type = mavlink_msg_global_position_int_cov_get_estimator_type(msg); +#else + memcpy(global_position_int_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h new file mode 100644 index 0000000..1a1e92c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h @@ -0,0 +1,353 @@ +// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101 + +typedef struct __mavlink_global_vision_position_estimate_t +{ + uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + float x; /*< Global X position*/ + float y; /*< Global Y position*/ + float z; /*< Global Z position*/ + float roll; /*< Roll angle in rad*/ + float pitch; /*< Pitch angle in rad*/ + float yaw; /*< Yaw angle in rad*/ +} mavlink_global_vision_position_estimate_t; + +#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32 +#define MAVLINK_MSG_ID_101_LEN 32 + +#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC 102 +#define MAVLINK_MSG_ID_101_CRC 102 + + + +#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \ + "GLOBAL_VISION_POSITION_ESTIMATE", \ + 7, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_vision_position_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_vision_position_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_vision_position_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_vision_position_estimate_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_vision_position_estimate_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_vision_position_estimate_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_vision_position_estimate_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a global_vision_position_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#else + mavlink_global_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif +} + +/** + * @brief Pack a global_vision_position_estimate message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#else + mavlink_global_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif +} + +/** + * @brief Encode a global_vision_position_estimate struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param global_vision_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) +{ + return mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw); +} + +/** + * @brief Encode a global_vision_position_estimate struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param global_vision_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_vision_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) +{ + return mavlink_msg_global_vision_position_estimate_pack_chan(system_id, component_id, chan, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw); +} + +/** + * @brief Send a global_vision_position_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif +#else + mavlink_global_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_global_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif +#else + mavlink_global_vision_position_estimate_t *packet = (mavlink_global_vision_position_estimate_t *)msgbuf; + packet->usec = usec; + packet->x = x; + packet->y = y; + packet->z = z; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from global_vision_position_estimate message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_global_vision_position_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from global_vision_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_global_vision_position_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from global_vision_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_global_vision_position_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from global_vision_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_global_vision_position_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field roll from global_vision_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_global_vision_position_estimate_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitch from global_vision_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_global_vision_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yaw from global_vision_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_global_vision_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a global_vision_position_estimate message into a struct + * + * @param msg The message to decode + * @param global_vision_position_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_global_vision_position_estimate_t* global_vision_position_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + global_vision_position_estimate->usec = mavlink_msg_global_vision_position_estimate_get_usec(msg); + global_vision_position_estimate->x = mavlink_msg_global_vision_position_estimate_get_x(msg); + global_vision_position_estimate->y = mavlink_msg_global_vision_position_estimate_get_y(msg); + global_vision_position_estimate->z = mavlink_msg_global_vision_position_estimate_get_z(msg); + global_vision_position_estimate->roll = mavlink_msg_global_vision_position_estimate_get_roll(msg); + global_vision_position_estimate->pitch = mavlink_msg_global_vision_position_estimate_get_pitch(msg); + global_vision_position_estimate->yaw = mavlink_msg_global_vision_position_estimate_get_yaw(msg); +#else + memcpy(global_vision_position_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps2_raw.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps2_raw.h new file mode 100644 index 0000000..f068d49 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps2_raw.h @@ -0,0 +1,473 @@ +// MESSAGE GPS2_RAW PACKING + +#define MAVLINK_MSG_ID_GPS2_RAW 124 + +typedef struct __mavlink_gps2_raw_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ + int32_t alt; /*< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)*/ + uint32_t dgps_age; /*< Age of DGPS info*/ + uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/ + uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/ + uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX*/ + uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ + uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.*/ + uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ + uint8_t dgps_numch; /*< Number of DGPS satellites*/ +} mavlink_gps2_raw_t; + +#define MAVLINK_MSG_ID_GPS2_RAW_LEN 35 +#define MAVLINK_MSG_ID_124_LEN 35 + +#define MAVLINK_MSG_ID_GPS2_RAW_CRC 87 +#define MAVLINK_MSG_ID_124_CRC 87 + + + +#define MAVLINK_MESSAGE_INFO_GPS2_RAW { \ + "GPS2_RAW", \ + 12, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \ + { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \ + { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \ + { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \ + { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \ + { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \ + { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \ + { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \ + } \ +} + + +/** + * @brief Pack a gps2_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @param dgps_numch Number of DGPS satellites + * @param dgps_age Age of DGPS info + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint32_t(buf, 20, dgps_age); + _mav_put_uint16_t(buf, 24, eph); + _mav_put_uint16_t(buf, 26, epv); + _mav_put_uint16_t(buf, 28, vel); + _mav_put_uint16_t(buf, 30, cog); + _mav_put_uint8_t(buf, 32, fix_type); + _mav_put_uint8_t(buf, 33, satellites_visible); + _mav_put_uint8_t(buf, 34, dgps_numch); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#else + mavlink_gps2_raw_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.dgps_age = dgps_age; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + packet.dgps_numch = dgps_numch; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS2_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif +} + +/** + * @brief Pack a gps2_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @param dgps_numch Number of DGPS satellites + * @param dgps_age Age of DGPS info + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible,uint8_t dgps_numch,uint32_t dgps_age) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint32_t(buf, 20, dgps_age); + _mav_put_uint16_t(buf, 24, eph); + _mav_put_uint16_t(buf, 26, epv); + _mav_put_uint16_t(buf, 28, vel); + _mav_put_uint16_t(buf, 30, cog); + _mav_put_uint8_t(buf, 32, fix_type); + _mav_put_uint8_t(buf, 33, satellites_visible); + _mav_put_uint8_t(buf, 34, dgps_numch); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#else + mavlink_gps2_raw_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.dgps_age = dgps_age; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + packet.dgps_numch = dgps_numch; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS2_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif +} + +/** + * @brief Encode a gps2_raw struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps2_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps2_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw) +{ + return mavlink_msg_gps2_raw_pack(system_id, component_id, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age); +} + +/** + * @brief Encode a gps2_raw struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps2_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw) +{ + return mavlink_msg_gps2_raw_pack_chan(system_id, component_id, chan, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age); +} + +/** + * @brief Send a gps2_raw message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @param dgps_numch Number of DGPS satellites + * @param dgps_age Age of DGPS info + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps2_raw_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint32_t(buf, 20, dgps_age); + _mav_put_uint16_t(buf, 24, eph); + _mav_put_uint16_t(buf, 26, epv); + _mav_put_uint16_t(buf, 28, vel); + _mav_put_uint16_t(buf, 30, cog); + _mav_put_uint8_t(buf, 32, fix_type); + _mav_put_uint8_t(buf, 33, satellites_visible); + _mav_put_uint8_t(buf, 34, dgps_numch); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif +#else + mavlink_gps2_raw_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.dgps_age = dgps_age; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + packet.dgps_numch = dgps_numch; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS2_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps2_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint32_t(buf, 20, dgps_age); + _mav_put_uint16_t(buf, 24, eph); + _mav_put_uint16_t(buf, 26, epv); + _mav_put_uint16_t(buf, 28, vel); + _mav_put_uint16_t(buf, 30, cog); + _mav_put_uint8_t(buf, 32, fix_type); + _mav_put_uint8_t(buf, 33, satellites_visible); + _mav_put_uint8_t(buf, 34, dgps_numch); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif +#else + mavlink_gps2_raw_t *packet = (mavlink_gps2_raw_t *)msgbuf; + packet->time_usec = time_usec; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->dgps_age = dgps_age; + packet->eph = eph; + packet->epv = epv; + packet->vel = vel; + packet->cog = cog; + packet->fix_type = fix_type; + packet->satellites_visible = satellites_visible; + packet->dgps_numch = dgps_numch; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS2_RAW UNPACKING + + +/** + * @brief Get field time_usec from gps2_raw message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field fix_type from gps2_raw message + * + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + */ +static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field lat from gps2_raw message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field lon from gps2_raw message + * + * @return Longitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field alt from gps2_raw message + * + * @return Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field eph from gps2_raw message + * + * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field epv from gps2_raw message + * + * @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field vel from gps2_raw message + * + * @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field cog from gps2_raw message + * + * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps2_raw_get_cog(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 30); +} + +/** + * @brief Get field satellites_visible from gps2_raw message + * + * @return Number of satellites visible. If unknown, set to 255 + */ +static inline uint8_t mavlink_msg_gps2_raw_get_satellites_visible(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field dgps_numch from gps2_raw message + * + * @return Number of DGPS satellites + */ +static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field dgps_age from gps2_raw message + * + * @return Age of DGPS info + */ +static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 20); +} + +/** + * @brief Decode a gps2_raw message into a struct + * + * @param msg The message to decode + * @param gps2_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps2_raw_decode(const mavlink_message_t* msg, mavlink_gps2_raw_t* gps2_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps2_raw->time_usec = mavlink_msg_gps2_raw_get_time_usec(msg); + gps2_raw->lat = mavlink_msg_gps2_raw_get_lat(msg); + gps2_raw->lon = mavlink_msg_gps2_raw_get_lon(msg); + gps2_raw->alt = mavlink_msg_gps2_raw_get_alt(msg); + gps2_raw->dgps_age = mavlink_msg_gps2_raw_get_dgps_age(msg); + gps2_raw->eph = mavlink_msg_gps2_raw_get_eph(msg); + gps2_raw->epv = mavlink_msg_gps2_raw_get_epv(msg); + gps2_raw->vel = mavlink_msg_gps2_raw_get_vel(msg); + gps2_raw->cog = mavlink_msg_gps2_raw_get_cog(msg); + gps2_raw->fix_type = mavlink_msg_gps2_raw_get_fix_type(msg); + gps2_raw->satellites_visible = mavlink_msg_gps2_raw_get_satellites_visible(msg); + gps2_raw->dgps_numch = mavlink_msg_gps2_raw_get_dgps_numch(msg); +#else + memcpy(gps2_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps2_rtk.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps2_rtk.h new file mode 100644 index 0000000..66ce52f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps2_rtk.h @@ -0,0 +1,497 @@ +// MESSAGE GPS2_RTK PACKING + +#define MAVLINK_MSG_ID_GPS2_RTK 128 + +typedef struct __mavlink_gps2_rtk_t +{ + uint32_t time_last_baseline_ms; /*< Time since boot of last baseline message received in ms.*/ + uint32_t tow; /*< GPS Time of Week of last baseline*/ + int32_t baseline_a_mm; /*< Current baseline in ECEF x or NED north component in mm.*/ + int32_t baseline_b_mm; /*< Current baseline in ECEF y or NED east component in mm.*/ + int32_t baseline_c_mm; /*< Current baseline in ECEF z or NED down component in mm.*/ + uint32_t accuracy; /*< Current estimate of baseline accuracy.*/ + int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/ + uint16_t wn; /*< GPS Week Number of last baseline*/ + uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/ + uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/ + uint8_t rtk_rate; /*< Rate of baseline messages being received by GPS, in HZ*/ + uint8_t nsats; /*< Current number of sats used for RTK calculation.*/ + uint8_t baseline_coords_type; /*< Coordinate system of baseline. 0 == ECEF, 1 == NED*/ +} mavlink_gps2_rtk_t; + +#define MAVLINK_MSG_ID_GPS2_RTK_LEN 35 +#define MAVLINK_MSG_ID_128_LEN 35 + +#define MAVLINK_MSG_ID_GPS2_RTK_CRC 226 +#define MAVLINK_MSG_ID_128_CRC 226 + + + +#define MAVLINK_MESSAGE_INFO_GPS2_RTK { \ + "GPS2_RTK", \ + 13, \ + { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \ + { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \ + { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \ + { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \ + { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \ + { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \ + { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \ + { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \ + { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \ + { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \ + { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \ + { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \ + { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \ + } \ +} + + +/** + * @brief Pack a gps2_rtk message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps2_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#else + mavlink_gps2_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS2_RTK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +} + +/** + * @brief Pack a gps2_rtk message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps2_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_last_baseline_ms,uint8_t rtk_receiver_id,uint16_t wn,uint32_t tow,uint8_t rtk_health,uint8_t rtk_rate,uint8_t nsats,uint8_t baseline_coords_type,int32_t baseline_a_mm,int32_t baseline_b_mm,int32_t baseline_c_mm,uint32_t accuracy,int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#else + mavlink_gps2_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS2_RTK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +} + +/** + * @brief Encode a gps2_rtk struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps2_rtk C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps2_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk) +{ + return mavlink_msg_gps2_rtk_pack(system_id, component_id, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses); +} + +/** + * @brief Encode a gps2_rtk struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps2_rtk C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps2_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk) +{ + return mavlink_msg_gps2_rtk_pack_chan(system_id, component_id, chan, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses); +} + +/** + * @brief Send a gps2_rtk message + * @param chan MAVLink channel to send the message + * + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps2_rtk_send(mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +#else + mavlink_gps2_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS2_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps2_rtk_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +#else + mavlink_gps2_rtk_t *packet = (mavlink_gps2_rtk_t *)msgbuf; + packet->time_last_baseline_ms = time_last_baseline_ms; + packet->tow = tow; + packet->baseline_a_mm = baseline_a_mm; + packet->baseline_b_mm = baseline_b_mm; + packet->baseline_c_mm = baseline_c_mm; + packet->accuracy = accuracy; + packet->iar_num_hypotheses = iar_num_hypotheses; + packet->wn = wn; + packet->rtk_receiver_id = rtk_receiver_id; + packet->rtk_health = rtk_health; + packet->rtk_rate = rtk_rate; + packet->nsats = nsats; + packet->baseline_coords_type = baseline_coords_type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS2_RTK UNPACKING + + +/** + * @brief Get field time_last_baseline_ms from gps2_rtk message + * + * @return Time since boot of last baseline message received in ms. + */ +static inline uint32_t mavlink_msg_gps2_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field rtk_receiver_id from gps2_rtk message + * + * @return Identification of connected RTK receiver. + */ +static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_receiver_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 30); +} + +/** + * @brief Get field wn from gps2_rtk message + * + * @return GPS Week Number of last baseline + */ +static inline uint16_t mavlink_msg_gps2_rtk_get_wn(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field tow from gps2_rtk message + * + * @return GPS Time of Week of last baseline + */ +static inline uint32_t mavlink_msg_gps2_rtk_get_tow(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Get field rtk_health from gps2_rtk message + * + * @return GPS-specific health report for RTK data. + */ +static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_health(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 31); +} + +/** + * @brief Get field rtk_rate from gps2_rtk message + * + * @return Rate of baseline messages being received by GPS, in HZ + */ +static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field nsats from gps2_rtk message + * + * @return Current number of sats used for RTK calculation. + */ +static inline uint8_t mavlink_msg_gps2_rtk_get_nsats(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field baseline_coords_type from gps2_rtk message + * + * @return Coordinate system of baseline. 0 == ECEF, 1 == NED + */ +static inline uint8_t mavlink_msg_gps2_rtk_get_baseline_coords_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field baseline_a_mm from gps2_rtk message + * + * @return Current baseline in ECEF x or NED north component in mm. + */ +static inline int32_t mavlink_msg_gps2_rtk_get_baseline_a_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field baseline_b_mm from gps2_rtk message + * + * @return Current baseline in ECEF y or NED east component in mm. + */ +static inline int32_t mavlink_msg_gps2_rtk_get_baseline_b_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field baseline_c_mm from gps2_rtk message + * + * @return Current baseline in ECEF z or NED down component in mm. + */ +static inline int32_t mavlink_msg_gps2_rtk_get_baseline_c_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field accuracy from gps2_rtk message + * + * @return Current estimate of baseline accuracy. + */ +static inline uint32_t mavlink_msg_gps2_rtk_get_accuracy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 20); +} + +/** + * @brief Get field iar_num_hypotheses from gps2_rtk message + * + * @return Current number of integer ambiguity hypotheses. + */ +static inline int32_t mavlink_msg_gps2_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 24); +} + +/** + * @brief Decode a gps2_rtk message into a struct + * + * @param msg The message to decode + * @param gps2_rtk C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps2_rtk_decode(const mavlink_message_t* msg, mavlink_gps2_rtk_t* gps2_rtk) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps2_rtk->time_last_baseline_ms = mavlink_msg_gps2_rtk_get_time_last_baseline_ms(msg); + gps2_rtk->tow = mavlink_msg_gps2_rtk_get_tow(msg); + gps2_rtk->baseline_a_mm = mavlink_msg_gps2_rtk_get_baseline_a_mm(msg); + gps2_rtk->baseline_b_mm = mavlink_msg_gps2_rtk_get_baseline_b_mm(msg); + gps2_rtk->baseline_c_mm = mavlink_msg_gps2_rtk_get_baseline_c_mm(msg); + gps2_rtk->accuracy = mavlink_msg_gps2_rtk_get_accuracy(msg); + gps2_rtk->iar_num_hypotheses = mavlink_msg_gps2_rtk_get_iar_num_hypotheses(msg); + gps2_rtk->wn = mavlink_msg_gps2_rtk_get_wn(msg); + gps2_rtk->rtk_receiver_id = mavlink_msg_gps2_rtk_get_rtk_receiver_id(msg); + gps2_rtk->rtk_health = mavlink_msg_gps2_rtk_get_rtk_health(msg); + gps2_rtk->rtk_rate = mavlink_msg_gps2_rtk_get_rtk_rate(msg); + gps2_rtk->nsats = mavlink_msg_gps2_rtk_get_nsats(msg); + gps2_rtk->baseline_coords_type = mavlink_msg_gps2_rtk_get_baseline_coords_type(msg); +#else + memcpy(gps2_rtk, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h new file mode 100644 index 0000000..58048c1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h @@ -0,0 +1,257 @@ +// MESSAGE GPS_GLOBAL_ORIGIN PACKING + +#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49 + +typedef struct __mavlink_gps_global_origin_t +{ + int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t longitude; /*< Longitude (WGS84), in degrees * 1E7*/ + int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ +} mavlink_gps_global_origin_t; + +#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12 +#define MAVLINK_MSG_ID_49_LEN 12 + +#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC 39 +#define MAVLINK_MSG_ID_49_CRC 39 + + + +#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \ + "GPS_GLOBAL_ORIGIN", \ + 3, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_global_origin_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_global_origin_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_global_origin_t, altitude) }, \ + } \ +} + + +/** + * @brief Pack a gps_global_origin message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84), in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#else + mavlink_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif +} + +/** + * @brief Pack a gps_global_origin message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84), in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int32_t latitude,int32_t longitude,int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#else + mavlink_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif +} + +/** + * @brief Encode a gps_global_origin struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_global_origin C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin) +{ + return mavlink_msg_gps_global_origin_pack(system_id, component_id, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude); +} + +/** + * @brief Encode a gps_global_origin struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps_global_origin C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_global_origin_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin) +{ + return mavlink_msg_gps_global_origin_pack_chan(system_id, component_id, chan, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude); +} + +/** + * @brief Send a gps_global_origin message + * @param chan MAVLink channel to send the message + * + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84), in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif +#else + mavlink_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps_global_origin_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif +#else + mavlink_gps_global_origin_t *packet = (mavlink_gps_global_origin_t *)msgbuf; + packet->latitude = latitude; + packet->longitude = longitude; + packet->altitude = altitude; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS_GLOBAL_ORIGIN UNPACKING + + +/** + * @brief Get field latitude from gps_global_origin message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from gps_global_origin message + * + * @return Longitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from gps_global_origin message + * + * @return Altitude (AMSL), in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Decode a gps_global_origin message into a struct + * + * @param msg The message to decode + * @param gps_global_origin C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_global_origin_t* gps_global_origin) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_global_origin->latitude = mavlink_msg_gps_global_origin_get_latitude(msg); + gps_global_origin->longitude = mavlink_msg_gps_global_origin_get_longitude(msg); + gps_global_origin->altitude = mavlink_msg_gps_global_origin_get_altitude(msg); +#else + memcpy(gps_global_origin, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h new file mode 100644 index 0000000..1eca5d8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h @@ -0,0 +1,273 @@ +// MESSAGE GPS_INJECT_DATA PACKING + +#define MAVLINK_MSG_ID_GPS_INJECT_DATA 123 + +typedef struct __mavlink_gps_inject_data_t +{ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t len; /*< data length*/ + uint8_t data[110]; /*< raw data (110 is enough for 12 satellites of RTCMv2)*/ +} mavlink_gps_inject_data_t; + +#define MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113 +#define MAVLINK_MSG_ID_123_LEN 113 + +#define MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC 250 +#define MAVLINK_MSG_ID_123_CRC 250 + +#define MAVLINK_MSG_GPS_INJECT_DATA_FIELD_DATA_LEN 110 + +#define MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA { \ + "GPS_INJECT_DATA", \ + 4, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_inject_data_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_inject_data_t, target_component) }, \ + { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gps_inject_data_t, len) }, \ + { "data", NULL, MAVLINK_TYPE_UINT8_T, 110, 3, offsetof(mavlink_gps_inject_data_t, data) }, \ + } \ +} + + +/** + * @brief Pack a gps_inject_data message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param len data length + * @param data raw data (110 is enough for 12 satellites of RTCMv2) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_inject_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, len); + _mav_put_uint8_t_array(buf, 3, data, 110); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#else + mavlink_gps_inject_data_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.len = len; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif +} + +/** + * @brief Pack a gps_inject_data message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param len data length + * @param data raw data (110 is enough for 12 satellites of RTCMv2) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_inject_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t len,const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, len); + _mav_put_uint8_t_array(buf, 3, data, 110); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#else + mavlink_gps_inject_data_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.len = len; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif +} + +/** + * @brief Encode a gps_inject_data struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_inject_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_inject_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data) +{ + return mavlink_msg_gps_inject_data_pack(system_id, component_id, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data); +} + +/** + * @brief Encode a gps_inject_data struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps_inject_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_inject_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data) +{ + return mavlink_msg_gps_inject_data_pack_chan(system_id, component_id, chan, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data); +} + +/** + * @brief Send a gps_inject_data message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param len data length + * @param data raw data (110 is enough for 12 satellites of RTCMv2) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_inject_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, len); + _mav_put_uint8_t_array(buf, 3, data, 110); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif +#else + mavlink_gps_inject_data_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.len = len; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps_inject_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, len); + _mav_put_uint8_t_array(buf, 3, data, 110); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif +#else + mavlink_gps_inject_data_t *packet = (mavlink_gps_inject_data_t *)msgbuf; + packet->target_system = target_system; + packet->target_component = target_component; + packet->len = len; + mav_array_memcpy(packet->data, data, sizeof(uint8_t)*110); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS_INJECT_DATA UNPACKING + + +/** + * @brief Get field target_system from gps_inject_data message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_gps_inject_data_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from gps_inject_data message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_gps_inject_data_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field len from gps_inject_data message + * + * @return data length + */ +static inline uint8_t mavlink_msg_gps_inject_data_get_len(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field data from gps_inject_data message + * + * @return raw data (110 is enough for 12 satellites of RTCMv2) + */ +static inline uint16_t mavlink_msg_gps_inject_data_get_data(const mavlink_message_t* msg, uint8_t *data) +{ + return _MAV_RETURN_uint8_t_array(msg, data, 110, 3); +} + +/** + * @brief Decode a gps_inject_data message into a struct + * + * @param msg The message to decode + * @param gps_inject_data C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_inject_data_decode(const mavlink_message_t* msg, mavlink_gps_inject_data_t* gps_inject_data) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_inject_data->target_system = mavlink_msg_gps_inject_data_get_target_system(msg); + gps_inject_data->target_component = mavlink_msg_gps_inject_data_get_target_component(msg); + gps_inject_data->len = mavlink_msg_gps_inject_data_get_len(msg); + mavlink_msg_gps_inject_data_get_data(msg, gps_inject_data->data); +#else + memcpy(gps_inject_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h new file mode 100644 index 0000000..feb5d13 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h @@ -0,0 +1,425 @@ +// MESSAGE GPS_RAW_INT PACKING + +#define MAVLINK_MSG_ID_GPS_RAW_INT 24 + +typedef struct __mavlink_gps_raw_int_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ + int32_t alt; /*< Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.*/ + uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/ + uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/ + uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX*/ + uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ + uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.*/ + uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ +} mavlink_gps_raw_int_t; + +#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30 +#define MAVLINK_MSG_ID_24_LEN 30 + +#define MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24 +#define MAVLINK_MSG_ID_24_CRC 24 + + + +#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \ + "GPS_RAW_INT", \ + 10, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \ + { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \ + { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \ + { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \ + { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ + { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \ + } \ +} + + +/** + * @brief Pack a gps_raw_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. + * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_uint16_t(buf, 26, cog); + _mav_put_uint8_t(buf, 28, fix_type); + _mav_put_uint8_t(buf, 29, satellites_visible); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#else + mavlink_gps_raw_int_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif +} + +/** + * @brief Pack a gps_raw_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. + * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_uint16_t(buf, 26, cog); + _mav_put_uint8_t(buf, 28, fix_type); + _mav_put_uint8_t(buf, 29, satellites_visible); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#else + mavlink_gps_raw_int_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif +} + +/** + * @brief Encode a gps_raw_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_raw_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int) +{ + return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible); +} + +/** + * @brief Encode a gps_raw_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps_raw_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int) +{ + return mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, chan, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible); +} + +/** + * @brief Send a gps_raw_int message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. + * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_uint16_t(buf, 26, cog); + _mav_put_uint8_t(buf, 28, fix_type); + _mav_put_uint8_t(buf, 29, satellites_visible); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif +#else + mavlink_gps_raw_int_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS_RAW_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_uint16_t(buf, 26, cog); + _mav_put_uint8_t(buf, 28, fix_type); + _mav_put_uint8_t(buf, 29, satellites_visible); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif +#else + mavlink_gps_raw_int_t *packet = (mavlink_gps_raw_int_t *)msgbuf; + packet->time_usec = time_usec; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->eph = eph; + packet->epv = epv; + packet->vel = vel; + packet->cog = cog; + packet->fix_type = fix_type; + packet->satellites_visible = satellites_visible; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS_RAW_INT UNPACKING + + +/** + * @brief Get field time_usec from gps_raw_int message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field fix_type from gps_raw_int message + * + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + */ +static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 28); +} + +/** + * @brief Get field lat from gps_raw_int message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field lon from gps_raw_int message + * + * @return Longitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field alt from gps_raw_int message + * + * @return Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. + */ +static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field eph from gps_raw_int message + * + * @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field epv from gps_raw_int message + * + * @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field vel from gps_raw_int message + * + * @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field cog from gps_raw_int message + * + * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field satellites_visible from gps_raw_int message + * + * @return Number of satellites visible. If unknown, set to 255 + */ +static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 29); +} + +/** + * @brief Decode a gps_raw_int message into a struct + * + * @param msg The message to decode + * @param gps_raw_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_raw_int->time_usec = mavlink_msg_gps_raw_int_get_time_usec(msg); + gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg); + gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg); + gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg); + gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg); + gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg); + gps_raw_int->vel = mavlink_msg_gps_raw_int_get_vel(msg); + gps_raw_int->cog = mavlink_msg_gps_raw_int_get_cog(msg); + gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg); + gps_raw_int->satellites_visible = mavlink_msg_gps_raw_int_get_satellites_visible(msg); +#else + memcpy(gps_raw_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps_rtk.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps_rtk.h new file mode 100644 index 0000000..b627d89 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps_rtk.h @@ -0,0 +1,497 @@ +// MESSAGE GPS_RTK PACKING + +#define MAVLINK_MSG_ID_GPS_RTK 127 + +typedef struct __mavlink_gps_rtk_t +{ + uint32_t time_last_baseline_ms; /*< Time since boot of last baseline message received in ms.*/ + uint32_t tow; /*< GPS Time of Week of last baseline*/ + int32_t baseline_a_mm; /*< Current baseline in ECEF x or NED north component in mm.*/ + int32_t baseline_b_mm; /*< Current baseline in ECEF y or NED east component in mm.*/ + int32_t baseline_c_mm; /*< Current baseline in ECEF z or NED down component in mm.*/ + uint32_t accuracy; /*< Current estimate of baseline accuracy.*/ + int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/ + uint16_t wn; /*< GPS Week Number of last baseline*/ + uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/ + uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/ + uint8_t rtk_rate; /*< Rate of baseline messages being received by GPS, in HZ*/ + uint8_t nsats; /*< Current number of sats used for RTK calculation.*/ + uint8_t baseline_coords_type; /*< Coordinate system of baseline. 0 == ECEF, 1 == NED*/ +} mavlink_gps_rtk_t; + +#define MAVLINK_MSG_ID_GPS_RTK_LEN 35 +#define MAVLINK_MSG_ID_127_LEN 35 + +#define MAVLINK_MSG_ID_GPS_RTK_CRC 25 +#define MAVLINK_MSG_ID_127_CRC 25 + + + +#define MAVLINK_MESSAGE_INFO_GPS_RTK { \ + "GPS_RTK", \ + 13, \ + { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps_rtk_t, time_last_baseline_ms) }, \ + { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps_rtk_t, tow) }, \ + { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_rtk_t, baseline_a_mm) }, \ + { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_rtk_t, baseline_b_mm) }, \ + { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_rtk_t, baseline_c_mm) }, \ + { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps_rtk_t, accuracy) }, \ + { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps_rtk_t, iar_num_hypotheses) }, \ + { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \ + { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \ + { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \ + { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \ + { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \ + { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \ + } \ +} + + +/** + * @brief Pack a gps_rtk message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTK_LEN); +#else + mavlink_gps_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RTK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +} + +/** + * @brief Pack a gps_rtk message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_last_baseline_ms,uint8_t rtk_receiver_id,uint16_t wn,uint32_t tow,uint8_t rtk_health,uint8_t rtk_rate,uint8_t nsats,uint8_t baseline_coords_type,int32_t baseline_a_mm,int32_t baseline_b_mm,int32_t baseline_c_mm,uint32_t accuracy,int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTK_LEN); +#else + mavlink_gps_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RTK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +} + +/** + * @brief Encode a gps_rtk struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_rtk C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_rtk_t* gps_rtk) +{ + return mavlink_msg_gps_rtk_pack(system_id, component_id, msg, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses); +} + +/** + * @brief Encode a gps_rtk struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps_rtk C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_rtk_t* gps_rtk) +{ + return mavlink_msg_gps_rtk_pack_chan(system_id, component_id, chan, msg, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses); +} + +/** + * @brief Send a gps_rtk message + * @param chan MAVLink channel to send the message + * + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_rtk_send(mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +#else + mavlink_gps_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps_rtk_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +#else + mavlink_gps_rtk_t *packet = (mavlink_gps_rtk_t *)msgbuf; + packet->time_last_baseline_ms = time_last_baseline_ms; + packet->tow = tow; + packet->baseline_a_mm = baseline_a_mm; + packet->baseline_b_mm = baseline_b_mm; + packet->baseline_c_mm = baseline_c_mm; + packet->accuracy = accuracy; + packet->iar_num_hypotheses = iar_num_hypotheses; + packet->wn = wn; + packet->rtk_receiver_id = rtk_receiver_id; + packet->rtk_health = rtk_health; + packet->rtk_rate = rtk_rate; + packet->nsats = nsats; + packet->baseline_coords_type = baseline_coords_type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS_RTK UNPACKING + + +/** + * @brief Get field time_last_baseline_ms from gps_rtk message + * + * @return Time since boot of last baseline message received in ms. + */ +static inline uint32_t mavlink_msg_gps_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field rtk_receiver_id from gps_rtk message + * + * @return Identification of connected RTK receiver. + */ +static inline uint8_t mavlink_msg_gps_rtk_get_rtk_receiver_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 30); +} + +/** + * @brief Get field wn from gps_rtk message + * + * @return GPS Week Number of last baseline + */ +static inline uint16_t mavlink_msg_gps_rtk_get_wn(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field tow from gps_rtk message + * + * @return GPS Time of Week of last baseline + */ +static inline uint32_t mavlink_msg_gps_rtk_get_tow(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Get field rtk_health from gps_rtk message + * + * @return GPS-specific health report for RTK data. + */ +static inline uint8_t mavlink_msg_gps_rtk_get_rtk_health(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 31); +} + +/** + * @brief Get field rtk_rate from gps_rtk message + * + * @return Rate of baseline messages being received by GPS, in HZ + */ +static inline uint8_t mavlink_msg_gps_rtk_get_rtk_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field nsats from gps_rtk message + * + * @return Current number of sats used for RTK calculation. + */ +static inline uint8_t mavlink_msg_gps_rtk_get_nsats(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field baseline_coords_type from gps_rtk message + * + * @return Coordinate system of baseline. 0 == ECEF, 1 == NED + */ +static inline uint8_t mavlink_msg_gps_rtk_get_baseline_coords_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field baseline_a_mm from gps_rtk message + * + * @return Current baseline in ECEF x or NED north component in mm. + */ +static inline int32_t mavlink_msg_gps_rtk_get_baseline_a_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field baseline_b_mm from gps_rtk message + * + * @return Current baseline in ECEF y or NED east component in mm. + */ +static inline int32_t mavlink_msg_gps_rtk_get_baseline_b_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field baseline_c_mm from gps_rtk message + * + * @return Current baseline in ECEF z or NED down component in mm. + */ +static inline int32_t mavlink_msg_gps_rtk_get_baseline_c_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field accuracy from gps_rtk message + * + * @return Current estimate of baseline accuracy. + */ +static inline uint32_t mavlink_msg_gps_rtk_get_accuracy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 20); +} + +/** + * @brief Get field iar_num_hypotheses from gps_rtk message + * + * @return Current number of integer ambiguity hypotheses. + */ +static inline int32_t mavlink_msg_gps_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 24); +} + +/** + * @brief Decode a gps_rtk message into a struct + * + * @param msg The message to decode + * @param gps_rtk C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_rtk_decode(const mavlink_message_t* msg, mavlink_gps_rtk_t* gps_rtk) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_rtk->time_last_baseline_ms = mavlink_msg_gps_rtk_get_time_last_baseline_ms(msg); + gps_rtk->tow = mavlink_msg_gps_rtk_get_tow(msg); + gps_rtk->baseline_a_mm = mavlink_msg_gps_rtk_get_baseline_a_mm(msg); + gps_rtk->baseline_b_mm = mavlink_msg_gps_rtk_get_baseline_b_mm(msg); + gps_rtk->baseline_c_mm = mavlink_msg_gps_rtk_get_baseline_c_mm(msg); + gps_rtk->accuracy = mavlink_msg_gps_rtk_get_accuracy(msg); + gps_rtk->iar_num_hypotheses = mavlink_msg_gps_rtk_get_iar_num_hypotheses(msg); + gps_rtk->wn = mavlink_msg_gps_rtk_get_wn(msg); + gps_rtk->rtk_receiver_id = mavlink_msg_gps_rtk_get_rtk_receiver_id(msg); + gps_rtk->rtk_health = mavlink_msg_gps_rtk_get_rtk_health(msg); + gps_rtk->rtk_rate = mavlink_msg_gps_rtk_get_rtk_rate(msg); + gps_rtk->nsats = mavlink_msg_gps_rtk_get_nsats(msg); + gps_rtk->baseline_coords_type = mavlink_msg_gps_rtk_get_baseline_coords_type(msg); +#else + memcpy(gps_rtk, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps_status.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps_status.h new file mode 100644 index 0000000..3e279b4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_gps_status.h @@ -0,0 +1,325 @@ +// MESSAGE GPS_STATUS PACKING + +#define MAVLINK_MSG_ID_GPS_STATUS 25 + +typedef struct __mavlink_gps_status_t +{ + uint8_t satellites_visible; /*< Number of satellites visible*/ + uint8_t satellite_prn[20]; /*< Global satellite ID*/ + uint8_t satellite_used[20]; /*< 0: Satellite not used, 1: used for localization*/ + uint8_t satellite_elevation[20]; /*< Elevation (0: right on top of receiver, 90: on the horizon) of satellite*/ + uint8_t satellite_azimuth[20]; /*< Direction of satellite, 0: 0 deg, 255: 360 deg.*/ + uint8_t satellite_snr[20]; /*< Signal to noise ratio of satellite*/ +} mavlink_gps_status_t; + +#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101 +#define MAVLINK_MSG_ID_25_LEN 101 + +#define MAVLINK_MSG_ID_GPS_STATUS_CRC 23 +#define MAVLINK_MSG_ID_25_CRC 23 + +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20 + +#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \ + "GPS_STATUS", \ + 6, \ + { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \ + { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \ + { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \ + { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \ + { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \ + { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \ + } \ +} + + +/** + * @brief Pack a gps_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN]; + _mav_put_uint8_t(buf, 0, satellites_visible); + _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); + _mav_put_uint8_t_array(buf, 21, satellite_used, 20); + _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); + _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); + _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#else + mavlink_gps_status_t packet; + packet.satellites_visible = satellites_visible; + mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif +} + +/** + * @brief Pack a gps_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t satellites_visible,const uint8_t *satellite_prn,const uint8_t *satellite_used,const uint8_t *satellite_elevation,const uint8_t *satellite_azimuth,const uint8_t *satellite_snr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN]; + _mav_put_uint8_t(buf, 0, satellites_visible); + _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); + _mav_put_uint8_t_array(buf, 21, satellite_used, 20); + _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); + _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); + _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#else + mavlink_gps_status_t packet; + packet.satellites_visible = satellites_visible; + mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif +} + +/** + * @brief Encode a gps_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) +{ + return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); +} + +/** + * @brief Encode a gps_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) +{ + return mavlink_msg_gps_status_pack_chan(system_id, component_id, chan, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); +} + +/** + * @brief Send a gps_status message + * @param chan MAVLink channel to send the message + * + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN]; + _mav_put_uint8_t(buf, 0, satellites_visible); + _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); + _mav_put_uint8_t_array(buf, 21, satellite_used, 20); + _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); + _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); + _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif +#else + mavlink_gps_status_t packet; + packet.satellites_visible = satellites_visible; + mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, satellites_visible); + _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); + _mav_put_uint8_t_array(buf, 21, satellite_used, 20); + _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); + _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); + _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif +#else + mavlink_gps_status_t *packet = (mavlink_gps_status_t *)msgbuf; + packet->satellites_visible = satellites_visible; + mav_array_memcpy(packet->satellite_prn, satellite_prn, sizeof(uint8_t)*20); + mav_array_memcpy(packet->satellite_used, satellite_used, sizeof(uint8_t)*20); + mav_array_memcpy(packet->satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); + mav_array_memcpy(packet->satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); + mav_array_memcpy(packet->satellite_snr, satellite_snr, sizeof(uint8_t)*20); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS_STATUS UNPACKING + + +/** + * @brief Get field satellites_visible from gps_status message + * + * @return Number of satellites visible + */ +static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field satellite_prn from gps_status message + * + * @return Global satellite ID + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_prn, 20, 1); +} + +/** + * @brief Get field satellite_used from gps_status message + * + * @return 0: Satellite not used, 1: used for localization + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_used, 20, 21); +} + +/** + * @brief Get field satellite_elevation from gps_status message + * + * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, 20, 41); +} + +/** + * @brief Get field satellite_azimuth from gps_status message + * + * @return Direction of satellite, 0: 0 deg, 255: 360 deg. + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, 20, 61); +} + +/** + * @brief Get field satellite_snr from gps_status message + * + * @return Signal to noise ratio of satellite + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_snr, 20, 81); +} + +/** + * @brief Decode a gps_status message into a struct + * + * @param msg The message to decode + * @param gps_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg); + mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn); + mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used); + mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation); + mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth); + mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr); +#else + memcpy(gps_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_heartbeat.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_heartbeat.h new file mode 100644 index 0000000..682b4d8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_heartbeat.h @@ -0,0 +1,326 @@ +// MESSAGE HEARTBEAT PACKING + +#define MAVLINK_MSG_ID_HEARTBEAT 0 + +typedef struct __mavlink_heartbeat_t +{ + uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/ + uint8_t type; /*< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)*/ + uint8_t autopilot; /*< Autopilot type / class. defined in MAV_AUTOPILOT ENUM*/ + uint8_t base_mode; /*< System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h*/ + uint8_t system_status; /*< System status flag, see MAV_STATE ENUM*/ + uint8_t mavlink_version; /*< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version*/ +} mavlink_heartbeat_t; + +#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9 +#define MAVLINK_MSG_ID_0_LEN 9 + +#define MAVLINK_MSG_ID_HEARTBEAT_CRC 50 +#define MAVLINK_MSG_ID_0_CRC 50 + + + +#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \ + "HEARTBEAT", \ + 6, \ + { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ + { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \ + { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \ + { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \ + { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ + } \ +} + + +/** + * @brief Pack a heartbeat message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM + * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param system_status System status flag, see MAV_STATE ENUM + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 3); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#else + mavlink_heartbeat_t packet; + packet.custom_mode = custom_mode; + packet.type = type; + packet.autopilot = autopilot; + packet.base_mode = base_mode; + packet.system_status = system_status; + packet.mavlink_version = 3; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif +} + +/** + * @brief Pack a heartbeat message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM + * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param system_status System status flag, see MAV_STATE ENUM + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 3); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#else + mavlink_heartbeat_t packet; + packet.custom_mode = custom_mode; + packet.type = type; + packet.autopilot = autopilot; + packet.base_mode = base_mode; + packet.system_status = system_status; + packet.mavlink_version = 3; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif +} + +/** + * @brief Encode a heartbeat struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param heartbeat C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) +{ + return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); +} + +/** + * @brief Encode a heartbeat struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param heartbeat C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) +{ + return mavlink_msg_heartbeat_pack_chan(system_id, component_id, chan, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); +} + +/** + * @brief Send a heartbeat message + * @param chan MAVLink channel to send the message + * + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM + * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param system_status System status flag, see MAV_STATE ENUM + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 3); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif +#else + mavlink_heartbeat_t packet; + packet.custom_mode = custom_mode; + packet.type = type; + packet.autopilot = autopilot; + packet.base_mode = base_mode; + packet.system_status = system_status; + packet.mavlink_version = 3; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 3); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif +#else + mavlink_heartbeat_t *packet = (mavlink_heartbeat_t *)msgbuf; + packet->custom_mode = custom_mode; + packet->type = type; + packet->autopilot = autopilot; + packet->base_mode = base_mode; + packet->system_status = system_status; + packet->mavlink_version = 3; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HEARTBEAT UNPACKING + + +/** + * @brief Get field type from heartbeat message + * + * @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + */ +static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field autopilot from heartbeat message + * + * @return Autopilot type / class. defined in MAV_AUTOPILOT ENUM + */ +static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field base_mode from heartbeat message + * + * @return System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h + */ +static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field custom_mode from heartbeat message + * + * @return A bitfield for use for autopilot-specific flags. + */ +static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field system_status from heartbeat message + * + * @return System status flag, see MAV_STATE ENUM + */ +static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field mavlink_version from heartbeat message + * + * @return MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version + */ +static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Decode a heartbeat message into a struct + * + * @param msg The message to decode + * @param heartbeat C-struct to decode the message contents into + */ +static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat) +{ +#if MAVLINK_NEED_BYTE_SWAP + heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg); + heartbeat->type = mavlink_msg_heartbeat_get_type(msg); + heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg); + heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg); + heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg); + heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg); +#else + memcpy(heartbeat, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_highres_imu.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_highres_imu.h new file mode 100644 index 0000000..654953d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_highres_imu.h @@ -0,0 +1,545 @@ +// MESSAGE HIGHRES_IMU PACKING + +#define MAVLINK_MSG_ID_HIGHRES_IMU 105 + +typedef struct __mavlink_highres_imu_t +{ + uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + float xacc; /*< X acceleration (m/s^2)*/ + float yacc; /*< Y acceleration (m/s^2)*/ + float zacc; /*< Z acceleration (m/s^2)*/ + float xgyro; /*< Angular speed around X axis (rad / sec)*/ + float ygyro; /*< Angular speed around Y axis (rad / sec)*/ + float zgyro; /*< Angular speed around Z axis (rad / sec)*/ + float xmag; /*< X Magnetic field (Gauss)*/ + float ymag; /*< Y Magnetic field (Gauss)*/ + float zmag; /*< Z Magnetic field (Gauss)*/ + float abs_pressure; /*< Absolute pressure in millibar*/ + float diff_pressure; /*< Differential pressure in millibar*/ + float pressure_alt; /*< Altitude calculated from pressure*/ + float temperature; /*< Temperature in degrees celsius*/ + uint16_t fields_updated; /*< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature*/ +} mavlink_highres_imu_t; + +#define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62 +#define MAVLINK_MSG_ID_105_LEN 62 + +#define MAVLINK_MSG_ID_HIGHRES_IMU_CRC 93 +#define MAVLINK_MSG_ID_105_CRC 93 + + + +#define MAVLINK_MESSAGE_INFO_HIGHRES_IMU { \ + "HIGHRES_IMU", \ + 15, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_highres_imu_t, time_usec) }, \ + { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_highres_imu_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_highres_imu_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_highres_imu_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_highres_imu_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_highres_imu_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_highres_imu_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_highres_imu_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_highres_imu_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_highres_imu_t, zmag) }, \ + { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_highres_imu_t, abs_pressure) }, \ + { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_highres_imu_t, diff_pressure) }, \ + { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_highres_imu_t, pressure_alt) }, \ + { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_highres_imu_t, temperature) }, \ + { "fields_updated", NULL, MAVLINK_TYPE_UINT16_T, 0, 60, offsetof(mavlink_highres_imu_t, fields_updated) }, \ + } \ +} + + +/** + * @brief Pack a highres_imu message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param xacc X acceleration (m/s^2) + * @param yacc Y acceleration (m/s^2) + * @param zacc Z acceleration (m/s^2) + * @param xgyro Angular speed around X axis (rad / sec) + * @param ygyro Angular speed around Y axis (rad / sec) + * @param zgyro Angular speed around Z axis (rad / sec) + * @param xmag X Magnetic field (Gauss) + * @param ymag Y Magnetic field (Gauss) + * @param zmag Z Magnetic field (Gauss) + * @param abs_pressure Absolute pressure in millibar + * @param diff_pressure Differential pressure in millibar + * @param pressure_alt Altitude calculated from pressure + * @param temperature Temperature in degrees celsius + * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint16_t(buf, 60, fields_updated); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#else + mavlink_highres_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + packet.abs_pressure = abs_pressure; + packet.diff_pressure = diff_pressure; + packet.pressure_alt = pressure_alt; + packet.temperature = temperature; + packet.fields_updated = fields_updated; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIGHRES_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif +} + +/** + * @brief Pack a highres_imu message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param xacc X acceleration (m/s^2) + * @param yacc Y acceleration (m/s^2) + * @param zacc Z acceleration (m/s^2) + * @param xgyro Angular speed around X axis (rad / sec) + * @param ygyro Angular speed around Y axis (rad / sec) + * @param zgyro Angular speed around Z axis (rad / sec) + * @param xmag X Magnetic field (Gauss) + * @param ymag Y Magnetic field (Gauss) + * @param zmag Z Magnetic field (Gauss) + * @param abs_pressure Absolute pressure in millibar + * @param diff_pressure Differential pressure in millibar + * @param pressure_alt Altitude calculated from pressure + * @param temperature Temperature in degrees celsius + * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,uint16_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint16_t(buf, 60, fields_updated); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#else + mavlink_highres_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + packet.abs_pressure = abs_pressure; + packet.diff_pressure = diff_pressure; + packet.pressure_alt = pressure_alt; + packet.temperature = temperature; + packet.fields_updated = fields_updated; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIGHRES_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif +} + +/** + * @brief Encode a highres_imu struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param highres_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_highres_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu) +{ + return mavlink_msg_highres_imu_pack(system_id, component_id, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated); +} + +/** + * @brief Encode a highres_imu struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param highres_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_highres_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu) +{ + return mavlink_msg_highres_imu_pack_chan(system_id, component_id, chan, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated); +} + +/** + * @brief Send a highres_imu message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param xacc X acceleration (m/s^2) + * @param yacc Y acceleration (m/s^2) + * @param zacc Z acceleration (m/s^2) + * @param xgyro Angular speed around X axis (rad / sec) + * @param ygyro Angular speed around Y axis (rad / sec) + * @param zgyro Angular speed around Z axis (rad / sec) + * @param xmag X Magnetic field (Gauss) + * @param ymag Y Magnetic field (Gauss) + * @param zmag Z Magnetic field (Gauss) + * @param abs_pressure Absolute pressure in millibar + * @param diff_pressure Differential pressure in millibar + * @param pressure_alt Altitude calculated from pressure + * @param temperature Temperature in degrees celsius + * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_highres_imu_send(mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint16_t(buf, 60, fields_updated); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif +#else + mavlink_highres_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + packet.abs_pressure = abs_pressure; + packet.diff_pressure = diff_pressure; + packet.pressure_alt = pressure_alt; + packet.temperature = temperature; + packet.fields_updated = fields_updated; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIGHRES_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_highres_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint16_t(buf, 60, fields_updated); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif +#else + mavlink_highres_imu_t *packet = (mavlink_highres_imu_t *)msgbuf; + packet->time_usec = time_usec; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->xmag = xmag; + packet->ymag = ymag; + packet->zmag = zmag; + packet->abs_pressure = abs_pressure; + packet->diff_pressure = diff_pressure; + packet->pressure_alt = pressure_alt; + packet->temperature = temperature; + packet->fields_updated = fields_updated; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIGHRES_IMU UNPACKING + + +/** + * @brief Get field time_usec from highres_imu message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_highres_imu_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field xacc from highres_imu message + * + * @return X acceleration (m/s^2) + */ +static inline float mavlink_msg_highres_imu_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yacc from highres_imu message + * + * @return Y acceleration (m/s^2) + */ +static inline float mavlink_msg_highres_imu_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field zacc from highres_imu message + * + * @return Z acceleration (m/s^2) + */ +static inline float mavlink_msg_highres_imu_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field xgyro from highres_imu message + * + * @return Angular speed around X axis (rad / sec) + */ +static inline float mavlink_msg_highres_imu_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field ygyro from highres_imu message + * + * @return Angular speed around Y axis (rad / sec) + */ +static inline float mavlink_msg_highres_imu_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field zgyro from highres_imu message + * + * @return Angular speed around Z axis (rad / sec) + */ +static inline float mavlink_msg_highres_imu_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field xmag from highres_imu message + * + * @return X Magnetic field (Gauss) + */ +static inline float mavlink_msg_highres_imu_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field ymag from highres_imu message + * + * @return Y Magnetic field (Gauss) + */ +static inline float mavlink_msg_highres_imu_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field zmag from highres_imu message + * + * @return Z Magnetic field (Gauss) + */ +static inline float mavlink_msg_highres_imu_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field abs_pressure from highres_imu message + * + * @return Absolute pressure in millibar + */ +static inline float mavlink_msg_highres_imu_get_abs_pressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field diff_pressure from highres_imu message + * + * @return Differential pressure in millibar + */ +static inline float mavlink_msg_highres_imu_get_diff_pressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 48); +} + +/** + * @brief Get field pressure_alt from highres_imu message + * + * @return Altitude calculated from pressure + */ +static inline float mavlink_msg_highres_imu_get_pressure_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 52); +} + +/** + * @brief Get field temperature from highres_imu message + * + * @return Temperature in degrees celsius + */ +static inline float mavlink_msg_highres_imu_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 56); +} + +/** + * @brief Get field fields_updated from highres_imu message + * + * @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + */ +static inline uint16_t mavlink_msg_highres_imu_get_fields_updated(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 60); +} + +/** + * @brief Decode a highres_imu message into a struct + * + * @param msg The message to decode + * @param highres_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_highres_imu_decode(const mavlink_message_t* msg, mavlink_highres_imu_t* highres_imu) +{ +#if MAVLINK_NEED_BYTE_SWAP + highres_imu->time_usec = mavlink_msg_highres_imu_get_time_usec(msg); + highres_imu->xacc = mavlink_msg_highres_imu_get_xacc(msg); + highres_imu->yacc = mavlink_msg_highres_imu_get_yacc(msg); + highres_imu->zacc = mavlink_msg_highres_imu_get_zacc(msg); + highres_imu->xgyro = mavlink_msg_highres_imu_get_xgyro(msg); + highres_imu->ygyro = mavlink_msg_highres_imu_get_ygyro(msg); + highres_imu->zgyro = mavlink_msg_highres_imu_get_zgyro(msg); + highres_imu->xmag = mavlink_msg_highres_imu_get_xmag(msg); + highres_imu->ymag = mavlink_msg_highres_imu_get_ymag(msg); + highres_imu->zmag = mavlink_msg_highres_imu_get_zmag(msg); + highres_imu->abs_pressure = mavlink_msg_highres_imu_get_abs_pressure(msg); + highres_imu->diff_pressure = mavlink_msg_highres_imu_get_diff_pressure(msg); + highres_imu->pressure_alt = mavlink_msg_highres_imu_get_pressure_alt(msg); + highres_imu->temperature = mavlink_msg_highres_imu_get_temperature(msg); + highres_imu->fields_updated = mavlink_msg_highres_imu_get_fields_updated(msg); +#else + memcpy(highres_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_controls.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_controls.h new file mode 100644 index 0000000..4d586af --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_controls.h @@ -0,0 +1,449 @@ +// MESSAGE HIL_CONTROLS PACKING + +#define MAVLINK_MSG_ID_HIL_CONTROLS 91 + +typedef struct __mavlink_hil_controls_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + float roll_ailerons; /*< Control output -1 .. 1*/ + float pitch_elevator; /*< Control output -1 .. 1*/ + float yaw_rudder; /*< Control output -1 .. 1*/ + float throttle; /*< Throttle 0 .. 1*/ + float aux1; /*< Aux 1, -1 .. 1*/ + float aux2; /*< Aux 2, -1 .. 1*/ + float aux3; /*< Aux 3, -1 .. 1*/ + float aux4; /*< Aux 4, -1 .. 1*/ + uint8_t mode; /*< System mode (MAV_MODE)*/ + uint8_t nav_mode; /*< Navigation mode (MAV_NAV_MODE)*/ +} mavlink_hil_controls_t; + +#define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42 +#define MAVLINK_MSG_ID_91_LEN 42 + +#define MAVLINK_MSG_ID_HIL_CONTROLS_CRC 63 +#define MAVLINK_MSG_ID_91_CRC 63 + + + +#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \ + "HIL_CONTROLS", \ + 11, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \ + { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \ + { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \ + { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \ + { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \ + { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \ + { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \ + { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \ + { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \ + { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \ + { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \ + } \ +} + + +/** + * @brief Pack a hil_controls message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll_ailerons Control output -1 .. 1 + * @param pitch_elevator Control output -1 .. 1 + * @param yaw_rudder Control output -1 .. 1 + * @param throttle Throttle 0 .. 1 + * @param aux1 Aux 1, -1 .. 1 + * @param aux2 Aux 2, -1 .. 1 + * @param aux3 Aux 3, -1 .. 1 + * @param aux4 Aux 4, -1 .. 1 + * @param mode System mode (MAV_MODE) + * @param nav_mode Navigation mode (MAV_NAV_MODE) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll_ailerons); + _mav_put_float(buf, 12, pitch_elevator); + _mav_put_float(buf, 16, yaw_rudder); + _mav_put_float(buf, 20, throttle); + _mav_put_float(buf, 24, aux1); + _mav_put_float(buf, 28, aux2); + _mav_put_float(buf, 32, aux3); + _mav_put_float(buf, 36, aux4); + _mav_put_uint8_t(buf, 40, mode); + _mav_put_uint8_t(buf, 41, nav_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#else + mavlink_hil_controls_t packet; + packet.time_usec = time_usec; + packet.roll_ailerons = roll_ailerons; + packet.pitch_elevator = pitch_elevator; + packet.yaw_rudder = yaw_rudder; + packet.throttle = throttle; + packet.aux1 = aux1; + packet.aux2 = aux2; + packet.aux3 = aux3; + packet.aux4 = aux4; + packet.mode = mode; + packet.nav_mode = nav_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif +} + +/** + * @brief Pack a hil_controls message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll_ailerons Control output -1 .. 1 + * @param pitch_elevator Control output -1 .. 1 + * @param yaw_rudder Control output -1 .. 1 + * @param throttle Throttle 0 .. 1 + * @param aux1 Aux 1, -1 .. 1 + * @param aux2 Aux 2, -1 .. 1 + * @param aux3 Aux 3, -1 .. 1 + * @param aux4 Aux 4, -1 .. 1 + * @param mode System mode (MAV_MODE) + * @param nav_mode Navigation mode (MAV_NAV_MODE) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,uint8_t mode,uint8_t nav_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll_ailerons); + _mav_put_float(buf, 12, pitch_elevator); + _mav_put_float(buf, 16, yaw_rudder); + _mav_put_float(buf, 20, throttle); + _mav_put_float(buf, 24, aux1); + _mav_put_float(buf, 28, aux2); + _mav_put_float(buf, 32, aux3); + _mav_put_float(buf, 36, aux4); + _mav_put_uint8_t(buf, 40, mode); + _mav_put_uint8_t(buf, 41, nav_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#else + mavlink_hil_controls_t packet; + packet.time_usec = time_usec; + packet.roll_ailerons = roll_ailerons; + packet.pitch_elevator = pitch_elevator; + packet.yaw_rudder = yaw_rudder; + packet.throttle = throttle; + packet.aux1 = aux1; + packet.aux2 = aux2; + packet.aux3 = aux3; + packet.aux4 = aux4; + packet.mode = mode; + packet.nav_mode = nav_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif +} + +/** + * @brief Encode a hil_controls struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_controls C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls) +{ + return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); +} + +/** + * @brief Encode a hil_controls struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param hil_controls C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_controls_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls) +{ + return mavlink_msg_hil_controls_pack_chan(system_id, component_id, chan, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); +} + +/** + * @brief Send a hil_controls message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll_ailerons Control output -1 .. 1 + * @param pitch_elevator Control output -1 .. 1 + * @param yaw_rudder Control output -1 .. 1 + * @param throttle Throttle 0 .. 1 + * @param aux1 Aux 1, -1 .. 1 + * @param aux2 Aux 2, -1 .. 1 + * @param aux3 Aux 3, -1 .. 1 + * @param aux4 Aux 4, -1 .. 1 + * @param mode System mode (MAV_MODE) + * @param nav_mode Navigation mode (MAV_NAV_MODE) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll_ailerons); + _mav_put_float(buf, 12, pitch_elevator); + _mav_put_float(buf, 16, yaw_rudder); + _mav_put_float(buf, 20, throttle); + _mav_put_float(buf, 24, aux1); + _mav_put_float(buf, 28, aux2); + _mav_put_float(buf, 32, aux3); + _mav_put_float(buf, 36, aux4); + _mav_put_uint8_t(buf, 40, mode); + _mav_put_uint8_t(buf, 41, nav_mode); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif +#else + mavlink_hil_controls_t packet; + packet.time_usec = time_usec; + packet.roll_ailerons = roll_ailerons; + packet.pitch_elevator = pitch_elevator; + packet.yaw_rudder = yaw_rudder; + packet.throttle = throttle; + packet.aux1 = aux1; + packet.aux2 = aux2; + packet.aux3 = aux3; + packet.aux4 = aux4; + packet.mode = mode; + packet.nav_mode = nav_mode; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIL_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_hil_controls_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll_ailerons); + _mav_put_float(buf, 12, pitch_elevator); + _mav_put_float(buf, 16, yaw_rudder); + _mav_put_float(buf, 20, throttle); + _mav_put_float(buf, 24, aux1); + _mav_put_float(buf, 28, aux2); + _mav_put_float(buf, 32, aux3); + _mav_put_float(buf, 36, aux4); + _mav_put_uint8_t(buf, 40, mode); + _mav_put_uint8_t(buf, 41, nav_mode); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif +#else + mavlink_hil_controls_t *packet = (mavlink_hil_controls_t *)msgbuf; + packet->time_usec = time_usec; + packet->roll_ailerons = roll_ailerons; + packet->pitch_elevator = pitch_elevator; + packet->yaw_rudder = yaw_rudder; + packet->throttle = throttle; + packet->aux1 = aux1; + packet->aux2 = aux2; + packet->aux3 = aux3; + packet->aux4 = aux4; + packet->mode = mode; + packet->nav_mode = nav_mode; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIL_CONTROLS UNPACKING + + +/** + * @brief Get field time_usec from hil_controls message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field roll_ailerons from hil_controls message + * + * @return Control output -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field pitch_elevator from hil_controls message + * + * @return Control output -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field yaw_rudder from hil_controls message + * + * @return Control output -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field throttle from hil_controls message + * + * @return Throttle 0 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field aux1 from hil_controls message + * + * @return Aux 1, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field aux2 from hil_controls message + * + * @return Aux 2, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field aux3 from hil_controls message + * + * @return Aux 3, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field aux4 from hil_controls message + * + * @return Aux 4, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field mode from hil_controls message + * + * @return System mode (MAV_MODE) + */ +static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 40); +} + +/** + * @brief Get field nav_mode from hil_controls message + * + * @return Navigation mode (MAV_NAV_MODE) + */ +static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 41); +} + +/** + * @brief Decode a hil_controls message into a struct + * + * @param msg The message to decode + * @param hil_controls C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_controls->time_usec = mavlink_msg_hil_controls_get_time_usec(msg); + hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg); + hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg); + hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg); + hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg); + hil_controls->aux1 = mavlink_msg_hil_controls_get_aux1(msg); + hil_controls->aux2 = mavlink_msg_hil_controls_get_aux2(msg); + hil_controls->aux3 = mavlink_msg_hil_controls_get_aux3(msg); + hil_controls->aux4 = mavlink_msg_hil_controls_get_aux4(msg); + hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg); + hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg); +#else + memcpy(hil_controls, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_gps.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_gps.h new file mode 100644 index 0000000..aef125c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_gps.h @@ -0,0 +1,497 @@ +// MESSAGE HIL_GPS PACKING + +#define MAVLINK_MSG_ID_HIL_GPS 113 + +typedef struct __mavlink_hil_gps_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ + int32_t alt; /*< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)*/ + uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535*/ + uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535*/ + uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: 65535*/ + int16_t vn; /*< GPS velocity in cm/s in NORTH direction in earth-fixed NED frame*/ + int16_t ve; /*< GPS velocity in cm/s in EAST direction in earth-fixed NED frame*/ + int16_t vd; /*< GPS velocity in cm/s in DOWN direction in earth-fixed NED frame*/ + uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535*/ + uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.*/ + uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ +} mavlink_hil_gps_t; + +#define MAVLINK_MSG_ID_HIL_GPS_LEN 36 +#define MAVLINK_MSG_ID_113_LEN 36 + +#define MAVLINK_MSG_ID_HIL_GPS_CRC 124 +#define MAVLINK_MSG_ID_113_CRC 124 + + + +#define MAVLINK_MESSAGE_INFO_HIL_GPS { \ + "HIL_GPS", \ + 13, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \ + { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_gps_t, eph) }, \ + { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_gps_t, epv) }, \ + { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_gps_t, vel) }, \ + { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_hil_gps_t, vn) }, \ + { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \ + { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \ + { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \ + { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \ + } \ +} + + +/** + * @brief Pack a hil_gps message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 + * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 + * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame + * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame + * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_int16_t(buf, 26, vn); + _mav_put_int16_t(buf, 28, ve); + _mav_put_int16_t(buf, 30, vd); + _mav_put_uint16_t(buf, 32, cog); + _mav_put_uint8_t(buf, 34, fix_type); + _mav_put_uint8_t(buf, 35, satellites_visible); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN); +#else + mavlink_hil_gps_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.vn = vn; + packet.ve = ve; + packet.vd = vd; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_GPS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif +} + +/** + * @brief Pack a hil_gps message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 + * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 + * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame + * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame + * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_gps_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,int16_t vn,int16_t ve,int16_t vd,uint16_t cog,uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_int16_t(buf, 26, vn); + _mav_put_int16_t(buf, 28, ve); + _mav_put_int16_t(buf, 30, vd); + _mav_put_uint16_t(buf, 32, cog); + _mav_put_uint8_t(buf, 34, fix_type); + _mav_put_uint8_t(buf, 35, satellites_visible); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN); +#else + mavlink_hil_gps_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.vn = vn; + packet.ve = ve; + packet.vd = vd; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_GPS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif +} + +/** + * @brief Encode a hil_gps struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_gps C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_gps_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps) +{ + return mavlink_msg_hil_gps_pack(system_id, component_id, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible); +} + +/** + * @brief Encode a hil_gps struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param hil_gps C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps) +{ + return mavlink_msg_hil_gps_pack_chan(system_id, component_id, chan, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible); +} + +/** + * @brief Send a hil_gps message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 + * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 + * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame + * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame + * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_gps_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_int16_t(buf, 26, vn); + _mav_put_int16_t(buf, 28, ve); + _mav_put_int16_t(buf, 30, vd); + _mav_put_uint16_t(buf, 32, cog); + _mav_put_uint8_t(buf, 34, fix_type); + _mav_put_uint8_t(buf, 35, satellites_visible); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif +#else + mavlink_hil_gps_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.vn = vn; + packet.ve = ve; + packet.vd = vd; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIL_GPS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_hil_gps_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_int16_t(buf, 26, vn); + _mav_put_int16_t(buf, 28, ve); + _mav_put_int16_t(buf, 30, vd); + _mav_put_uint16_t(buf, 32, cog); + _mav_put_uint8_t(buf, 34, fix_type); + _mav_put_uint8_t(buf, 35, satellites_visible); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif +#else + mavlink_hil_gps_t *packet = (mavlink_hil_gps_t *)msgbuf; + packet->time_usec = time_usec; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->eph = eph; + packet->epv = epv; + packet->vel = vel; + packet->vn = vn; + packet->ve = ve; + packet->vd = vd; + packet->cog = cog; + packet->fix_type = fix_type; + packet->satellites_visible = satellites_visible; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIL_GPS UNPACKING + + +/** + * @brief Get field time_usec from hil_gps message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_gps_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field fix_type from hil_gps message + * + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + */ +static inline uint8_t mavlink_msg_hil_gps_get_fix_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field lat from hil_gps message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field lon from hil_gps message + * + * @return Longitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field alt from hil_gps message + * + * @return Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field eph from hil_gps message + * + * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field epv from hil_gps message + * + * @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field vel from hil_gps message + * + * @return GPS ground speed (m/s * 100). If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field vn from hil_gps message + * + * @return GPS velocity in cm/s in NORTH direction in earth-fixed NED frame + */ +static inline int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 26); +} + +/** + * @brief Get field ve from hil_gps message + * + * @return GPS velocity in cm/s in EAST direction in earth-fixed NED frame + */ +static inline int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 28); +} + +/** + * @brief Get field vd from hil_gps message + * + * @return GPS velocity in cm/s in DOWN direction in earth-fixed NED frame + */ +static inline int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 30); +} + +/** + * @brief Get field cog from hil_gps message + * + * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_hil_gps_get_cog(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 32); +} + +/** + * @brief Get field satellites_visible from hil_gps message + * + * @return Number of satellites visible. If unknown, set to 255 + */ +static inline uint8_t mavlink_msg_hil_gps_get_satellites_visible(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 35); +} + +/** + * @brief Decode a hil_gps message into a struct + * + * @param msg The message to decode + * @param hil_gps C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_gps_decode(const mavlink_message_t* msg, mavlink_hil_gps_t* hil_gps) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_gps->time_usec = mavlink_msg_hil_gps_get_time_usec(msg); + hil_gps->lat = mavlink_msg_hil_gps_get_lat(msg); + hil_gps->lon = mavlink_msg_hil_gps_get_lon(msg); + hil_gps->alt = mavlink_msg_hil_gps_get_alt(msg); + hil_gps->eph = mavlink_msg_hil_gps_get_eph(msg); + hil_gps->epv = mavlink_msg_hil_gps_get_epv(msg); + hil_gps->vel = mavlink_msg_hil_gps_get_vel(msg); + hil_gps->vn = mavlink_msg_hil_gps_get_vn(msg); + hil_gps->ve = mavlink_msg_hil_gps_get_ve(msg); + hil_gps->vd = mavlink_msg_hil_gps_get_vd(msg); + hil_gps->cog = mavlink_msg_hil_gps_get_cog(msg); + hil_gps->fix_type = mavlink_msg_hil_gps_get_fix_type(msg); + hil_gps->satellites_visible = mavlink_msg_hil_gps_get_satellites_visible(msg); +#else + memcpy(hil_gps, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h new file mode 100644 index 0000000..27abb05 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h @@ -0,0 +1,473 @@ +// MESSAGE HIL_OPTICAL_FLOW PACKING + +#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW 114 + +typedef struct __mavlink_hil_optical_flow_t +{ + uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + uint32_t integration_time_us; /*< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/ + float integrated_x; /*< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/ + float integrated_y; /*< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/ + float integrated_xgyro; /*< RH rotation around X axis (rad)*/ + float integrated_ygyro; /*< RH rotation around Y axis (rad)*/ + float integrated_zgyro; /*< RH rotation around Z axis (rad)*/ + uint32_t time_delta_distance_us; /*< Time in microseconds since the distance was sampled.*/ + float distance; /*< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.*/ + int16_t temperature; /*< Temperature * 100 in centi-degrees Celsius*/ + uint8_t sensor_id; /*< Sensor ID*/ + uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/ +} mavlink_hil_optical_flow_t; + +#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 44 +#define MAVLINK_MSG_ID_114_LEN 44 + +#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC 237 +#define MAVLINK_MSG_ID_114_CRC 237 + + + +#define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW { \ + "HIL_OPTICAL_FLOW", \ + 12, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \ + { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \ + { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \ + { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \ + { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \ + { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \ + { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \ + { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \ + { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \ + { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \ + } \ +} + + +/** + * @brief Pack a hil_optical_flow message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param sensor_id Sensor ID + * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro RH rotation around X axis (rad) + * @param integrated_ygyro RH rotation around Y axis (rad) + * @param integrated_zgyro RH rotation around Z axis (rad) + * @param temperature Temperature * 100 in centi-degrees Celsius + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us Time in microseconds since the distance was sampled. + * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#else + mavlink_hil_optical_flow_t packet; + packet.time_usec = time_usec; + packet.integration_time_us = integration_time_us; + packet.integrated_x = integrated_x; + packet.integrated_y = integrated_y; + packet.integrated_xgyro = integrated_xgyro; + packet.integrated_ygyro = integrated_ygyro; + packet.integrated_zgyro = integrated_zgyro; + packet.time_delta_distance_us = time_delta_distance_us; + packet.distance = distance; + packet.temperature = temperature; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif +} + +/** + * @brief Pack a hil_optical_flow message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param sensor_id Sensor ID + * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro RH rotation around X axis (rad) + * @param integrated_ygyro RH rotation around Y axis (rad) + * @param integrated_zgyro RH rotation around Z axis (rad) + * @param temperature Temperature * 100 in centi-degrees Celsius + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us Time in microseconds since the distance was sampled. + * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t sensor_id,uint32_t integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,int16_t temperature,uint8_t quality,uint32_t time_delta_distance_us,float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#else + mavlink_hil_optical_flow_t packet; + packet.time_usec = time_usec; + packet.integration_time_us = integration_time_us; + packet.integrated_x = integrated_x; + packet.integrated_y = integrated_y; + packet.integrated_xgyro = integrated_xgyro; + packet.integrated_ygyro = integrated_ygyro; + packet.integrated_zgyro = integrated_zgyro; + packet.time_delta_distance_us = time_delta_distance_us; + packet.distance = distance; + packet.temperature = temperature; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif +} + +/** + * @brief Encode a hil_optical_flow struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_optical_flow C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow) +{ + return mavlink_msg_hil_optical_flow_pack(system_id, component_id, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance); +} + +/** + * @brief Encode a hil_optical_flow struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param hil_optical_flow C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow) +{ + return mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, chan, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance); +} + +/** + * @brief Send a hil_optical_flow message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param sensor_id Sensor ID + * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro RH rotation around X axis (rad) + * @param integrated_ygyro RH rotation around Y axis (rad) + * @param integrated_zgyro RH rotation around Z axis (rad) + * @param temperature Temperature * 100 in centi-degrees Celsius + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us Time in microseconds since the distance was sampled. + * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif +#else + mavlink_hil_optical_flow_t packet; + packet.time_usec = time_usec; + packet.integration_time_us = integration_time_us; + packet.integrated_x = integrated_x; + packet.integrated_y = integrated_y; + packet.integrated_xgyro = integrated_xgyro; + packet.integrated_ygyro = integrated_ygyro; + packet.integrated_zgyro = integrated_zgyro; + packet.time_delta_distance_us = time_delta_distance_us; + packet.distance = distance; + packet.temperature = temperature; + packet.sensor_id = sensor_id; + packet.quality = quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_hil_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif +#else + mavlink_hil_optical_flow_t *packet = (mavlink_hil_optical_flow_t *)msgbuf; + packet->time_usec = time_usec; + packet->integration_time_us = integration_time_us; + packet->integrated_x = integrated_x; + packet->integrated_y = integrated_y; + packet->integrated_xgyro = integrated_xgyro; + packet->integrated_ygyro = integrated_ygyro; + packet->integrated_zgyro = integrated_zgyro; + packet->time_delta_distance_us = time_delta_distance_us; + packet->distance = distance; + packet->temperature = temperature; + packet->sensor_id = sensor_id; + packet->quality = quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIL_OPTICAL_FLOW UNPACKING + + +/** + * @brief Get field time_usec from hil_optical_flow message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_hil_optical_flow_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field sensor_id from hil_optical_flow message + * + * @return Sensor ID + */ +static inline uint8_t mavlink_msg_hil_optical_flow_get_sensor_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 42); +} + +/** + * @brief Get field integration_time_us from hil_optical_flow message + * + * @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + */ +static inline uint32_t mavlink_msg_hil_optical_flow_get_integration_time_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field integrated_x from hil_optical_flow message + * + * @return Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + */ +static inline float mavlink_msg_hil_optical_flow_get_integrated_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field integrated_y from hil_optical_flow message + * + * @return Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + */ +static inline float mavlink_msg_hil_optical_flow_get_integrated_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field integrated_xgyro from hil_optical_flow message + * + * @return RH rotation around X axis (rad) + */ +static inline float mavlink_msg_hil_optical_flow_get_integrated_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field integrated_ygyro from hil_optical_flow message + * + * @return RH rotation around Y axis (rad) + */ +static inline float mavlink_msg_hil_optical_flow_get_integrated_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field integrated_zgyro from hil_optical_flow message + * + * @return RH rotation around Z axis (rad) + */ +static inline float mavlink_msg_hil_optical_flow_get_integrated_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field temperature from hil_optical_flow message + * + * @return Temperature * 100 in centi-degrees Celsius + */ +static inline int16_t mavlink_msg_hil_optical_flow_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 40); +} + +/** + * @brief Get field quality from hil_optical_flow message + * + * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + */ +static inline uint8_t mavlink_msg_hil_optical_flow_get_quality(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 43); +} + +/** + * @brief Get field time_delta_distance_us from hil_optical_flow message + * + * @return Time in microseconds since the distance was sampled. + */ +static inline uint32_t mavlink_msg_hil_optical_flow_get_time_delta_distance_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 32); +} + +/** + * @brief Get field distance from hil_optical_flow message + * + * @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + */ +static inline float mavlink_msg_hil_optical_flow_get_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Decode a hil_optical_flow message into a struct + * + * @param msg The message to decode + * @param hil_optical_flow C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_optical_flow_decode(const mavlink_message_t* msg, mavlink_hil_optical_flow_t* hil_optical_flow) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_optical_flow->time_usec = mavlink_msg_hil_optical_flow_get_time_usec(msg); + hil_optical_flow->integration_time_us = mavlink_msg_hil_optical_flow_get_integration_time_us(msg); + hil_optical_flow->integrated_x = mavlink_msg_hil_optical_flow_get_integrated_x(msg); + hil_optical_flow->integrated_y = mavlink_msg_hil_optical_flow_get_integrated_y(msg); + hil_optical_flow->integrated_xgyro = mavlink_msg_hil_optical_flow_get_integrated_xgyro(msg); + hil_optical_flow->integrated_ygyro = mavlink_msg_hil_optical_flow_get_integrated_ygyro(msg); + hil_optical_flow->integrated_zgyro = mavlink_msg_hil_optical_flow_get_integrated_zgyro(msg); + hil_optical_flow->time_delta_distance_us = mavlink_msg_hil_optical_flow_get_time_delta_distance_us(msg); + hil_optical_flow->distance = mavlink_msg_hil_optical_flow_get_distance(msg); + hil_optical_flow->temperature = mavlink_msg_hil_optical_flow_get_temperature(msg); + hil_optical_flow->sensor_id = mavlink_msg_hil_optical_flow_get_sensor_id(msg); + hil_optical_flow->quality = mavlink_msg_hil_optical_flow_get_quality(msg); +#else + memcpy(hil_optical_flow, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h new file mode 100644 index 0000000..be30cd4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h @@ -0,0 +1,521 @@ +// MESSAGE HIL_RC_INPUTS_RAW PACKING + +#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW 92 + +typedef struct __mavlink_hil_rc_inputs_raw_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + uint16_t chan1_raw; /*< RC channel 1 value, in microseconds*/ + uint16_t chan2_raw; /*< RC channel 2 value, in microseconds*/ + uint16_t chan3_raw; /*< RC channel 3 value, in microseconds*/ + uint16_t chan4_raw; /*< RC channel 4 value, in microseconds*/ + uint16_t chan5_raw; /*< RC channel 5 value, in microseconds*/ + uint16_t chan6_raw; /*< RC channel 6 value, in microseconds*/ + uint16_t chan7_raw; /*< RC channel 7 value, in microseconds*/ + uint16_t chan8_raw; /*< RC channel 8 value, in microseconds*/ + uint16_t chan9_raw; /*< RC channel 9 value, in microseconds*/ + uint16_t chan10_raw; /*< RC channel 10 value, in microseconds*/ + uint16_t chan11_raw; /*< RC channel 11 value, in microseconds*/ + uint16_t chan12_raw; /*< RC channel 12 value, in microseconds*/ + uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 255: 100%*/ +} mavlink_hil_rc_inputs_raw_t; + +#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33 +#define MAVLINK_MSG_ID_92_LEN 33 + +#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC 54 +#define MAVLINK_MSG_ID_92_CRC 54 + + + +#define MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW { \ + "HIL_RC_INPUTS_RAW", \ + 14, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_rc_inputs_raw_t, time_usec) }, \ + { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_hil_rc_inputs_raw_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_hil_rc_inputs_raw_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_hil_rc_inputs_raw_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_hil_rc_inputs_raw_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_hil_rc_inputs_raw_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_hil_rc_inputs_raw_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_rc_inputs_raw_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_rc_inputs_raw_t, chan8_raw) }, \ + { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_rc_inputs_raw_t, chan9_raw) }, \ + { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_hil_rc_inputs_raw_t, chan10_raw) }, \ + { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_hil_rc_inputs_raw_t, chan11_raw) }, \ + { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_hil_rc_inputs_raw_t, chan12_raw) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_hil_rc_inputs_raw_t, rssi) }, \ + } \ +} + + +/** + * @brief Pack a hil_rc_inputs_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param chan9_raw RC channel 9 value, in microseconds + * @param chan10_raw RC channel 10 value, in microseconds + * @param chan11_raw RC channel 11 value, in microseconds + * @param chan12_raw RC channel 12 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 8, chan1_raw); + _mav_put_uint16_t(buf, 10, chan2_raw); + _mav_put_uint16_t(buf, 12, chan3_raw); + _mav_put_uint16_t(buf, 14, chan4_raw); + _mav_put_uint16_t(buf, 16, chan5_raw); + _mav_put_uint16_t(buf, 18, chan6_raw); + _mav_put_uint16_t(buf, 20, chan7_raw); + _mav_put_uint16_t(buf, 22, chan8_raw); + _mav_put_uint16_t(buf, 24, chan9_raw); + _mav_put_uint16_t(buf, 26, chan10_raw); + _mav_put_uint16_t(buf, 28, chan11_raw); + _mav_put_uint16_t(buf, 30, chan12_raw); + _mav_put_uint8_t(buf, 32, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#else + mavlink_hil_rc_inputs_raw_t packet; + packet.time_usec = time_usec; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif +} + +/** + * @brief Pack a hil_rc_inputs_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param chan9_raw RC channel 9 value, in microseconds + * @param chan10_raw RC channel 10 value, in microseconds + * @param chan11_raw RC channel 11 value, in microseconds + * @param chan12_raw RC channel 12 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 8, chan1_raw); + _mav_put_uint16_t(buf, 10, chan2_raw); + _mav_put_uint16_t(buf, 12, chan3_raw); + _mav_put_uint16_t(buf, 14, chan4_raw); + _mav_put_uint16_t(buf, 16, chan5_raw); + _mav_put_uint16_t(buf, 18, chan6_raw); + _mav_put_uint16_t(buf, 20, chan7_raw); + _mav_put_uint16_t(buf, 22, chan8_raw); + _mav_put_uint16_t(buf, 24, chan9_raw); + _mav_put_uint16_t(buf, 26, chan10_raw); + _mav_put_uint16_t(buf, 28, chan11_raw); + _mav_put_uint16_t(buf, 30, chan12_raw); + _mav_put_uint8_t(buf, 32, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#else + mavlink_hil_rc_inputs_raw_t packet; + packet.time_usec = time_usec; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif +} + +/** + * @brief Encode a hil_rc_inputs_raw struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_rc_inputs_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) +{ + return mavlink_msg_hil_rc_inputs_raw_pack(system_id, component_id, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); +} + +/** + * @brief Encode a hil_rc_inputs_raw struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param hil_rc_inputs_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) +{ + return mavlink_msg_hil_rc_inputs_raw_pack_chan(system_id, component_id, chan, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); +} + +/** + * @brief Send a hil_rc_inputs_raw message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param chan9_raw RC channel 9 value, in microseconds + * @param chan10_raw RC channel 10 value, in microseconds + * @param chan11_raw RC channel 11 value, in microseconds + * @param chan12_raw RC channel 12 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_rc_inputs_raw_send(mavlink_channel_t chan, uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 8, chan1_raw); + _mav_put_uint16_t(buf, 10, chan2_raw); + _mav_put_uint16_t(buf, 12, chan3_raw); + _mav_put_uint16_t(buf, 14, chan4_raw); + _mav_put_uint16_t(buf, 16, chan5_raw); + _mav_put_uint16_t(buf, 18, chan6_raw); + _mav_put_uint16_t(buf, 20, chan7_raw); + _mav_put_uint16_t(buf, 22, chan8_raw); + _mav_put_uint16_t(buf, 24, chan9_raw); + _mav_put_uint16_t(buf, 26, chan10_raw); + _mav_put_uint16_t(buf, 28, chan11_raw); + _mav_put_uint16_t(buf, 30, chan12_raw); + _mav_put_uint8_t(buf, 32, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif +#else + mavlink_hil_rc_inputs_raw_t packet; + packet.time_usec = time_usec; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_hil_rc_inputs_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 8, chan1_raw); + _mav_put_uint16_t(buf, 10, chan2_raw); + _mav_put_uint16_t(buf, 12, chan3_raw); + _mav_put_uint16_t(buf, 14, chan4_raw); + _mav_put_uint16_t(buf, 16, chan5_raw); + _mav_put_uint16_t(buf, 18, chan6_raw); + _mav_put_uint16_t(buf, 20, chan7_raw); + _mav_put_uint16_t(buf, 22, chan8_raw); + _mav_put_uint16_t(buf, 24, chan9_raw); + _mav_put_uint16_t(buf, 26, chan10_raw); + _mav_put_uint16_t(buf, 28, chan11_raw); + _mav_put_uint16_t(buf, 30, chan12_raw); + _mav_put_uint8_t(buf, 32, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif +#else + mavlink_hil_rc_inputs_raw_t *packet = (mavlink_hil_rc_inputs_raw_t *)msgbuf; + packet->time_usec = time_usec; + packet->chan1_raw = chan1_raw; + packet->chan2_raw = chan2_raw; + packet->chan3_raw = chan3_raw; + packet->chan4_raw = chan4_raw; + packet->chan5_raw = chan5_raw; + packet->chan6_raw = chan6_raw; + packet->chan7_raw = chan7_raw; + packet->chan8_raw = chan8_raw; + packet->chan9_raw = chan9_raw; + packet->chan10_raw = chan10_raw; + packet->chan11_raw = chan11_raw; + packet->chan12_raw = chan12_raw; + packet->rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIL_RC_INPUTS_RAW UNPACKING + + +/** + * @brief Get field time_usec from hil_rc_inputs_raw message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_rc_inputs_raw_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field chan1_raw from hil_rc_inputs_raw message + * + * @return RC channel 1 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field chan2_raw from hil_rc_inputs_raw message + * + * @return RC channel 2 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field chan3_raw from hil_rc_inputs_raw message + * + * @return RC channel 3 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field chan4_raw from hil_rc_inputs_raw message + * + * @return RC channel 4 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field chan5_raw from hil_rc_inputs_raw message + * + * @return RC channel 5 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field chan6_raw from hil_rc_inputs_raw message + * + * @return RC channel 6 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field chan7_raw from hil_rc_inputs_raw message + * + * @return RC channel 7 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field chan8_raw from hil_rc_inputs_raw message + * + * @return RC channel 8 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field chan9_raw from hil_rc_inputs_raw message + * + * @return RC channel 9 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field chan10_raw from hil_rc_inputs_raw message + * + * @return RC channel 10 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field chan11_raw from hil_rc_inputs_raw message + * + * @return RC channel 11 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field chan12_raw from hil_rc_inputs_raw message + * + * @return RC channel 12 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 30); +} + +/** + * @brief Get field rssi from hil_rc_inputs_raw message + * + * @return Receive signal strength indicator, 0: 0%, 255: 100% + */ +static inline uint8_t mavlink_msg_hil_rc_inputs_raw_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Decode a hil_rc_inputs_raw message into a struct + * + * @param msg The message to decode + * @param hil_rc_inputs_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_rc_inputs_raw_decode(const mavlink_message_t* msg, mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_rc_inputs_raw->time_usec = mavlink_msg_hil_rc_inputs_raw_get_time_usec(msg); + hil_rc_inputs_raw->chan1_raw = mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(msg); + hil_rc_inputs_raw->chan2_raw = mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(msg); + hil_rc_inputs_raw->chan3_raw = mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(msg); + hil_rc_inputs_raw->chan4_raw = mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(msg); + hil_rc_inputs_raw->chan5_raw = mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(msg); + hil_rc_inputs_raw->chan6_raw = mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(msg); + hil_rc_inputs_raw->chan7_raw = mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(msg); + hil_rc_inputs_raw->chan8_raw = mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(msg); + hil_rc_inputs_raw->chan9_raw = mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(msg); + hil_rc_inputs_raw->chan10_raw = mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(msg); + hil_rc_inputs_raw->chan11_raw = mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(msg); + hil_rc_inputs_raw->chan12_raw = mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(msg); + hil_rc_inputs_raw->rssi = mavlink_msg_hil_rc_inputs_raw_get_rssi(msg); +#else + memcpy(hil_rc_inputs_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_sensor.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_sensor.h new file mode 100644 index 0000000..baa3b27 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_sensor.h @@ -0,0 +1,545 @@ +// MESSAGE HIL_SENSOR PACKING + +#define MAVLINK_MSG_ID_HIL_SENSOR 107 + +typedef struct __mavlink_hil_sensor_t +{ + uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + float xacc; /*< X acceleration (m/s^2)*/ + float yacc; /*< Y acceleration (m/s^2)*/ + float zacc; /*< Z acceleration (m/s^2)*/ + float xgyro; /*< Angular speed around X axis in body frame (rad / sec)*/ + float ygyro; /*< Angular speed around Y axis in body frame (rad / sec)*/ + float zgyro; /*< Angular speed around Z axis in body frame (rad / sec)*/ + float xmag; /*< X Magnetic field (Gauss)*/ + float ymag; /*< Y Magnetic field (Gauss)*/ + float zmag; /*< Z Magnetic field (Gauss)*/ + float abs_pressure; /*< Absolute pressure in millibar*/ + float diff_pressure; /*< Differential pressure (airspeed) in millibar*/ + float pressure_alt; /*< Altitude calculated from pressure*/ + float temperature; /*< Temperature in degrees celsius*/ + uint32_t fields_updated; /*< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.*/ +} mavlink_hil_sensor_t; + +#define MAVLINK_MSG_ID_HIL_SENSOR_LEN 64 +#define MAVLINK_MSG_ID_107_LEN 64 + +#define MAVLINK_MSG_ID_HIL_SENSOR_CRC 108 +#define MAVLINK_MSG_ID_107_CRC 108 + + + +#define MAVLINK_MESSAGE_INFO_HIL_SENSOR { \ + "HIL_SENSOR", \ + 15, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_sensor_t, time_usec) }, \ + { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_sensor_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_sensor_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_sensor_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_sensor_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_sensor_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_sensor_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_sensor_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_sensor_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_hil_sensor_t, zmag) }, \ + { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_hil_sensor_t, abs_pressure) }, \ + { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_hil_sensor_t, diff_pressure) }, \ + { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_hil_sensor_t, pressure_alt) }, \ + { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_hil_sensor_t, temperature) }, \ + { "fields_updated", NULL, MAVLINK_TYPE_UINT32_T, 0, 60, offsetof(mavlink_hil_sensor_t, fields_updated) }, \ + } \ +} + + +/** + * @brief Pack a hil_sensor message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param xacc X acceleration (m/s^2) + * @param yacc Y acceleration (m/s^2) + * @param zacc Z acceleration (m/s^2) + * @param xgyro Angular speed around X axis in body frame (rad / sec) + * @param ygyro Angular speed around Y axis in body frame (rad / sec) + * @param zgyro Angular speed around Z axis in body frame (rad / sec) + * @param xmag X Magnetic field (Gauss) + * @param ymag Y Magnetic field (Gauss) + * @param zmag Z Magnetic field (Gauss) + * @param abs_pressure Absolute pressure in millibar + * @param diff_pressure Differential pressure (airspeed) in millibar + * @param pressure_alt Altitude calculated from pressure + * @param temperature Temperature in degrees celsius + * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint32_t(buf, 60, fields_updated); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#else + mavlink_hil_sensor_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + packet.abs_pressure = abs_pressure; + packet.diff_pressure = diff_pressure; + packet.pressure_alt = pressure_alt; + packet.temperature = temperature; + packet.fields_updated = fields_updated; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_SENSOR; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +} + +/** + * @brief Pack a hil_sensor message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param xacc X acceleration (m/s^2) + * @param yacc Y acceleration (m/s^2) + * @param zacc Z acceleration (m/s^2) + * @param xgyro Angular speed around X axis in body frame (rad / sec) + * @param ygyro Angular speed around Y axis in body frame (rad / sec) + * @param zgyro Angular speed around Z axis in body frame (rad / sec) + * @param xmag X Magnetic field (Gauss) + * @param ymag Y Magnetic field (Gauss) + * @param zmag Z Magnetic field (Gauss) + * @param abs_pressure Absolute pressure in millibar + * @param diff_pressure Differential pressure (airspeed) in millibar + * @param pressure_alt Altitude calculated from pressure + * @param temperature Temperature in degrees celsius + * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,uint32_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint32_t(buf, 60, fields_updated); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#else + mavlink_hil_sensor_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + packet.abs_pressure = abs_pressure; + packet.diff_pressure = diff_pressure; + packet.pressure_alt = pressure_alt; + packet.temperature = temperature; + packet.fields_updated = fields_updated; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_SENSOR; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +} + +/** + * @brief Encode a hil_sensor struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_sensor C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_sensor_t* hil_sensor) +{ + return mavlink_msg_hil_sensor_pack(system_id, component_id, msg, hil_sensor->time_usec, hil_sensor->xacc, hil_sensor->yacc, hil_sensor->zacc, hil_sensor->xgyro, hil_sensor->ygyro, hil_sensor->zgyro, hil_sensor->xmag, hil_sensor->ymag, hil_sensor->zmag, hil_sensor->abs_pressure, hil_sensor->diff_pressure, hil_sensor->pressure_alt, hil_sensor->temperature, hil_sensor->fields_updated); +} + +/** + * @brief Encode a hil_sensor struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param hil_sensor C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_sensor_t* hil_sensor) +{ + return mavlink_msg_hil_sensor_pack_chan(system_id, component_id, chan, msg, hil_sensor->time_usec, hil_sensor->xacc, hil_sensor->yacc, hil_sensor->zacc, hil_sensor->xgyro, hil_sensor->ygyro, hil_sensor->zgyro, hil_sensor->xmag, hil_sensor->ymag, hil_sensor->zmag, hil_sensor->abs_pressure, hil_sensor->diff_pressure, hil_sensor->pressure_alt, hil_sensor->temperature, hil_sensor->fields_updated); +} + +/** + * @brief Send a hil_sensor message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param xacc X acceleration (m/s^2) + * @param yacc Y acceleration (m/s^2) + * @param zacc Z acceleration (m/s^2) + * @param xgyro Angular speed around X axis in body frame (rad / sec) + * @param ygyro Angular speed around Y axis in body frame (rad / sec) + * @param zgyro Angular speed around Z axis in body frame (rad / sec) + * @param xmag X Magnetic field (Gauss) + * @param ymag Y Magnetic field (Gauss) + * @param zmag Z Magnetic field (Gauss) + * @param abs_pressure Absolute pressure in millibar + * @param diff_pressure Differential pressure (airspeed) in millibar + * @param pressure_alt Altitude calculated from pressure + * @param temperature Temperature in degrees celsius + * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_sensor_send(mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint32_t(buf, 60, fields_updated); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +#else + mavlink_hil_sensor_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + packet.abs_pressure = abs_pressure; + packet.diff_pressure = diff_pressure; + packet.pressure_alt = pressure_alt; + packet.temperature = temperature; + packet.fields_updated = fields_updated; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIL_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_hil_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint32_t(buf, 60, fields_updated); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +#else + mavlink_hil_sensor_t *packet = (mavlink_hil_sensor_t *)msgbuf; + packet->time_usec = time_usec; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->xmag = xmag; + packet->ymag = ymag; + packet->zmag = zmag; + packet->abs_pressure = abs_pressure; + packet->diff_pressure = diff_pressure; + packet->pressure_alt = pressure_alt; + packet->temperature = temperature; + packet->fields_updated = fields_updated; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIL_SENSOR UNPACKING + + +/** + * @brief Get field time_usec from hil_sensor message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_hil_sensor_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field xacc from hil_sensor message + * + * @return X acceleration (m/s^2) + */ +static inline float mavlink_msg_hil_sensor_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yacc from hil_sensor message + * + * @return Y acceleration (m/s^2) + */ +static inline float mavlink_msg_hil_sensor_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field zacc from hil_sensor message + * + * @return Z acceleration (m/s^2) + */ +static inline float mavlink_msg_hil_sensor_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field xgyro from hil_sensor message + * + * @return Angular speed around X axis in body frame (rad / sec) + */ +static inline float mavlink_msg_hil_sensor_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field ygyro from hil_sensor message + * + * @return Angular speed around Y axis in body frame (rad / sec) + */ +static inline float mavlink_msg_hil_sensor_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field zgyro from hil_sensor message + * + * @return Angular speed around Z axis in body frame (rad / sec) + */ +static inline float mavlink_msg_hil_sensor_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field xmag from hil_sensor message + * + * @return X Magnetic field (Gauss) + */ +static inline float mavlink_msg_hil_sensor_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field ymag from hil_sensor message + * + * @return Y Magnetic field (Gauss) + */ +static inline float mavlink_msg_hil_sensor_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field zmag from hil_sensor message + * + * @return Z Magnetic field (Gauss) + */ +static inline float mavlink_msg_hil_sensor_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field abs_pressure from hil_sensor message + * + * @return Absolute pressure in millibar + */ +static inline float mavlink_msg_hil_sensor_get_abs_pressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field diff_pressure from hil_sensor message + * + * @return Differential pressure (airspeed) in millibar + */ +static inline float mavlink_msg_hil_sensor_get_diff_pressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 48); +} + +/** + * @brief Get field pressure_alt from hil_sensor message + * + * @return Altitude calculated from pressure + */ +static inline float mavlink_msg_hil_sensor_get_pressure_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 52); +} + +/** + * @brief Get field temperature from hil_sensor message + * + * @return Temperature in degrees celsius + */ +static inline float mavlink_msg_hil_sensor_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 56); +} + +/** + * @brief Get field fields_updated from hil_sensor message + * + * @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + */ +static inline uint32_t mavlink_msg_hil_sensor_get_fields_updated(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 60); +} + +/** + * @brief Decode a hil_sensor message into a struct + * + * @param msg The message to decode + * @param hil_sensor C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_sensor_decode(const mavlink_message_t* msg, mavlink_hil_sensor_t* hil_sensor) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_sensor->time_usec = mavlink_msg_hil_sensor_get_time_usec(msg); + hil_sensor->xacc = mavlink_msg_hil_sensor_get_xacc(msg); + hil_sensor->yacc = mavlink_msg_hil_sensor_get_yacc(msg); + hil_sensor->zacc = mavlink_msg_hil_sensor_get_zacc(msg); + hil_sensor->xgyro = mavlink_msg_hil_sensor_get_xgyro(msg); + hil_sensor->ygyro = mavlink_msg_hil_sensor_get_ygyro(msg); + hil_sensor->zgyro = mavlink_msg_hil_sensor_get_zgyro(msg); + hil_sensor->xmag = mavlink_msg_hil_sensor_get_xmag(msg); + hil_sensor->ymag = mavlink_msg_hil_sensor_get_ymag(msg); + hil_sensor->zmag = mavlink_msg_hil_sensor_get_zmag(msg); + hil_sensor->abs_pressure = mavlink_msg_hil_sensor_get_abs_pressure(msg); + hil_sensor->diff_pressure = mavlink_msg_hil_sensor_get_diff_pressure(msg); + hil_sensor->pressure_alt = mavlink_msg_hil_sensor_get_pressure_alt(msg); + hil_sensor->temperature = mavlink_msg_hil_sensor_get_temperature(msg); + hil_sensor->fields_updated = mavlink_msg_hil_sensor_get_fields_updated(msg); +#else + memcpy(hil_sensor, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_state.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_state.h new file mode 100644 index 0000000..e58141e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_state.h @@ -0,0 +1,569 @@ +// MESSAGE HIL_STATE PACKING + +#define MAVLINK_MSG_ID_HIL_STATE 90 + +typedef struct __mavlink_hil_state_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + float roll; /*< Roll angle (rad)*/ + float pitch; /*< Pitch angle (rad)*/ + float yaw; /*< Yaw angle (rad)*/ + float rollspeed; /*< Body frame roll / phi angular speed (rad/s)*/ + float pitchspeed; /*< Body frame pitch / theta angular speed (rad/s)*/ + float yawspeed; /*< Body frame yaw / psi angular speed (rad/s)*/ + int32_t lat; /*< Latitude, expressed as * 1E7*/ + int32_t lon; /*< Longitude, expressed as * 1E7*/ + int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters)*/ + int16_t vx; /*< Ground X Speed (Latitude), expressed as m/s * 100*/ + int16_t vy; /*< Ground Y Speed (Longitude), expressed as m/s * 100*/ + int16_t vz; /*< Ground Z Speed (Altitude), expressed as m/s * 100*/ + int16_t xacc; /*< X acceleration (mg)*/ + int16_t yacc; /*< Y acceleration (mg)*/ + int16_t zacc; /*< Z acceleration (mg)*/ +} mavlink_hil_state_t; + +#define MAVLINK_MSG_ID_HIL_STATE_LEN 56 +#define MAVLINK_MSG_ID_90_LEN 56 + +#define MAVLINK_MSG_ID_HIL_STATE_CRC 183 +#define MAVLINK_MSG_ID_90_CRC 183 + + + +#define MAVLINK_MESSAGE_INFO_HIL_STATE { \ + "HIL_STATE", \ + 16, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \ + { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \ + } \ +} + + +/** + * @brief Pack a hil_state message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Body frame roll / phi angular speed (rad/s) + * @param pitchspeed Body frame pitch / theta angular speed (rad/s) + * @param yawspeed Body frame yaw / psi angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_STATE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_int32_t(buf, 32, lat); + _mav_put_int32_t(buf, 36, lon); + _mav_put_int32_t(buf, 40, alt); + _mav_put_int16_t(buf, 44, vx); + _mav_put_int16_t(buf, 46, vy); + _mav_put_int16_t(buf, 48, vz); + _mav_put_int16_t(buf, 50, xacc); + _mav_put_int16_t(buf, 52, yacc); + _mav_put_int16_t(buf, 54, zacc); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN); +#else + mavlink_hil_state_t packet; + packet.time_usec = time_usec; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif +} + +/** + * @brief Pack a hil_state message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Body frame roll / phi angular speed (rad/s) + * @param pitchspeed Body frame pitch / theta angular speed (rad/s) + * @param yawspeed Body frame yaw / psi angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,int16_t xacc,int16_t yacc,int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_STATE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_int32_t(buf, 32, lat); + _mav_put_int32_t(buf, 36, lon); + _mav_put_int32_t(buf, 40, alt); + _mav_put_int16_t(buf, 44, vx); + _mav_put_int16_t(buf, 46, vy); + _mav_put_int16_t(buf, 48, vz); + _mav_put_int16_t(buf, 50, xacc); + _mav_put_int16_t(buf, 52, yacc); + _mav_put_int16_t(buf, 54, zacc); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN); +#else + mavlink_hil_state_t packet; + packet.time_usec = time_usec; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif +} + +/** + * @brief Encode a hil_state struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state) +{ + return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); +} + +/** + * @brief Encode a hil_state struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param hil_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state) +{ + return mavlink_msg_hil_state_pack_chan(system_id, component_id, chan, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); +} + +/** + * @brief Send a hil_state message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Body frame roll / phi angular speed (rad/s) + * @param pitchspeed Body frame pitch / theta angular speed (rad/s) + * @param yawspeed Body frame yaw / psi angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_STATE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_int32_t(buf, 32, lat); + _mav_put_int32_t(buf, 36, lon); + _mav_put_int32_t(buf, 40, alt); + _mav_put_int16_t(buf, 44, vx); + _mav_put_int16_t(buf, 46, vy); + _mav_put_int16_t(buf, 48, vz); + _mav_put_int16_t(buf, 50, xacc); + _mav_put_int16_t(buf, 52, yacc); + _mav_put_int16_t(buf, 54, zacc); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif +#else + mavlink_hil_state_t packet; + packet.time_usec = time_usec; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIL_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_hil_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_int32_t(buf, 32, lat); + _mav_put_int32_t(buf, 36, lon); + _mav_put_int32_t(buf, 40, alt); + _mav_put_int16_t(buf, 44, vx); + _mav_put_int16_t(buf, 46, vy); + _mav_put_int16_t(buf, 48, vz); + _mav_put_int16_t(buf, 50, xacc); + _mav_put_int16_t(buf, 52, yacc); + _mav_put_int16_t(buf, 54, zacc); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif +#else + mavlink_hil_state_t *packet = (mavlink_hil_state_t *)msgbuf; + packet->time_usec = time_usec; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + packet->rollspeed = rollspeed; + packet->pitchspeed = pitchspeed; + packet->yawspeed = yawspeed; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIL_STATE UNPACKING + + +/** + * @brief Get field time_usec from hil_state message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field roll from hil_state message + * + * @return Roll angle (rad) + */ +static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field pitch from hil_state message + * + * @return Pitch angle (rad) + */ +static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field yaw from hil_state message + * + * @return Yaw angle (rad) + */ +static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field rollspeed from hil_state message + * + * @return Body frame roll / phi angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitchspeed from hil_state message + * + * @return Body frame pitch / theta angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yawspeed from hil_state message + * + * @return Body frame yaw / psi angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field lat from hil_state message + * + * @return Latitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 32); +} + +/** + * @brief Get field lon from hil_state message + * + * @return Longitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 36); +} + +/** + * @brief Get field alt from hil_state message + * + * @return Altitude in meters, expressed as * 1000 (millimeters) + */ +static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 40); +} + +/** + * @brief Get field vx from hil_state message + * + * @return Ground X Speed (Latitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 44); +} + +/** + * @brief Get field vy from hil_state message + * + * @return Ground Y Speed (Longitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 46); +} + +/** + * @brief Get field vz from hil_state message + * + * @return Ground Z Speed (Altitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 48); +} + +/** + * @brief Get field xacc from hil_state message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 50); +} + +/** + * @brief Get field yacc from hil_state message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 52); +} + +/** + * @brief Get field zacc from hil_state message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 54); +} + +/** + * @brief Decode a hil_state message into a struct + * + * @param msg The message to decode + * @param hil_state C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_state->time_usec = mavlink_msg_hil_state_get_time_usec(msg); + hil_state->roll = mavlink_msg_hil_state_get_roll(msg); + hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg); + hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg); + hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg); + hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg); + hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg); + hil_state->lat = mavlink_msg_hil_state_get_lat(msg); + hil_state->lon = mavlink_msg_hil_state_get_lon(msg); + hil_state->alt = mavlink_msg_hil_state_get_alt(msg); + hil_state->vx = mavlink_msg_hil_state_get_vx(msg); + hil_state->vy = mavlink_msg_hil_state_get_vy(msg); + hil_state->vz = mavlink_msg_hil_state_get_vz(msg); + hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg); + hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg); + hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg); +#else + memcpy(hil_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h new file mode 100644 index 0000000..9663813 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h @@ -0,0 +1,561 @@ +// MESSAGE HIL_STATE_QUATERNION PACKING + +#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION 115 + +typedef struct __mavlink_hil_state_quaternion_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + float attitude_quaternion[4]; /*< Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)*/ + float rollspeed; /*< Body frame roll / phi angular speed (rad/s)*/ + float pitchspeed; /*< Body frame pitch / theta angular speed (rad/s)*/ + float yawspeed; /*< Body frame yaw / psi angular speed (rad/s)*/ + int32_t lat; /*< Latitude, expressed as * 1E7*/ + int32_t lon; /*< Longitude, expressed as * 1E7*/ + int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters)*/ + int16_t vx; /*< Ground X Speed (Latitude), expressed as m/s * 100*/ + int16_t vy; /*< Ground Y Speed (Longitude), expressed as m/s * 100*/ + int16_t vz; /*< Ground Z Speed (Altitude), expressed as m/s * 100*/ + uint16_t ind_airspeed; /*< Indicated airspeed, expressed as m/s * 100*/ + uint16_t true_airspeed; /*< True airspeed, expressed as m/s * 100*/ + int16_t xacc; /*< X acceleration (mg)*/ + int16_t yacc; /*< Y acceleration (mg)*/ + int16_t zacc; /*< Z acceleration (mg)*/ +} mavlink_hil_state_quaternion_t; + +#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN 64 +#define MAVLINK_MSG_ID_115_LEN 64 + +#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC 4 +#define MAVLINK_MSG_ID_115_CRC 4 + +#define MAVLINK_MSG_HIL_STATE_QUATERNION_FIELD_ATTITUDE_QUATERNION_LEN 4 + +#define MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION { \ + "HIL_STATE_QUATERNION", \ + 16, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_quaternion_t, time_usec) }, \ + { "attitude_quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_hil_state_quaternion_t, attitude_quaternion) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_quaternion_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_quaternion_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_state_quaternion_t, yawspeed) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_quaternion_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_quaternion_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_hil_state_quaternion_t, alt) }, \ + { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_quaternion_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_quaternion_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_quaternion_t, vz) }, \ + { "ind_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 54, offsetof(mavlink_hil_state_quaternion_t, ind_airspeed) }, \ + { "true_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_hil_state_quaternion_t, true_airspeed) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_hil_state_quaternion_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_hil_state_quaternion_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 62, offsetof(mavlink_hil_state_quaternion_t, zacc) }, \ + } \ +} + + +/** + * @brief Pack a hil_state_quaternion message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + * @param rollspeed Body frame roll / phi angular speed (rad/s) + * @param pitchspeed Body frame pitch / theta angular speed (rad/s) + * @param yawspeed Body frame yaw / psi angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param ind_airspeed Indicated airspeed, expressed as m/s * 100 + * @param true_airspeed True airspeed, expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_state_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, rollspeed); + _mav_put_float(buf, 28, pitchspeed); + _mav_put_float(buf, 32, yawspeed); + _mav_put_int32_t(buf, 36, lat); + _mav_put_int32_t(buf, 40, lon); + _mav_put_int32_t(buf, 44, alt); + _mav_put_int16_t(buf, 48, vx); + _mav_put_int16_t(buf, 50, vy); + _mav_put_int16_t(buf, 52, vz); + _mav_put_uint16_t(buf, 54, ind_airspeed); + _mav_put_uint16_t(buf, 56, true_airspeed); + _mav_put_int16_t(buf, 58, xacc); + _mav_put_int16_t(buf, 60, yacc); + _mav_put_int16_t(buf, 62, zacc); + _mav_put_float_array(buf, 8, attitude_quaternion, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#else + mavlink_hil_state_quaternion_t packet; + packet.time_usec = time_usec; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ind_airspeed = ind_airspeed; + packet.true_airspeed = true_airspeed; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif +} + +/** + * @brief Pack a hil_state_quaternion message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + * @param rollspeed Body frame roll / phi angular speed (rad/s) + * @param pitchspeed Body frame pitch / theta angular speed (rad/s) + * @param yawspeed Body frame yaw / psi angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param ind_airspeed Indicated airspeed, expressed as m/s * 100 + * @param true_airspeed True airspeed, expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_state_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,const float *attitude_quaternion,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,uint16_t ind_airspeed,uint16_t true_airspeed,int16_t xacc,int16_t yacc,int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, rollspeed); + _mav_put_float(buf, 28, pitchspeed); + _mav_put_float(buf, 32, yawspeed); + _mav_put_int32_t(buf, 36, lat); + _mav_put_int32_t(buf, 40, lon); + _mav_put_int32_t(buf, 44, alt); + _mav_put_int16_t(buf, 48, vx); + _mav_put_int16_t(buf, 50, vy); + _mav_put_int16_t(buf, 52, vz); + _mav_put_uint16_t(buf, 54, ind_airspeed); + _mav_put_uint16_t(buf, 56, true_airspeed); + _mav_put_int16_t(buf, 58, xacc); + _mav_put_int16_t(buf, 60, yacc); + _mav_put_int16_t(buf, 62, zacc); + _mav_put_float_array(buf, 8, attitude_quaternion, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#else + mavlink_hil_state_quaternion_t packet; + packet.time_usec = time_usec; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ind_airspeed = ind_airspeed; + packet.true_airspeed = true_airspeed; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif +} + +/** + * @brief Encode a hil_state_quaternion struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_state_quaternion C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_state_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion) +{ + return mavlink_msg_hil_state_quaternion_pack(system_id, component_id, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc); +} + +/** + * @brief Encode a hil_state_quaternion struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param hil_state_quaternion C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_state_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion) +{ + return mavlink_msg_hil_state_quaternion_pack_chan(system_id, component_id, chan, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc); +} + +/** + * @brief Send a hil_state_quaternion message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + * @param rollspeed Body frame roll / phi angular speed (rad/s) + * @param pitchspeed Body frame pitch / theta angular speed (rad/s) + * @param yawspeed Body frame yaw / psi angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param ind_airspeed Indicated airspeed, expressed as m/s * 100 + * @param true_airspeed True airspeed, expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_state_quaternion_send(mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, rollspeed); + _mav_put_float(buf, 28, pitchspeed); + _mav_put_float(buf, 32, yawspeed); + _mav_put_int32_t(buf, 36, lat); + _mav_put_int32_t(buf, 40, lon); + _mav_put_int32_t(buf, 44, alt); + _mav_put_int16_t(buf, 48, vx); + _mav_put_int16_t(buf, 50, vy); + _mav_put_int16_t(buf, 52, vz); + _mav_put_uint16_t(buf, 54, ind_airspeed); + _mav_put_uint16_t(buf, 56, true_airspeed); + _mav_put_int16_t(buf, 58, xacc); + _mav_put_int16_t(buf, 60, yacc); + _mav_put_int16_t(buf, 62, zacc); + _mav_put_float_array(buf, 8, attitude_quaternion, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif +#else + mavlink_hil_state_quaternion_t packet; + packet.time_usec = time_usec; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ind_airspeed = ind_airspeed; + packet.true_airspeed = true_airspeed; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_hil_state_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, rollspeed); + _mav_put_float(buf, 28, pitchspeed); + _mav_put_float(buf, 32, yawspeed); + _mav_put_int32_t(buf, 36, lat); + _mav_put_int32_t(buf, 40, lon); + _mav_put_int32_t(buf, 44, alt); + _mav_put_int16_t(buf, 48, vx); + _mav_put_int16_t(buf, 50, vy); + _mav_put_int16_t(buf, 52, vz); + _mav_put_uint16_t(buf, 54, ind_airspeed); + _mav_put_uint16_t(buf, 56, true_airspeed); + _mav_put_int16_t(buf, 58, xacc); + _mav_put_int16_t(buf, 60, yacc); + _mav_put_int16_t(buf, 62, zacc); + _mav_put_float_array(buf, 8, attitude_quaternion, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif +#else + mavlink_hil_state_quaternion_t *packet = (mavlink_hil_state_quaternion_t *)msgbuf; + packet->time_usec = time_usec; + packet->rollspeed = rollspeed; + packet->pitchspeed = pitchspeed; + packet->yawspeed = yawspeed; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->ind_airspeed = ind_airspeed; + packet->true_airspeed = true_airspeed; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + mav_array_memcpy(packet->attitude_quaternion, attitude_quaternion, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIL_STATE_QUATERNION UNPACKING + + +/** + * @brief Get field time_usec from hil_state_quaternion message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_state_quaternion_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field attitude_quaternion from hil_state_quaternion message + * + * @return Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + */ +static inline uint16_t mavlink_msg_hil_state_quaternion_get_attitude_quaternion(const mavlink_message_t* msg, float *attitude_quaternion) +{ + return _MAV_RETURN_float_array(msg, attitude_quaternion, 4, 8); +} + +/** + * @brief Get field rollspeed from hil_state_quaternion message + * + * @return Body frame roll / phi angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_quaternion_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field pitchspeed from hil_state_quaternion message + * + * @return Body frame pitch / theta angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_quaternion_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field yawspeed from hil_state_quaternion message + * + * @return Body frame yaw / psi angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_quaternion_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field lat from hil_state_quaternion message + * + * @return Latitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_hil_state_quaternion_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 36); +} + +/** + * @brief Get field lon from hil_state_quaternion message + * + * @return Longitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_hil_state_quaternion_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 40); +} + +/** + * @brief Get field alt from hil_state_quaternion message + * + * @return Altitude in meters, expressed as * 1000 (millimeters) + */ +static inline int32_t mavlink_msg_hil_state_quaternion_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 44); +} + +/** + * @brief Get field vx from hil_state_quaternion message + * + * @return Ground X Speed (Latitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_quaternion_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 48); +} + +/** + * @brief Get field vy from hil_state_quaternion message + * + * @return Ground Y Speed (Longitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_quaternion_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 50); +} + +/** + * @brief Get field vz from hil_state_quaternion message + * + * @return Ground Z Speed (Altitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_quaternion_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 52); +} + +/** + * @brief Get field ind_airspeed from hil_state_quaternion message + * + * @return Indicated airspeed, expressed as m/s * 100 + */ +static inline uint16_t mavlink_msg_hil_state_quaternion_get_ind_airspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 54); +} + +/** + * @brief Get field true_airspeed from hil_state_quaternion message + * + * @return True airspeed, expressed as m/s * 100 + */ +static inline uint16_t mavlink_msg_hil_state_quaternion_get_true_airspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 56); +} + +/** + * @brief Get field xacc from hil_state_quaternion message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_quaternion_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 58); +} + +/** + * @brief Get field yacc from hil_state_quaternion message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_quaternion_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 60); +} + +/** + * @brief Get field zacc from hil_state_quaternion message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_quaternion_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 62); +} + +/** + * @brief Decode a hil_state_quaternion message into a struct + * + * @param msg The message to decode + * @param hil_state_quaternion C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_state_quaternion_decode(const mavlink_message_t* msg, mavlink_hil_state_quaternion_t* hil_state_quaternion) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_state_quaternion->time_usec = mavlink_msg_hil_state_quaternion_get_time_usec(msg); + mavlink_msg_hil_state_quaternion_get_attitude_quaternion(msg, hil_state_quaternion->attitude_quaternion); + hil_state_quaternion->rollspeed = mavlink_msg_hil_state_quaternion_get_rollspeed(msg); + hil_state_quaternion->pitchspeed = mavlink_msg_hil_state_quaternion_get_pitchspeed(msg); + hil_state_quaternion->yawspeed = mavlink_msg_hil_state_quaternion_get_yawspeed(msg); + hil_state_quaternion->lat = mavlink_msg_hil_state_quaternion_get_lat(msg); + hil_state_quaternion->lon = mavlink_msg_hil_state_quaternion_get_lon(msg); + hil_state_quaternion->alt = mavlink_msg_hil_state_quaternion_get_alt(msg); + hil_state_quaternion->vx = mavlink_msg_hil_state_quaternion_get_vx(msg); + hil_state_quaternion->vy = mavlink_msg_hil_state_quaternion_get_vy(msg); + hil_state_quaternion->vz = mavlink_msg_hil_state_quaternion_get_vz(msg); + hil_state_quaternion->ind_airspeed = mavlink_msg_hil_state_quaternion_get_ind_airspeed(msg); + hil_state_quaternion->true_airspeed = mavlink_msg_hil_state_quaternion_get_true_airspeed(msg); + hil_state_quaternion->xacc = mavlink_msg_hil_state_quaternion_get_xacc(msg); + hil_state_quaternion->yacc = mavlink_msg_hil_state_quaternion_get_yacc(msg); + hil_state_quaternion->zacc = mavlink_msg_hil_state_quaternion_get_zacc(msg); +#else + memcpy(hil_state_quaternion, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_home_position.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_home_position.h new file mode 100644 index 0000000..c7181b7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_home_position.h @@ -0,0 +1,417 @@ +// MESSAGE HOME_POSITION PACKING + +#define MAVLINK_MSG_ID_HOME_POSITION 242 + +typedef struct __mavlink_home_position_t +{ + int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/ + int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ + float x; /*< Local X position of this position in the local coordinate frame*/ + float y; /*< Local Y position of this position in the local coordinate frame*/ + float z; /*< Local Z position of this position in the local coordinate frame*/ + float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/ + float approach_x; /*< Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ + float approach_y; /*< Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ + float approach_z; /*< Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ +} mavlink_home_position_t; + +#define MAVLINK_MSG_ID_HOME_POSITION_LEN 52 +#define MAVLINK_MSG_ID_242_LEN 52 + +#define MAVLINK_MSG_ID_HOME_POSITION_CRC 104 +#define MAVLINK_MSG_ID_242_CRC 104 + +#define MAVLINK_MSG_HOME_POSITION_FIELD_Q_LEN 4 + +#define MAVLINK_MESSAGE_INFO_HOME_POSITION { \ + "HOME_POSITION", \ + 10, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_home_position_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_home_position_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_home_position_t, z) }, \ + { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_home_position_t, q) }, \ + { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \ + { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \ + { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \ + } \ +} + + +/** + * @brief Pack a home_position message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param x Local X position of this position in the local coordinate frame + * @param y Local Y position of this position in the local coordinate frame + * @param z Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_float_array(buf, 24, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#else + mavlink_home_position_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.x = x; + packet.y = y; + packet.z = z; + packet.approach_x = approach_x; + packet.approach_y = approach_y; + packet.approach_z = approach_z; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HOME_POSITION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif +} + +/** + * @brief Pack a home_position message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param x Local X position of this position in the local coordinate frame + * @param y Local Y position of this position in the local coordinate frame + * @param z Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int32_t latitude,int32_t longitude,int32_t altitude,float x,float y,float z,const float *q,float approach_x,float approach_y,float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_float_array(buf, 24, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#else + mavlink_home_position_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.x = x; + packet.y = y; + packet.z = z; + packet.approach_x = approach_x; + packet.approach_y = approach_y; + packet.approach_z = approach_z; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HOME_POSITION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif +} + +/** + * @brief Encode a home_position struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param home_position C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_home_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_home_position_t* home_position) +{ + return mavlink_msg_home_position_pack(system_id, component_id, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z); +} + +/** + * @brief Encode a home_position struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param home_position C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_home_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_home_position_t* home_position) +{ + return mavlink_msg_home_position_pack_chan(system_id, component_id, chan, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z); +} + +/** + * @brief Send a home_position message + * @param chan MAVLink channel to send the message + * + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param x Local X position of this position in the local coordinate frame + * @param y Local Y position of this position in the local coordinate frame + * @param z Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_home_position_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_float_array(buf, 24, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif +#else + mavlink_home_position_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.x = x; + packet.y = y; + packet.z = z; + packet.approach_x = approach_x; + packet.approach_y = approach_y; + packet.approach_z = approach_z; + mav_array_memcpy(packet.q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_home_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_float_array(buf, 24, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif +#else + mavlink_home_position_t *packet = (mavlink_home_position_t *)msgbuf; + packet->latitude = latitude; + packet->longitude = longitude; + packet->altitude = altitude; + packet->x = x; + packet->y = y; + packet->z = z; + packet->approach_x = approach_x; + packet->approach_y = approach_y; + packet->approach_z = approach_z; + mav_array_memcpy(packet->q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HOME_POSITION UNPACKING + + +/** + * @brief Get field latitude from home_position message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_home_position_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from home_position message + * + * @return Longitude (WGS84, in degrees * 1E7 + */ +static inline int32_t mavlink_msg_home_position_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from home_position message + * + * @return Altitude (AMSL), in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_home_position_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field x from home_position message + * + * @return Local X position of this position in the local coordinate frame + */ +static inline float mavlink_msg_home_position_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field y from home_position message + * + * @return Local Y position of this position in the local coordinate frame + */ +static inline float mavlink_msg_home_position_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field z from home_position message + * + * @return Local Z position of this position in the local coordinate frame + */ +static inline float mavlink_msg_home_position_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field q from home_position message + * + * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + */ +static inline uint16_t mavlink_msg_home_position_get_q(const mavlink_message_t* msg, float *q) +{ + return _MAV_RETURN_float_array(msg, q, 4, 24); +} + +/** + * @brief Get field approach_x from home_position message + * + * @return Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +static inline float mavlink_msg_home_position_get_approach_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field approach_y from home_position message + * + * @return Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +static inline float mavlink_msg_home_position_get_approach_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field approach_z from home_position message + * + * @return Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +static inline float mavlink_msg_home_position_get_approach_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 48); +} + +/** + * @brief Decode a home_position message into a struct + * + * @param msg The message to decode + * @param home_position C-struct to decode the message contents into + */ +static inline void mavlink_msg_home_position_decode(const mavlink_message_t* msg, mavlink_home_position_t* home_position) +{ +#if MAVLINK_NEED_BYTE_SWAP + home_position->latitude = mavlink_msg_home_position_get_latitude(msg); + home_position->longitude = mavlink_msg_home_position_get_longitude(msg); + home_position->altitude = mavlink_msg_home_position_get_altitude(msg); + home_position->x = mavlink_msg_home_position_get_x(msg); + home_position->y = mavlink_msg_home_position_get_y(msg); + home_position->z = mavlink_msg_home_position_get_z(msg); + mavlink_msg_home_position_get_q(msg, home_position->q); + home_position->approach_x = mavlink_msg_home_position_get_approach_x(msg); + home_position->approach_y = mavlink_msg_home_position_get_approach_y(msg); + home_position->approach_z = mavlink_msg_home_position_get_approach_z(msg); +#else + memcpy(home_position, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_landing_target.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_landing_target.h new file mode 100644 index 0000000..14b03bf --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_landing_target.h @@ -0,0 +1,377 @@ +// MESSAGE LANDING_TARGET PACKING + +#define MAVLINK_MSG_ID_LANDING_TARGET 149 + +typedef struct __mavlink_landing_target_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float angle_x; /*< X-axis angular offset (in radians) of the target from the center of the image*/ + float angle_y; /*< Y-axis angular offset (in radians) of the target from the center of the image*/ + float distance; /*< Distance to the target from the vehicle in meters*/ + float size_x; /*< Size in radians of target along x-axis*/ + float size_y; /*< Size in radians of target along y-axis*/ + uint8_t target_num; /*< The ID of the target if multiple targets are present*/ + uint8_t frame; /*< MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc.*/ +} mavlink_landing_target_t; + +#define MAVLINK_MSG_ID_LANDING_TARGET_LEN 30 +#define MAVLINK_MSG_ID_149_LEN 30 + +#define MAVLINK_MSG_ID_LANDING_TARGET_CRC 200 +#define MAVLINK_MSG_ID_149_CRC 200 + + + +#define MAVLINK_MESSAGE_INFO_LANDING_TARGET { \ + "LANDING_TARGET", \ + 8, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \ + { "angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_landing_target_t, angle_x) }, \ + { "angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_landing_target_t, angle_y) }, \ + { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \ + { "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \ + { "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \ + { "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \ + } \ +} + + +/** + * @brief Pack a landing_target message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param target_num The ID of the target if multiple targets are present + * @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. + * @param angle_x X-axis angular offset (in radians) of the target from the center of the image + * @param angle_y Y-axis angular offset (in radians) of the target from the center of the image + * @param distance Distance to the target from the vehicle in meters + * @param size_x Size in radians of target along x-axis + * @param size_y Size in radians of target along y-axis + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, angle_x); + _mav_put_float(buf, 12, angle_y); + _mav_put_float(buf, 16, distance); + _mav_put_float(buf, 20, size_x); + _mav_put_float(buf, 24, size_y); + _mav_put_uint8_t(buf, 28, target_num); + _mav_put_uint8_t(buf, 29, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#else + mavlink_landing_target_t packet; + packet.time_usec = time_usec; + packet.angle_x = angle_x; + packet.angle_y = angle_y; + packet.distance = distance; + packet.size_x = size_x; + packet.size_y = size_y; + packet.target_num = target_num; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LANDING_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif +} + +/** + * @brief Pack a landing_target message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param target_num The ID of the target if multiple targets are present + * @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. + * @param angle_x X-axis angular offset (in radians) of the target from the center of the image + * @param angle_y Y-axis angular offset (in radians) of the target from the center of the image + * @param distance Distance to the target from the vehicle in meters + * @param size_x Size in radians of target along x-axis + * @param size_y Size in radians of target along y-axis + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t target_num,uint8_t frame,float angle_x,float angle_y,float distance,float size_x,float size_y) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, angle_x); + _mav_put_float(buf, 12, angle_y); + _mav_put_float(buf, 16, distance); + _mav_put_float(buf, 20, size_x); + _mav_put_float(buf, 24, size_y); + _mav_put_uint8_t(buf, 28, target_num); + _mav_put_uint8_t(buf, 29, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#else + mavlink_landing_target_t packet; + packet.time_usec = time_usec; + packet.angle_x = angle_x; + packet.angle_y = angle_y; + packet.distance = distance; + packet.size_x = size_x; + packet.size_y = size_y; + packet.target_num = target_num; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LANDING_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif +} + +/** + * @brief Encode a landing_target struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param landing_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_landing_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_landing_target_t* landing_target) +{ + return mavlink_msg_landing_target_pack(system_id, component_id, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y); +} + +/** + * @brief Encode a landing_target struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param landing_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_landing_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_landing_target_t* landing_target) +{ + return mavlink_msg_landing_target_pack_chan(system_id, component_id, chan, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y); +} + +/** + * @brief Send a landing_target message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param target_num The ID of the target if multiple targets are present + * @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. + * @param angle_x X-axis angular offset (in radians) of the target from the center of the image + * @param angle_y Y-axis angular offset (in radians) of the target from the center of the image + * @param distance Distance to the target from the vehicle in meters + * @param size_x Size in radians of target along x-axis + * @param size_y Size in radians of target along y-axis + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, angle_x); + _mav_put_float(buf, 12, angle_y); + _mav_put_float(buf, 16, distance); + _mav_put_float(buf, 20, size_x); + _mav_put_float(buf, 24, size_y); + _mav_put_uint8_t(buf, 28, target_num); + _mav_put_uint8_t(buf, 29, frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif +#else + mavlink_landing_target_t packet; + packet.time_usec = time_usec; + packet.angle_x = angle_x; + packet.angle_y = angle_y; + packet.distance = distance; + packet.size_x = size_x; + packet.size_y = size_y; + packet.target_num = target_num; + packet.frame = frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)&packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)&packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LANDING_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_landing_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, angle_x); + _mav_put_float(buf, 12, angle_y); + _mav_put_float(buf, 16, distance); + _mav_put_float(buf, 20, size_x); + _mav_put_float(buf, 24, size_y); + _mav_put_uint8_t(buf, 28, target_num); + _mav_put_uint8_t(buf, 29, frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif +#else + mavlink_landing_target_t *packet = (mavlink_landing_target_t *)msgbuf; + packet->time_usec = time_usec; + packet->angle_x = angle_x; + packet->angle_y = angle_y; + packet->distance = distance; + packet->size_x = size_x; + packet->size_y = size_y; + packet->target_num = target_num; + packet->frame = frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LANDING_TARGET UNPACKING + + +/** + * @brief Get field time_usec from landing_target message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_landing_target_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field target_num from landing_target message + * + * @return The ID of the target if multiple targets are present + */ +static inline uint8_t mavlink_msg_landing_target_get_target_num(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 28); +} + +/** + * @brief Get field frame from landing_target message + * + * @return MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. + */ +static inline uint8_t mavlink_msg_landing_target_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 29); +} + +/** + * @brief Get field angle_x from landing_target message + * + * @return X-axis angular offset (in radians) of the target from the center of the image + */ +static inline float mavlink_msg_landing_target_get_angle_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field angle_y from landing_target message + * + * @return Y-axis angular offset (in radians) of the target from the center of the image + */ +static inline float mavlink_msg_landing_target_get_angle_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field distance from landing_target message + * + * @return Distance to the target from the vehicle in meters + */ +static inline float mavlink_msg_landing_target_get_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field size_x from landing_target message + * + * @return Size in radians of target along x-axis + */ +static inline float mavlink_msg_landing_target_get_size_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field size_y from landing_target message + * + * @return Size in radians of target along y-axis + */ +static inline float mavlink_msg_landing_target_get_size_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a landing_target message into a struct + * + * @param msg The message to decode + * @param landing_target C-struct to decode the message contents into + */ +static inline void mavlink_msg_landing_target_decode(const mavlink_message_t* msg, mavlink_landing_target_t* landing_target) +{ +#if MAVLINK_NEED_BYTE_SWAP + landing_target->time_usec = mavlink_msg_landing_target_get_time_usec(msg); + landing_target->angle_x = mavlink_msg_landing_target_get_angle_x(msg); + landing_target->angle_y = mavlink_msg_landing_target_get_angle_y(msg); + landing_target->distance = mavlink_msg_landing_target_get_distance(msg); + landing_target->size_x = mavlink_msg_landing_target_get_size_x(msg); + landing_target->size_y = mavlink_msg_landing_target_get_size_y(msg); + landing_target->target_num = mavlink_msg_landing_target_get_target_num(msg); + landing_target->frame = mavlink_msg_landing_target_get_frame(msg); +#else + memcpy(landing_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_local_position_ned.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_local_position_ned.h new file mode 100644 index 0000000..a15dbce --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_local_position_ned.h @@ -0,0 +1,353 @@ +// MESSAGE LOCAL_POSITION_NED PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED 32 + +typedef struct __mavlink_local_position_ned_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float x; /*< X Position*/ + float y; /*< Y Position*/ + float z; /*< Z Position*/ + float vx; /*< X Speed*/ + float vy; /*< Y Speed*/ + float vz; /*< Z Speed*/ +} mavlink_local_position_ned_t; + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28 +#define MAVLINK_MSG_ID_32_LEN 28 + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC 185 +#define MAVLINK_MSG_ID_32_CRC 185 + + + +#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \ + "LOCAL_POSITION_NED", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \ + } \ +} + + +/** + * @brief Pack a local_position_ned message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#else + mavlink_local_position_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif +} + +/** + * @brief Pack a local_position_ned message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float x,float y,float z,float vx,float vy,float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#else + mavlink_local_position_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif +} + +/** + * @brief Encode a local_position_ned struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param local_position_ned C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned) +{ + return mavlink_msg_local_position_ned_pack(system_id, component_id, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); +} + +/** + * @brief Encode a local_position_ned struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param local_position_ned C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned) +{ + return mavlink_msg_local_position_ned_pack_chan(system_id, component_id, chan, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); +} + +/** + * @brief Send a local_position_ned message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif +#else + mavlink_local_position_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_local_position_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif +#else + mavlink_local_position_ned_t *packet = (mavlink_local_position_ned_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->x = x; + packet->y = y; + packet->z = z; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOCAL_POSITION_NED UNPACKING + + +/** + * @brief Get field time_boot_ms from local_position_ned message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_local_position_ned_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field x from local_position_ned message + * + * @return X Position + */ +static inline float mavlink_msg_local_position_ned_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field y from local_position_ned message + * + * @return Y Position + */ +static inline float mavlink_msg_local_position_ned_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field z from local_position_ned message + * + * @return Z Position + */ +static inline float mavlink_msg_local_position_ned_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vx from local_position_ned message + * + * @return X Speed + */ +static inline float mavlink_msg_local_position_ned_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vy from local_position_ned message + * + * @return Y Speed + */ +static inline float mavlink_msg_local_position_ned_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vz from local_position_ned message + * + * @return Z Speed + */ +static inline float mavlink_msg_local_position_ned_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a local_position_ned message into a struct + * + * @param msg The message to decode + * @param local_position_ned C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_position_ned_decode(const mavlink_message_t* msg, mavlink_local_position_ned_t* local_position_ned) +{ +#if MAVLINK_NEED_BYTE_SWAP + local_position_ned->time_boot_ms = mavlink_msg_local_position_ned_get_time_boot_ms(msg); + local_position_ned->x = mavlink_msg_local_position_ned_get_x(msg); + local_position_ned->y = mavlink_msg_local_position_ned_get_y(msg); + local_position_ned->z = mavlink_msg_local_position_ned_get_z(msg); + local_position_ned->vx = mavlink_msg_local_position_ned_get_vx(msg); + local_position_ned->vy = mavlink_msg_local_position_ned_get_vy(msg); + local_position_ned->vz = mavlink_msg_local_position_ned_get_vz(msg); +#else + memcpy(local_position_ned, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_local_position_ned_cov.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_local_position_ned_cov.h new file mode 100644 index 0000000..59b8369 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_local_position_ned_cov.h @@ -0,0 +1,489 @@ +// MESSAGE LOCAL_POSITION_NED_COV PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV 64 + +typedef struct __mavlink_local_position_ned_cov_t +{ + uint64_t time_utc; /*< Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.*/ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp*/ + float x; /*< X Position*/ + float y; /*< Y Position*/ + float z; /*< Z Position*/ + float vx; /*< X Speed (m/s)*/ + float vy; /*< Y Speed (m/s)*/ + float vz; /*< Z Speed (m/s)*/ + float ax; /*< X Acceleration (m/s^2)*/ + float ay; /*< Y Acceleration (m/s^2)*/ + float az; /*< Z Acceleration (m/s^2)*/ + float covariance[45]; /*< Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)*/ + uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/ +} mavlink_local_position_ned_cov_t; + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN 229 +#define MAVLINK_MSG_ID_64_LEN 229 + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC 59 +#define MAVLINK_MSG_ID_64_CRC 59 + +#define MAVLINK_MSG_LOCAL_POSITION_NED_COV_FIELD_COVARIANCE_LEN 45 + +#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \ + "LOCAL_POSITION_NED_COV", \ + 13, \ + { { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_utc) }, \ + { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_local_position_ned_cov_t, time_boot_ms) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, z) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, vz) }, \ + { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ax) }, \ + { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, ay) }, \ + { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_local_position_ned_cov_t, az) }, \ + { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 48, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \ + { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 228, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \ + } \ +} + + +/** + * @brief Pack a local_position_ned_cov message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp + * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed (m/s) + * @param vy Y Speed (m/s) + * @param vz Z Speed (m/s) + * @param ax X Acceleration (m/s^2) + * @param ay Y Acceleration (m/s^2) + * @param az Z Acceleration (m/s^2) + * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 24, vx); + _mav_put_float(buf, 28, vy); + _mav_put_float(buf, 32, vz); + _mav_put_float(buf, 36, ax); + _mav_put_float(buf, 40, ay); + _mav_put_float(buf, 44, az); + _mav_put_uint8_t(buf, 228, estimator_type); + _mav_put_float_array(buf, 48, covariance, 45); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#else + mavlink_local_position_ned_cov_t packet; + packet.time_utc = time_utc; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ax = ax; + packet.ay = ay; + packet.az = az; + packet.estimator_type = estimator_type; + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif +} + +/** + * @brief Pack a local_position_ned_cov message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp + * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed (m/s) + * @param vy Y Speed (m/s) + * @param vz Z Speed (m/s) + * @param ax X Acceleration (m/s^2) + * @param ay Y Acceleration (m/s^2) + * @param az Z Acceleration (m/s^2) + * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint64_t time_utc,uint8_t estimator_type,float x,float y,float z,float vx,float vy,float vz,float ax,float ay,float az,const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 24, vx); + _mav_put_float(buf, 28, vy); + _mav_put_float(buf, 32, vz); + _mav_put_float(buf, 36, ax); + _mav_put_float(buf, 40, ay); + _mav_put_float(buf, 44, az); + _mav_put_uint8_t(buf, 228, estimator_type); + _mav_put_float_array(buf, 48, covariance, 45); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#else + mavlink_local_position_ned_cov_t packet; + packet.time_utc = time_utc; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ax = ax; + packet.ay = ay; + packet.az = az; + packet.estimator_type = estimator_type; + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif +} + +/** + * @brief Encode a local_position_ned_cov struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param local_position_ned_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_ned_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov) +{ + return mavlink_msg_local_position_ned_cov_pack(system_id, component_id, msg, local_position_ned_cov->time_boot_ms, local_position_ned_cov->time_utc, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance); +} + +/** + * @brief Encode a local_position_ned_cov struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param local_position_ned_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_ned_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov) +{ + return mavlink_msg_local_position_ned_cov_pack_chan(system_id, component_id, chan, msg, local_position_ned_cov->time_boot_ms, local_position_ned_cov->time_utc, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance); +} + +/** + * @brief Send a local_position_ned_cov message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp + * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed (m/s) + * @param vy Y Speed (m/s) + * @param vz Z Speed (m/s) + * @param ax X Acceleration (m/s^2) + * @param ay Y Acceleration (m/s^2) + * @param az Z Acceleration (m/s^2) + * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_ned_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 24, vx); + _mav_put_float(buf, 28, vy); + _mav_put_float(buf, 32, vz); + _mav_put_float(buf, 36, ax); + _mav_put_float(buf, 40, ay); + _mav_put_float(buf, 44, az); + _mav_put_uint8_t(buf, 228, estimator_type); + _mav_put_float_array(buf, 48, covariance, 45); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif +#else + mavlink_local_position_ned_cov_t packet; + packet.time_utc = time_utc; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ax = ax; + packet.ay = ay; + packet.az = az; + packet.estimator_type = estimator_type; + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_local_position_ned_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 24, vx); + _mav_put_float(buf, 28, vy); + _mav_put_float(buf, 32, vz); + _mav_put_float(buf, 36, ax); + _mav_put_float(buf, 40, ay); + _mav_put_float(buf, 44, az); + _mav_put_uint8_t(buf, 228, estimator_type); + _mav_put_float_array(buf, 48, covariance, 45); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif +#else + mavlink_local_position_ned_cov_t *packet = (mavlink_local_position_ned_cov_t *)msgbuf; + packet->time_utc = time_utc; + packet->time_boot_ms = time_boot_ms; + packet->x = x; + packet->y = y; + packet->z = z; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->ax = ax; + packet->ay = ay; + packet->az = az; + packet->estimator_type = estimator_type; + mav_array_memcpy(packet->covariance, covariance, sizeof(float)*45); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOCAL_POSITION_NED_COV UNPACKING + + +/** + * @brief Get field time_boot_ms from local_position_ned_cov message + * + * @return Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp + */ +static inline uint32_t mavlink_msg_local_position_ned_cov_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field time_utc from local_position_ned_cov message + * + * @return Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + */ +static inline uint64_t mavlink_msg_local_position_ned_cov_get_time_utc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field estimator_type from local_position_ned_cov message + * + * @return Class id of the estimator this estimate originated from. + */ +static inline uint8_t mavlink_msg_local_position_ned_cov_get_estimator_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 228); +} + +/** + * @brief Get field x from local_position_ned_cov message + * + * @return X Position + */ +static inline float mavlink_msg_local_position_ned_cov_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field y from local_position_ned_cov message + * + * @return Y Position + */ +static inline float mavlink_msg_local_position_ned_cov_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field z from local_position_ned_cov message + * + * @return Z Position + */ +static inline float mavlink_msg_local_position_ned_cov_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vx from local_position_ned_cov message + * + * @return X Speed (m/s) + */ +static inline float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field vy from local_position_ned_cov message + * + * @return Y Speed (m/s) + */ +static inline float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field vz from local_position_ned_cov message + * + * @return Z Speed (m/s) + */ +static inline float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field ax from local_position_ned_cov message + * + * @return X Acceleration (m/s^2) + */ +static inline float mavlink_msg_local_position_ned_cov_get_ax(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field ay from local_position_ned_cov message + * + * @return Y Acceleration (m/s^2) + */ +static inline float mavlink_msg_local_position_ned_cov_get_ay(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field az from local_position_ned_cov message + * + * @return Z Acceleration (m/s^2) + */ +static inline float mavlink_msg_local_position_ned_cov_get_az(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field covariance from local_position_ned_cov message + * + * @return Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + */ +static inline uint16_t mavlink_msg_local_position_ned_cov_get_covariance(const mavlink_message_t* msg, float *covariance) +{ + return _MAV_RETURN_float_array(msg, covariance, 45, 48); +} + +/** + * @brief Decode a local_position_ned_cov message into a struct + * + * @param msg The message to decode + * @param local_position_ned_cov C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_position_ned_cov_decode(const mavlink_message_t* msg, mavlink_local_position_ned_cov_t* local_position_ned_cov) +{ +#if MAVLINK_NEED_BYTE_SWAP + local_position_ned_cov->time_utc = mavlink_msg_local_position_ned_cov_get_time_utc(msg); + local_position_ned_cov->time_boot_ms = mavlink_msg_local_position_ned_cov_get_time_boot_ms(msg); + local_position_ned_cov->x = mavlink_msg_local_position_ned_cov_get_x(msg); + local_position_ned_cov->y = mavlink_msg_local_position_ned_cov_get_y(msg); + local_position_ned_cov->z = mavlink_msg_local_position_ned_cov_get_z(msg); + local_position_ned_cov->vx = mavlink_msg_local_position_ned_cov_get_vx(msg); + local_position_ned_cov->vy = mavlink_msg_local_position_ned_cov_get_vy(msg); + local_position_ned_cov->vz = mavlink_msg_local_position_ned_cov_get_vz(msg); + local_position_ned_cov->ax = mavlink_msg_local_position_ned_cov_get_ax(msg); + local_position_ned_cov->ay = mavlink_msg_local_position_ned_cov_get_ay(msg); + local_position_ned_cov->az = mavlink_msg_local_position_ned_cov_get_az(msg); + mavlink_msg_local_position_ned_cov_get_covariance(msg, local_position_ned_cov->covariance); + local_position_ned_cov->estimator_type = mavlink_msg_local_position_ned_cov_get_estimator_type(msg); +#else + memcpy(local_position_ned_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h new file mode 100644 index 0000000..e6d0766 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h @@ -0,0 +1,353 @@ +// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET 89 + +typedef struct __mavlink_local_position_ned_system_global_offset_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float x; /*< X Position*/ + float y; /*< Y Position*/ + float z; /*< Z Position*/ + float roll; /*< Roll*/ + float pitch; /*< Pitch*/ + float yaw; /*< Yaw*/ +} mavlink_local_position_ned_system_global_offset_t; + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN 28 +#define MAVLINK_MSG_ID_89_LEN 28 + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC 231 +#define MAVLINK_MSG_ID_89_CRC 231 + + + +#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET { \ + "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_system_global_offset_t, time_boot_ms) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_system_global_offset_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_system_global_offset_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_system_global_offset_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_system_global_offset_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_system_global_offset_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_system_global_offset_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a local_position_ned_system_global_offset message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param roll Roll + * @param pitch Pitch + * @param yaw Yaw + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#else + mavlink_local_position_ned_system_global_offset_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif +} + +/** + * @brief Pack a local_position_ned_system_global_offset message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param roll Roll + * @param pitch Pitch + * @param yaw Yaw + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#else + mavlink_local_position_ned_system_global_offset_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif +} + +/** + * @brief Encode a local_position_ned_system_global_offset struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param local_position_ned_system_global_offset C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) +{ + return mavlink_msg_local_position_ned_system_global_offset_pack(system_id, component_id, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); +} + +/** + * @brief Encode a local_position_ned_system_global_offset struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param local_position_ned_system_global_offset C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) +{ + return mavlink_msg_local_position_ned_system_global_offset_pack_chan(system_id, component_id, chan, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); +} + +/** + * @brief Send a local_position_ned_system_global_offset message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param roll Roll + * @param pitch Pitch + * @param yaw Yaw + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_ned_system_global_offset_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif +#else + mavlink_local_position_ned_system_global_offset_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_local_position_ned_system_global_offset_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif +#else + mavlink_local_position_ned_system_global_offset_t *packet = (mavlink_local_position_ned_system_global_offset_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->x = x; + packet->y = y; + packet->z = z; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET UNPACKING + + +/** + * @brief Get field time_boot_ms from local_position_ned_system_global_offset message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field x from local_position_ned_system_global_offset message + * + * @return X Position + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field y from local_position_ned_system_global_offset message + * + * @return Y Position + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field z from local_position_ned_system_global_offset message + * + * @return Z Position + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field roll from local_position_ned_system_global_offset message + * + * @return Roll + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field pitch from local_position_ned_system_global_offset message + * + * @return Pitch + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field yaw from local_position_ned_system_global_offset message + * + * @return Yaw + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a local_position_ned_system_global_offset message into a struct + * + * @param msg The message to decode + * @param local_position_ned_system_global_offset C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_position_ned_system_global_offset_decode(const mavlink_message_t* msg, mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) +{ +#if MAVLINK_NEED_BYTE_SWAP + local_position_ned_system_global_offset->time_boot_ms = mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(msg); + local_position_ned_system_global_offset->x = mavlink_msg_local_position_ned_system_global_offset_get_x(msg); + local_position_ned_system_global_offset->y = mavlink_msg_local_position_ned_system_global_offset_get_y(msg); + local_position_ned_system_global_offset->z = mavlink_msg_local_position_ned_system_global_offset_get_z(msg); + local_position_ned_system_global_offset->roll = mavlink_msg_local_position_ned_system_global_offset_get_roll(msg); + local_position_ned_system_global_offset->pitch = mavlink_msg_local_position_ned_system_global_offset_get_pitch(msg); + local_position_ned_system_global_offset->yaw = mavlink_msg_local_position_ned_system_global_offset_get_yaw(msg); +#else + memcpy(local_position_ned_system_global_offset, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_data.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_data.h new file mode 100644 index 0000000..9caae57 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_data.h @@ -0,0 +1,273 @@ +// MESSAGE LOG_DATA PACKING + +#define MAVLINK_MSG_ID_LOG_DATA 120 + +typedef struct __mavlink_log_data_t +{ + uint32_t ofs; /*< Offset into the log*/ + uint16_t id; /*< Log id (from LOG_ENTRY reply)*/ + uint8_t count; /*< Number of bytes (zero for end of log)*/ + uint8_t data[90]; /*< log data*/ +} mavlink_log_data_t; + +#define MAVLINK_MSG_ID_LOG_DATA_LEN 97 +#define MAVLINK_MSG_ID_120_LEN 97 + +#define MAVLINK_MSG_ID_LOG_DATA_CRC 134 +#define MAVLINK_MSG_ID_120_CRC 134 + +#define MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN 90 + +#define MAVLINK_MESSAGE_INFO_LOG_DATA { \ + "LOG_DATA", \ + 4, \ + { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \ + { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \ + { "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \ + } \ +} + + +/** + * @brief Pack a log_data message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes (zero for end of log) + * @param data log data + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint16_t(buf, 4, id); + _mav_put_uint8_t(buf, 6, count); + _mav_put_uint8_t_array(buf, 7, data, 90); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN); +#else + mavlink_log_data_t packet; + packet.ofs = ofs; + packet.id = id; + packet.count = count; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +} + +/** + * @brief Pack a log_data message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes (zero for end of log) + * @param data log data + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t id,uint32_t ofs,uint8_t count,const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint16_t(buf, 4, id); + _mav_put_uint8_t(buf, 6, count); + _mav_put_uint8_t_array(buf, 7, data, 90); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN); +#else + mavlink_log_data_t packet; + packet.ofs = ofs; + packet.id = id; + packet.count = count; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +} + +/** + * @brief Encode a log_data struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param log_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_data_t* log_data) +{ + return mavlink_msg_log_data_pack(system_id, component_id, msg, log_data->id, log_data->ofs, log_data->count, log_data->data); +} + +/** + * @brief Encode a log_data struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param log_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_data_t* log_data) +{ + return mavlink_msg_log_data_pack_chan(system_id, component_id, chan, msg, log_data->id, log_data->ofs, log_data->count, log_data->data); +} + +/** + * @brief Send a log_data message + * @param chan MAVLink channel to send the message + * + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes (zero for end of log) + * @param data log data + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_data_send(mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint16_t(buf, 4, id); + _mav_put_uint8_t(buf, 6, count); + _mav_put_uint8_t_array(buf, 7, data, 90); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +#else + mavlink_log_data_t packet; + packet.ofs = ofs; + packet.id = id; + packet.count = count; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOG_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_log_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint16_t(buf, 4, id); + _mav_put_uint8_t(buf, 6, count); + _mav_put_uint8_t_array(buf, 7, data, 90); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +#else + mavlink_log_data_t *packet = (mavlink_log_data_t *)msgbuf; + packet->ofs = ofs; + packet->id = id; + packet->count = count; + mav_array_memcpy(packet->data, data, sizeof(uint8_t)*90); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOG_DATA UNPACKING + + +/** + * @brief Get field id from log_data message + * + * @return Log id (from LOG_ENTRY reply) + */ +static inline uint16_t mavlink_msg_log_data_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field ofs from log_data message + * + * @return Offset into the log + */ +static inline uint32_t mavlink_msg_log_data_get_ofs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field count from log_data message + * + * @return Number of bytes (zero for end of log) + */ +static inline uint8_t mavlink_msg_log_data_get_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field data from log_data message + * + * @return log data + */ +static inline uint16_t mavlink_msg_log_data_get_data(const mavlink_message_t* msg, uint8_t *data) +{ + return _MAV_RETURN_uint8_t_array(msg, data, 90, 7); +} + +/** + * @brief Decode a log_data message into a struct + * + * @param msg The message to decode + * @param log_data C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_data_decode(const mavlink_message_t* msg, mavlink_log_data_t* log_data) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_data->ofs = mavlink_msg_log_data_get_ofs(msg); + log_data->id = mavlink_msg_log_data_get_id(msg); + log_data->count = mavlink_msg_log_data_get_count(msg); + mavlink_msg_log_data_get_data(msg, log_data->data); +#else + memcpy(log_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_entry.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_entry.h new file mode 100644 index 0000000..4523516 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_entry.h @@ -0,0 +1,305 @@ +// MESSAGE LOG_ENTRY PACKING + +#define MAVLINK_MSG_ID_LOG_ENTRY 118 + +typedef struct __mavlink_log_entry_t +{ + uint32_t time_utc; /*< UTC timestamp of log in seconds since 1970, or 0 if not available*/ + uint32_t size; /*< Size of the log (may be approximate) in bytes*/ + uint16_t id; /*< Log id*/ + uint16_t num_logs; /*< Total number of logs*/ + uint16_t last_log_num; /*< High log number*/ +} mavlink_log_entry_t; + +#define MAVLINK_MSG_ID_LOG_ENTRY_LEN 14 +#define MAVLINK_MSG_ID_118_LEN 14 + +#define MAVLINK_MSG_ID_LOG_ENTRY_CRC 56 +#define MAVLINK_MSG_ID_118_CRC 56 + + + +#define MAVLINK_MESSAGE_INFO_LOG_ENTRY { \ + "LOG_ENTRY", \ + 5, \ + { { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ + { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ + { "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \ + { "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \ + } \ +} + + +/** + * @brief Pack a log_entry message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param id Log id + * @param num_logs Total number of logs + * @param last_log_num High log number + * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available + * @param size Size of the log (may be approximate) in bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_entry_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; + _mav_put_uint32_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 4, size); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint16_t(buf, 10, num_logs); + _mav_put_uint16_t(buf, 12, last_log_num); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#else + mavlink_log_entry_t packet; + packet.time_utc = time_utc; + packet.size = size; + packet.id = id; + packet.num_logs = num_logs; + packet.last_log_num = last_log_num; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +} + +/** + * @brief Pack a log_entry message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param id Log id + * @param num_logs Total number of logs + * @param last_log_num High log number + * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available + * @param size Size of the log (may be approximate) in bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_entry_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t id,uint16_t num_logs,uint16_t last_log_num,uint32_t time_utc,uint32_t size) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; + _mav_put_uint32_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 4, size); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint16_t(buf, 10, num_logs); + _mav_put_uint16_t(buf, 12, last_log_num); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#else + mavlink_log_entry_t packet; + packet.time_utc = time_utc; + packet.size = size; + packet.id = id; + packet.num_logs = num_logs; + packet.last_log_num = last_log_num; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +} + +/** + * @brief Encode a log_entry struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param log_entry C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_entry_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry) +{ + return mavlink_msg_log_entry_pack(system_id, component_id, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); +} + +/** + * @brief Encode a log_entry struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param log_entry C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_entry_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry) +{ + return mavlink_msg_log_entry_pack_chan(system_id, component_id, chan, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); +} + +/** + * @brief Send a log_entry message + * @param chan MAVLink channel to send the message + * + * @param id Log id + * @param num_logs Total number of logs + * @param last_log_num High log number + * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available + * @param size Size of the log (may be approximate) in bytes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_entry_send(mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; + _mav_put_uint32_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 4, size); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint16_t(buf, 10, num_logs); + _mav_put_uint16_t(buf, 12, last_log_num); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +#else + mavlink_log_entry_t packet; + packet.time_utc = time_utc; + packet.size = size; + packet.id = id; + packet.num_logs = num_logs; + packet.last_log_num = last_log_num; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)&packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)&packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOG_ENTRY_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_log_entry_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 4, size); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint16_t(buf, 10, num_logs); + _mav_put_uint16_t(buf, 12, last_log_num); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +#else + mavlink_log_entry_t *packet = (mavlink_log_entry_t *)msgbuf; + packet->time_utc = time_utc; + packet->size = size; + packet->id = id; + packet->num_logs = num_logs; + packet->last_log_num = last_log_num; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOG_ENTRY UNPACKING + + +/** + * @brief Get field id from log_entry message + * + * @return Log id + */ +static inline uint16_t mavlink_msg_log_entry_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field num_logs from log_entry message + * + * @return Total number of logs + */ +static inline uint16_t mavlink_msg_log_entry_get_num_logs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field last_log_num from log_entry message + * + * @return High log number + */ +static inline uint16_t mavlink_msg_log_entry_get_last_log_num(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field time_utc from log_entry message + * + * @return UTC timestamp of log in seconds since 1970, or 0 if not available + */ +static inline uint32_t mavlink_msg_log_entry_get_time_utc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field size from log_entry message + * + * @return Size of the log (may be approximate) in bytes + */ +static inline uint32_t mavlink_msg_log_entry_get_size(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Decode a log_entry message into a struct + * + * @param msg The message to decode + * @param log_entry C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_entry_decode(const mavlink_message_t* msg, mavlink_log_entry_t* log_entry) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_entry->time_utc = mavlink_msg_log_entry_get_time_utc(msg); + log_entry->size = mavlink_msg_log_entry_get_size(msg); + log_entry->id = mavlink_msg_log_entry_get_id(msg); + log_entry->num_logs = mavlink_msg_log_entry_get_num_logs(msg); + log_entry->last_log_num = mavlink_msg_log_entry_get_last_log_num(msg); +#else + memcpy(log_entry, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_erase.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_erase.h new file mode 100644 index 0000000..06c58be --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_erase.h @@ -0,0 +1,233 @@ +// MESSAGE LOG_ERASE PACKING + +#define MAVLINK_MSG_ID_LOG_ERASE 121 + +typedef struct __mavlink_log_erase_t +{ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_log_erase_t; + +#define MAVLINK_MSG_ID_LOG_ERASE_LEN 2 +#define MAVLINK_MSG_ID_121_LEN 2 + +#define MAVLINK_MSG_ID_LOG_ERASE_CRC 237 +#define MAVLINK_MSG_ID_121_CRC 237 + + + +#define MAVLINK_MESSAGE_INFO_LOG_ERASE { \ + "LOG_ERASE", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_erase_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_erase_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a log_erase message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_erase_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#else + mavlink_log_erase_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_ERASE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +} + +/** + * @brief Pack a log_erase message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_erase_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#else + mavlink_log_erase_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_ERASE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +} + +/** + * @brief Encode a log_erase struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param log_erase C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_erase_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase) +{ + return mavlink_msg_log_erase_pack(system_id, component_id, msg, log_erase->target_system, log_erase->target_component); +} + +/** + * @brief Encode a log_erase struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param log_erase C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_erase_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase) +{ + return mavlink_msg_log_erase_pack_chan(system_id, component_id, chan, msg, log_erase->target_system, log_erase->target_component); +} + +/** + * @brief Send a log_erase message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_erase_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +#else + mavlink_log_erase_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)&packet, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)&packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOG_ERASE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_log_erase_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +#else + mavlink_log_erase_t *packet = (mavlink_log_erase_t *)msgbuf; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)packet, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOG_ERASE UNPACKING + + +/** + * @brief Get field target_system from log_erase message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_log_erase_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from log_erase message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_log_erase_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a log_erase message into a struct + * + * @param msg The message to decode + * @param log_erase C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_erase_decode(const mavlink_message_t* msg, mavlink_log_erase_t* log_erase) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_erase->target_system = mavlink_msg_log_erase_get_target_system(msg); + log_erase->target_component = mavlink_msg_log_erase_get_target_component(msg); +#else + memcpy(log_erase, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_request_data.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_request_data.h new file mode 100644 index 0000000..0b52ea2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_request_data.h @@ -0,0 +1,305 @@ +// MESSAGE LOG_REQUEST_DATA PACKING + +#define MAVLINK_MSG_ID_LOG_REQUEST_DATA 119 + +typedef struct __mavlink_log_request_data_t +{ + uint32_t ofs; /*< Offset into the log*/ + uint32_t count; /*< Number of bytes*/ + uint16_t id; /*< Log id (from LOG_ENTRY reply)*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_log_request_data_t; + +#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN 12 +#define MAVLINK_MSG_ID_119_LEN 12 + +#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC 116 +#define MAVLINK_MSG_ID_119_CRC 116 + + + +#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \ + "LOG_REQUEST_DATA", \ + 5, \ + { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \ + { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a log_request_data message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint32_t(buf, 4, count); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint8_t(buf, 10, target_system); + _mav_put_uint8_t(buf, 11, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#else + mavlink_log_request_data_t packet; + packet.ofs = ofs; + packet.count = count; + packet.id = id; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +} + +/** + * @brief Pack a log_request_data message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t id,uint32_t ofs,uint32_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint32_t(buf, 4, count); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint8_t(buf, 10, target_system); + _mav_put_uint8_t(buf, 11, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#else + mavlink_log_request_data_t packet; + packet.ofs = ofs; + packet.count = count; + packet.id = id; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +} + +/** + * @brief Encode a log_request_data struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param log_request_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data) +{ + return mavlink_msg_log_request_data_pack(system_id, component_id, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); +} + +/** + * @brief Encode a log_request_data struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param log_request_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data) +{ + return mavlink_msg_log_request_data_pack_chan(system_id, component_id, chan, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); +} + +/** + * @brief Send a log_request_data message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_request_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint32_t(buf, 4, count); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint8_t(buf, 10, target_system); + _mav_put_uint8_t(buf, 11, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +#else + mavlink_log_request_data_t packet; + packet.ofs = ofs; + packet.count = count; + packet.id = id; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_log_request_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint32_t(buf, 4, count); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint8_t(buf, 10, target_system); + _mav_put_uint8_t(buf, 11, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +#else + mavlink_log_request_data_t *packet = (mavlink_log_request_data_t *)msgbuf; + packet->ofs = ofs; + packet->count = count; + packet->id = id; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOG_REQUEST_DATA UNPACKING + + +/** + * @brief Get field target_system from log_request_data message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_log_request_data_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 10); +} + +/** + * @brief Get field target_component from log_request_data message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_log_request_data_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 11); +} + +/** + * @brief Get field id from log_request_data message + * + * @return Log id (from LOG_ENTRY reply) + */ +static inline uint16_t mavlink_msg_log_request_data_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field ofs from log_request_data message + * + * @return Offset into the log + */ +static inline uint32_t mavlink_msg_log_request_data_get_ofs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field count from log_request_data message + * + * @return Number of bytes + */ +static inline uint32_t mavlink_msg_log_request_data_get_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Decode a log_request_data message into a struct + * + * @param msg The message to decode + * @param log_request_data C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_request_data_decode(const mavlink_message_t* msg, mavlink_log_request_data_t* log_request_data) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_request_data->ofs = mavlink_msg_log_request_data_get_ofs(msg); + log_request_data->count = mavlink_msg_log_request_data_get_count(msg); + log_request_data->id = mavlink_msg_log_request_data_get_id(msg); + log_request_data->target_system = mavlink_msg_log_request_data_get_target_system(msg); + log_request_data->target_component = mavlink_msg_log_request_data_get_target_component(msg); +#else + memcpy(log_request_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_request_end.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_request_end.h new file mode 100644 index 0000000..e4da542 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_request_end.h @@ -0,0 +1,233 @@ +// MESSAGE LOG_REQUEST_END PACKING + +#define MAVLINK_MSG_ID_LOG_REQUEST_END 122 + +typedef struct __mavlink_log_request_end_t +{ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_log_request_end_t; + +#define MAVLINK_MSG_ID_LOG_REQUEST_END_LEN 2 +#define MAVLINK_MSG_ID_122_LEN 2 + +#define MAVLINK_MSG_ID_LOG_REQUEST_END_CRC 203 +#define MAVLINK_MSG_ID_122_CRC 203 + + + +#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_END { \ + "LOG_REQUEST_END", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_request_end_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_request_end_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a log_request_end message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_end_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#else + mavlink_log_request_end_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +} + +/** + * @brief Pack a log_request_end message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_end_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#else + mavlink_log_request_end_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +} + +/** + * @brief Encode a log_request_end struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param log_request_end C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_end_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end) +{ + return mavlink_msg_log_request_end_pack(system_id, component_id, msg, log_request_end->target_system, log_request_end->target_component); +} + +/** + * @brief Encode a log_request_end struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param log_request_end C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_end_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end) +{ + return mavlink_msg_log_request_end_pack_chan(system_id, component_id, chan, msg, log_request_end->target_system, log_request_end->target_component); +} + +/** + * @brief Send a log_request_end message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_request_end_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +#else + mavlink_log_request_end_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOG_REQUEST_END_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_log_request_end_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +#else + mavlink_log_request_end_t *packet = (mavlink_log_request_end_t *)msgbuf; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOG_REQUEST_END UNPACKING + + +/** + * @brief Get field target_system from log_request_end message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_log_request_end_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from log_request_end message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_log_request_end_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a log_request_end message into a struct + * + * @param msg The message to decode + * @param log_request_end C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_request_end_decode(const mavlink_message_t* msg, mavlink_log_request_end_t* log_request_end) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_request_end->target_system = mavlink_msg_log_request_end_get_target_system(msg); + log_request_end->target_component = mavlink_msg_log_request_end_get_target_component(msg); +#else + memcpy(log_request_end, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_request_list.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_request_list.h new file mode 100644 index 0000000..a4d5ea0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_log_request_list.h @@ -0,0 +1,281 @@ +// MESSAGE LOG_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_LOG_REQUEST_LIST 117 + +typedef struct __mavlink_log_request_list_t +{ + uint16_t start; /*< First log id (0 for first available)*/ + uint16_t end; /*< Last log id (0xffff for last available)*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_log_request_list_t; + +#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN 6 +#define MAVLINK_MSG_ID_117_LEN 6 + +#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC 128 +#define MAVLINK_MSG_ID_117_CRC 128 + + + +#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST { \ + "LOG_REQUEST_LIST", \ + 4, \ + { { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \ + { "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a log_request_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param start First log id (0 for first available) + * @param end Last log id (0xffff for last available) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; + _mav_put_uint16_t(buf, 0, start); + _mav_put_uint16_t(buf, 2, end); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#else + mavlink_log_request_list_t packet; + packet.start = start; + packet.end = end; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +} + +/** + * @brief Pack a log_request_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param start First log id (0 for first available) + * @param end Last log id (0xffff for last available) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t start,uint16_t end) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; + _mav_put_uint16_t(buf, 0, start); + _mav_put_uint16_t(buf, 2, end); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#else + mavlink_log_request_list_t packet; + packet.start = start; + packet.end = end; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +} + +/** + * @brief Encode a log_request_list struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param log_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list) +{ + return mavlink_msg_log_request_list_pack(system_id, component_id, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); +} + +/** + * @brief Encode a log_request_list struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param log_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list) +{ + return mavlink_msg_log_request_list_pack_chan(system_id, component_id, chan, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); +} + +/** + * @brief Send a log_request_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param start First log id (0 for first available) + * @param end Last log id (0xffff for last available) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; + _mav_put_uint16_t(buf, 0, start); + _mav_put_uint16_t(buf, 2, end); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +#else + mavlink_log_request_list_t packet; + packet.start = start; + packet.end = end; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_log_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, start); + _mav_put_uint16_t(buf, 2, end); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +#else + mavlink_log_request_list_t *packet = (mavlink_log_request_list_t *)msgbuf; + packet->start = start; + packet->end = end; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOG_REQUEST_LIST UNPACKING + + +/** + * @brief Get field target_system from log_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_log_request_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from log_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_log_request_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field start from log_request_list message + * + * @return First log id (0 for first available) + */ +static inline uint16_t mavlink_msg_log_request_list_get_start(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field end from log_request_list message + * + * @return Last log id (0xffff for last available) + */ +static inline uint16_t mavlink_msg_log_request_list_get_end(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Decode a log_request_list message into a struct + * + * @param msg The message to decode + * @param log_request_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_request_list_decode(const mavlink_message_t* msg, mavlink_log_request_list_t* log_request_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_request_list->start = mavlink_msg_log_request_list_get_start(msg); + log_request_list->end = mavlink_msg_log_request_list_get_end(msg); + log_request_list->target_system = mavlink_msg_log_request_list_get_target_system(msg); + log_request_list->target_component = mavlink_msg_log_request_list_get_target_component(msg); +#else + memcpy(log_request_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_manual_control.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_manual_control.h new file mode 100644 index 0000000..69802bc --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_manual_control.h @@ -0,0 +1,329 @@ +// MESSAGE MANUAL_CONTROL PACKING + +#define MAVLINK_MSG_ID_MANUAL_CONTROL 69 + +typedef struct __mavlink_manual_control_t +{ + int16_t x; /*< X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.*/ + int16_t y; /*< Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.*/ + int16_t z; /*< Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.*/ + int16_t r; /*< R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.*/ + uint16_t buttons; /*< A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.*/ + uint8_t target; /*< The system to be controlled.*/ +} mavlink_manual_control_t; + +#define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 11 +#define MAVLINK_MSG_ID_69_LEN 11 + +#define MAVLINK_MSG_ID_MANUAL_CONTROL_CRC 243 +#define MAVLINK_MSG_ID_69_CRC 243 + + + +#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \ + "MANUAL_CONTROL", \ + 6, \ + { { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \ + { "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \ + { "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \ + { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \ + } \ +} + + +/** + * @brief Pack a manual_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target The system to be controlled. + * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN]; + _mav_put_int16_t(buf, 0, x); + _mav_put_int16_t(buf, 2, y); + _mav_put_int16_t(buf, 4, z); + _mav_put_int16_t(buf, 6, r); + _mav_put_uint16_t(buf, 8, buttons); + _mav_put_uint8_t(buf, 10, target); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#else + mavlink_manual_control_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.r = r; + packet.buttons = buttons; + packet.target = target; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif +} + +/** + * @brief Pack a manual_control message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target The system to be controlled. + * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target,int16_t x,int16_t y,int16_t z,int16_t r,uint16_t buttons) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN]; + _mav_put_int16_t(buf, 0, x); + _mav_put_int16_t(buf, 2, y); + _mav_put_int16_t(buf, 4, z); + _mav_put_int16_t(buf, 6, r); + _mav_put_uint16_t(buf, 8, buttons); + _mav_put_uint8_t(buf, 10, target); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#else + mavlink_manual_control_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.r = r; + packet.buttons = buttons; + packet.target = target; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif +} + +/** + * @brief Encode a manual_control struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param manual_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) +{ + return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons); +} + +/** + * @brief Encode a manual_control struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param manual_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_manual_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) +{ + return mavlink_msg_manual_control_pack_chan(system_id, component_id, chan, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons); +} + +/** + * @brief Send a manual_control message + * @param chan MAVLink channel to send the message + * + * @param target The system to be controlled. + * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN]; + _mav_put_int16_t(buf, 0, x); + _mav_put_int16_t(buf, 2, y); + _mav_put_int16_t(buf, 4, z); + _mav_put_int16_t(buf, 6, r); + _mav_put_uint16_t(buf, 8, buttons); + _mav_put_uint8_t(buf, 10, target); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif +#else + mavlink_manual_control_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.r = r; + packet.buttons = buttons; + packet.target = target; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MANUAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_manual_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int16_t(buf, 0, x); + _mav_put_int16_t(buf, 2, y); + _mav_put_int16_t(buf, 4, z); + _mav_put_int16_t(buf, 6, r); + _mav_put_uint16_t(buf, 8, buttons); + _mav_put_uint8_t(buf, 10, target); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif +#else + mavlink_manual_control_t *packet = (mavlink_manual_control_t *)msgbuf; + packet->x = x; + packet->y = y; + packet->z = z; + packet->r = r; + packet->buttons = buttons; + packet->target = target; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MANUAL_CONTROL UNPACKING + + +/** + * @brief Get field target from manual_control message + * + * @return The system to be controlled. + */ +static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 10); +} + +/** + * @brief Get field x from manual_control message + * + * @return X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + */ +static inline int16_t mavlink_msg_manual_control_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Get field y from manual_control message + * + * @return Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + */ +static inline int16_t mavlink_msg_manual_control_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 2); +} + +/** + * @brief Get field z from manual_control message + * + * @return Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + */ +static inline int16_t mavlink_msg_manual_control_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Get field r from manual_control message + * + * @return R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + */ +static inline int16_t mavlink_msg_manual_control_get_r(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 6); +} + +/** + * @brief Get field buttons from manual_control message + * + * @return A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + */ +static inline uint16_t mavlink_msg_manual_control_get_buttons(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Decode a manual_control message into a struct + * + * @param msg The message to decode + * @param manual_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + manual_control->x = mavlink_msg_manual_control_get_x(msg); + manual_control->y = mavlink_msg_manual_control_get_y(msg); + manual_control->z = mavlink_msg_manual_control_get_z(msg); + manual_control->r = mavlink_msg_manual_control_get_r(msg); + manual_control->buttons = mavlink_msg_manual_control_get_buttons(msg); + manual_control->target = mavlink_msg_manual_control_get_target(msg); +#else + memcpy(manual_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h new file mode 100644 index 0000000..dcb0ed0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h @@ -0,0 +1,353 @@ +// MESSAGE MANUAL_SETPOINT PACKING + +#define MAVLINK_MSG_ID_MANUAL_SETPOINT 81 + +typedef struct __mavlink_manual_setpoint_t +{ + uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ + float roll; /*< Desired roll rate in radians per second*/ + float pitch; /*< Desired pitch rate in radians per second*/ + float yaw; /*< Desired yaw rate in radians per second*/ + float thrust; /*< Collective thrust, normalized to 0 .. 1*/ + uint8_t mode_switch; /*< Flight mode switch position, 0.. 255*/ + uint8_t manual_override_switch; /*< Override mode switch position, 0.. 255*/ +} mavlink_manual_setpoint_t; + +#define MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22 +#define MAVLINK_MSG_ID_81_LEN 22 + +#define MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC 106 +#define MAVLINK_MSG_ID_81_CRC 106 + + + +#define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT { \ + "MANUAL_SETPOINT", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_manual_setpoint_t, time_boot_ms) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_setpoint_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_setpoint_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_setpoint_t, yaw) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_manual_setpoint_t, thrust) }, \ + { "mode_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_setpoint_t, mode_switch) }, \ + { "manual_override_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_manual_setpoint_t, manual_override_switch) }, \ + } \ +} + + +/** + * @brief Pack a manual_setpoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll Desired roll rate in radians per second + * @param pitch Desired pitch rate in radians per second + * @param yaw Desired yaw rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 + * @param mode_switch Flight mode switch position, 0.. 255 + * @param manual_override_switch Override mode switch position, 0.. 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + _mav_put_uint8_t(buf, 20, mode_switch); + _mav_put_uint8_t(buf, 21, manual_override_switch); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#else + mavlink_manual_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.mode_switch = mode_switch; + packet.manual_override_switch = manual_override_switch; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif +} + +/** + * @brief Pack a manual_setpoint message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll Desired roll rate in radians per second + * @param pitch Desired pitch rate in radians per second + * @param yaw Desired yaw rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 + * @param mode_switch Flight mode switch position, 0.. 255 + * @param manual_override_switch Override mode switch position, 0.. 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float roll,float pitch,float yaw,float thrust,uint8_t mode_switch,uint8_t manual_override_switch) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + _mav_put_uint8_t(buf, 20, mode_switch); + _mav_put_uint8_t(buf, 21, manual_override_switch); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#else + mavlink_manual_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.mode_switch = mode_switch; + packet.manual_override_switch = manual_override_switch; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif +} + +/** + * @brief Encode a manual_setpoint struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param manual_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_manual_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint) +{ + return mavlink_msg_manual_setpoint_pack(system_id, component_id, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); +} + +/** + * @brief Encode a manual_setpoint struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param manual_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_manual_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint) +{ + return mavlink_msg_manual_setpoint_pack_chan(system_id, component_id, chan, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); +} + +/** + * @brief Send a manual_setpoint message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll Desired roll rate in radians per second + * @param pitch Desired pitch rate in radians per second + * @param yaw Desired yaw rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 + * @param mode_switch Flight mode switch position, 0.. 255 + * @param manual_override_switch Override mode switch position, 0.. 255 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_manual_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + _mav_put_uint8_t(buf, 20, mode_switch); + _mav_put_uint8_t(buf, 21, manual_override_switch); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif +#else + mavlink_manual_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.mode_switch = mode_switch; + packet.manual_override_switch = manual_override_switch; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_manual_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + _mav_put_uint8_t(buf, 20, mode_switch); + _mav_put_uint8_t(buf, 21, manual_override_switch); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif +#else + mavlink_manual_setpoint_t *packet = (mavlink_manual_setpoint_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + packet->thrust = thrust; + packet->mode_switch = mode_switch; + packet->manual_override_switch = manual_override_switch; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MANUAL_SETPOINT UNPACKING + + +/** + * @brief Get field time_boot_ms from manual_setpoint message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field roll from manual_setpoint message + * + * @return Desired roll rate in radians per second + */ +static inline float mavlink_msg_manual_setpoint_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field pitch from manual_setpoint message + * + * @return Desired pitch rate in radians per second + */ +static inline float mavlink_msg_manual_setpoint_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from manual_setpoint message + * + * @return Desired yaw rate in radians per second + */ +static inline float mavlink_msg_manual_setpoint_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field thrust from manual_setpoint message + * + * @return Collective thrust, normalized to 0 .. 1 + */ +static inline float mavlink_msg_manual_setpoint_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field mode_switch from manual_setpoint message + * + * @return Flight mode switch position, 0.. 255 + */ +static inline uint8_t mavlink_msg_manual_setpoint_get_mode_switch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field manual_override_switch from manual_setpoint message + * + * @return Override mode switch position, 0.. 255 + */ +static inline uint8_t mavlink_msg_manual_setpoint_get_manual_override_switch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 21); +} + +/** + * @brief Decode a manual_setpoint message into a struct + * + * @param msg The message to decode + * @param manual_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_manual_setpoint_decode(const mavlink_message_t* msg, mavlink_manual_setpoint_t* manual_setpoint) +{ +#if MAVLINK_NEED_BYTE_SWAP + manual_setpoint->time_boot_ms = mavlink_msg_manual_setpoint_get_time_boot_ms(msg); + manual_setpoint->roll = mavlink_msg_manual_setpoint_get_roll(msg); + manual_setpoint->pitch = mavlink_msg_manual_setpoint_get_pitch(msg); + manual_setpoint->yaw = mavlink_msg_manual_setpoint_get_yaw(msg); + manual_setpoint->thrust = mavlink_msg_manual_setpoint_get_thrust(msg); + manual_setpoint->mode_switch = mavlink_msg_manual_setpoint_get_mode_switch(msg); + manual_setpoint->manual_override_switch = mavlink_msg_manual_setpoint_get_manual_override_switch(msg); +#else + memcpy(manual_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_memory_vect.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_memory_vect.h new file mode 100644 index 0000000..bf63bc5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_memory_vect.h @@ -0,0 +1,273 @@ +// MESSAGE MEMORY_VECT PACKING + +#define MAVLINK_MSG_ID_MEMORY_VECT 249 + +typedef struct __mavlink_memory_vect_t +{ + uint16_t address; /*< Starting address of the debug variables*/ + uint8_t ver; /*< Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below*/ + uint8_t type; /*< Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14*/ + int8_t value[32]; /*< Memory contents at specified address*/ +} mavlink_memory_vect_t; + +#define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36 +#define MAVLINK_MSG_ID_249_LEN 36 + +#define MAVLINK_MSG_ID_MEMORY_VECT_CRC 204 +#define MAVLINK_MSG_ID_249_CRC 204 + +#define MAVLINK_MSG_MEMORY_VECT_FIELD_VALUE_LEN 32 + +#define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \ + "MEMORY_VECT", \ + 4, \ + { { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \ + { "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \ + { "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \ + } \ +} + + +/** + * @brief Pack a memory_vect message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param address Starting address of the debug variables + * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @param value Memory contents at specified address + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN]; + _mav_put_uint16_t(buf, 0, address); + _mav_put_uint8_t(buf, 2, ver); + _mav_put_uint8_t(buf, 3, type); + _mav_put_int8_t_array(buf, 4, value, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#else + mavlink_memory_vect_t packet; + packet.address = address; + packet.ver = ver; + packet.type = type; + mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif +} + +/** + * @brief Pack a memory_vect message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param address Starting address of the debug variables + * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @param value Memory contents at specified address + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t address,uint8_t ver,uint8_t type,const int8_t *value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN]; + _mav_put_uint16_t(buf, 0, address); + _mav_put_uint8_t(buf, 2, ver); + _mav_put_uint8_t(buf, 3, type); + _mav_put_int8_t_array(buf, 4, value, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#else + mavlink_memory_vect_t packet; + packet.address = address; + packet.ver = ver; + packet.type = type; + mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif +} + +/** + * @brief Encode a memory_vect struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param memory_vect C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_memory_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect) +{ + return mavlink_msg_memory_vect_pack(system_id, component_id, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); +} + +/** + * @brief Encode a memory_vect struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param memory_vect C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_memory_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect) +{ + return mavlink_msg_memory_vect_pack_chan(system_id, component_id, chan, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); +} + +/** + * @brief Send a memory_vect message + * @param chan MAVLink channel to send the message + * + * @param address Starting address of the debug variables + * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @param value Memory contents at specified address + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_memory_vect_send(mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN]; + _mav_put_uint16_t(buf, 0, address); + _mav_put_uint8_t(buf, 2, ver); + _mav_put_uint8_t(buf, 3, type); + _mav_put_int8_t_array(buf, 4, value, 32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif +#else + mavlink_memory_vect_t packet; + packet.address = address; + packet.ver = ver; + packet.type = type; + mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MEMORY_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_memory_vect_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, address); + _mav_put_uint8_t(buf, 2, ver); + _mav_put_uint8_t(buf, 3, type); + _mav_put_int8_t_array(buf, 4, value, 32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif +#else + mavlink_memory_vect_t *packet = (mavlink_memory_vect_t *)msgbuf; + packet->address = address; + packet->ver = ver; + packet->type = type; + mav_array_memcpy(packet->value, value, sizeof(int8_t)*32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MEMORY_VECT UNPACKING + + +/** + * @brief Get field address from memory_vect message + * + * @return Starting address of the debug variables + */ +static inline uint16_t mavlink_msg_memory_vect_get_address(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field ver from memory_vect message + * + * @return Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + */ +static inline uint8_t mavlink_msg_memory_vect_get_ver(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field type from memory_vect message + * + * @return Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + */ +static inline uint8_t mavlink_msg_memory_vect_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field value from memory_vect message + * + * @return Memory contents at specified address + */ +static inline uint16_t mavlink_msg_memory_vect_get_value(const mavlink_message_t* msg, int8_t *value) +{ + return _MAV_RETURN_int8_t_array(msg, value, 32, 4); +} + +/** + * @brief Decode a memory_vect message into a struct + * + * @param msg The message to decode + * @param memory_vect C-struct to decode the message contents into + */ +static inline void mavlink_msg_memory_vect_decode(const mavlink_message_t* msg, mavlink_memory_vect_t* memory_vect) +{ +#if MAVLINK_NEED_BYTE_SWAP + memory_vect->address = mavlink_msg_memory_vect_get_address(msg); + memory_vect->ver = mavlink_msg_memory_vect_get_ver(msg); + memory_vect->type = mavlink_msg_memory_vect_get_type(msg); + mavlink_msg_memory_vect_get_value(msg, memory_vect->value); +#else + memcpy(memory_vect, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_message_interval.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_message_interval.h new file mode 100644 index 0000000..32c26be --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_message_interval.h @@ -0,0 +1,233 @@ +// MESSAGE MESSAGE_INTERVAL PACKING + +#define MAVLINK_MSG_ID_MESSAGE_INTERVAL 244 + +typedef struct __mavlink_message_interval_t +{ + int32_t interval_us; /*< The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.*/ + uint16_t message_id; /*< The ID of the requested MAVLink message. v1.0 is limited to 254 messages.*/ +} mavlink_message_interval_t; + +#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN 6 +#define MAVLINK_MSG_ID_244_LEN 6 + +#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC 95 +#define MAVLINK_MSG_ID_244_CRC 95 + + + +#define MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL { \ + "MESSAGE_INTERVAL", \ + 2, \ + { { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \ + { "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \ + } \ +} + + +/** + * @brief Pack a message_interval message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + * @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_message_interval_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t message_id, int32_t interval_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN]; + _mav_put_int32_t(buf, 0, interval_us); + _mav_put_uint16_t(buf, 4, message_id); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#else + mavlink_message_interval_t packet; + packet.interval_us = interval_us; + packet.message_id = message_id; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MESSAGE_INTERVAL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif +} + +/** + * @brief Pack a message_interval message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + * @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_message_interval_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t message_id,int32_t interval_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN]; + _mav_put_int32_t(buf, 0, interval_us); + _mav_put_uint16_t(buf, 4, message_id); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#else + mavlink_message_interval_t packet; + packet.interval_us = interval_us; + packet.message_id = message_id; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MESSAGE_INTERVAL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif +} + +/** + * @brief Encode a message_interval struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param message_interval C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_message_interval_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_message_interval_t* message_interval) +{ + return mavlink_msg_message_interval_pack(system_id, component_id, msg, message_interval->message_id, message_interval->interval_us); +} + +/** + * @brief Encode a message_interval struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param message_interval C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_message_interval_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_message_interval_t* message_interval) +{ + return mavlink_msg_message_interval_pack_chan(system_id, component_id, chan, msg, message_interval->message_id, message_interval->interval_us); +} + +/** + * @brief Send a message_interval message + * @param chan MAVLink channel to send the message + * + * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + * @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_message_interval_send(mavlink_channel_t chan, uint16_t message_id, int32_t interval_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN]; + _mav_put_int32_t(buf, 0, interval_us); + _mav_put_uint16_t(buf, 4, message_id); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif +#else + mavlink_message_interval_t packet; + packet.interval_us = interval_us; + packet.message_id = message_id; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)&packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)&packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_message_interval_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t message_id, int32_t interval_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, interval_us); + _mav_put_uint16_t(buf, 4, message_id); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif +#else + mavlink_message_interval_t *packet = (mavlink_message_interval_t *)msgbuf; + packet->interval_us = interval_us; + packet->message_id = message_id; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MESSAGE_INTERVAL UNPACKING + + +/** + * @brief Get field message_id from message_interval message + * + * @return The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + */ +static inline uint16_t mavlink_msg_message_interval_get_message_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field interval_us from message_interval message + * + * @return The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + */ +static inline int32_t mavlink_msg_message_interval_get_interval_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Decode a message_interval message into a struct + * + * @param msg The message to decode + * @param message_interval C-struct to decode the message contents into + */ +static inline void mavlink_msg_message_interval_decode(const mavlink_message_t* msg, mavlink_message_interval_t* message_interval) +{ +#if MAVLINK_NEED_BYTE_SWAP + message_interval->interval_us = mavlink_msg_message_interval_get_interval_us(msg); + message_interval->message_id = mavlink_msg_message_interval_get_message_id(msg); +#else + memcpy(message_interval, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_ack.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_ack.h new file mode 100644 index 0000000..357b3aa --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_ack.h @@ -0,0 +1,257 @@ +// MESSAGE MISSION_ACK PACKING + +#define MAVLINK_MSG_ID_MISSION_ACK 47 + +typedef struct __mavlink_mission_ack_t +{ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t type; /*< See MAV_MISSION_RESULT enum*/ +} mavlink_mission_ack_t; + +#define MAVLINK_MSG_ID_MISSION_ACK_LEN 3 +#define MAVLINK_MSG_ID_47_LEN 3 + +#define MAVLINK_MSG_ID_MISSION_ACK_CRC 153 +#define MAVLINK_MSG_ID_47_CRC 153 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_ACK { \ + "MISSION_ACK", \ + 3, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_ack_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_ack_t, target_component) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_ack_t, type) }, \ + } \ +} + + +/** + * @brief Pack a mission_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param type See MAV_MISSION_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ACK_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#else + mavlink_mission_ack_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type = type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif +} + +/** + * @brief Pack a mission_ack message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param type See MAV_MISSION_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ACK_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#else + mavlink_mission_ack_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type = type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif +} + +/** + * @brief Encode a mission_ack struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack) +{ + return mavlink_msg_mission_ack_pack(system_id, component_id, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type); +} + +/** + * @brief Encode a mission_ack struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack) +{ + return mavlink_msg_mission_ack_pack_chan(system_id, component_id, chan, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type); +} + +/** + * @brief Send a mission_ack message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param type See MAV_MISSION_RESULT enum + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ACK_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif +#else + mavlink_mission_ack_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type = type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif +#else + mavlink_mission_ack_t *packet = (mavlink_mission_ack_t *)msgbuf; + packet->target_system = target_system; + packet->target_component = target_component; + packet->type = type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)packet, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_ACK UNPACKING + + +/** + * @brief Get field target_system from mission_ack message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_ack_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from mission_ack message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_ack_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field type from mission_ack message + * + * @return See MAV_MISSION_RESULT enum + */ +static inline uint8_t mavlink_msg_mission_ack_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a mission_ack message into a struct + * + * @param msg The message to decode + * @param mission_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_ack_decode(const mavlink_message_t* msg, mavlink_mission_ack_t* mission_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_ack->target_system = mavlink_msg_mission_ack_get_target_system(msg); + mission_ack->target_component = mavlink_msg_mission_ack_get_target_component(msg); + mission_ack->type = mavlink_msg_mission_ack_get_type(msg); +#else + memcpy(mission_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h new file mode 100644 index 0000000..32c065a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h @@ -0,0 +1,233 @@ +// MESSAGE MISSION_CLEAR_ALL PACKING + +#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL 45 + +typedef struct __mavlink_mission_clear_all_t +{ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_clear_all_t; + +#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 2 +#define MAVLINK_MSG_ID_45_LEN 2 + +#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC 232 +#define MAVLINK_MSG_ID_45_CRC 232 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \ + "MISSION_CLEAR_ALL", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_clear_all_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_clear_all_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_clear_all message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#else + mavlink_mission_clear_all_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif +} + +/** + * @brief Pack a mission_clear_all message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_clear_all_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#else + mavlink_mission_clear_all_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif +} + +/** + * @brief Encode a mission_clear_all struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_clear_all C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all) +{ + return mavlink_msg_mission_clear_all_pack(system_id, component_id, msg, mission_clear_all->target_system, mission_clear_all->target_component); +} + +/** + * @brief Encode a mission_clear_all struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_clear_all C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_clear_all_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all) +{ + return mavlink_msg_mission_clear_all_pack_chan(system_id, component_id, chan, msg, mission_clear_all->target_system, mission_clear_all->target_component); +} + +/** + * @brief Send a mission_clear_all message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif +#else + mavlink_mission_clear_all_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_clear_all_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif +#else + mavlink_mission_clear_all_t *packet = (mavlink_mission_clear_all_t *)msgbuf; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_CLEAR_ALL UNPACKING + + +/** + * @brief Get field target_system from mission_clear_all message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_clear_all_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from mission_clear_all message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_clear_all_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a mission_clear_all message into a struct + * + * @param msg The message to decode + * @param mission_clear_all C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_clear_all_decode(const mavlink_message_t* msg, mavlink_mission_clear_all_t* mission_clear_all) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_clear_all->target_system = mavlink_msg_mission_clear_all_get_target_system(msg); + mission_clear_all->target_component = mavlink_msg_mission_clear_all_get_target_component(msg); +#else + memcpy(mission_clear_all, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_count.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_count.h new file mode 100644 index 0000000..991a2c2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_count.h @@ -0,0 +1,257 @@ +// MESSAGE MISSION_COUNT PACKING + +#define MAVLINK_MSG_ID_MISSION_COUNT 44 + +typedef struct __mavlink_mission_count_t +{ + uint16_t count; /*< Number of mission items in the sequence*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_count_t; + +#define MAVLINK_MSG_ID_MISSION_COUNT_LEN 4 +#define MAVLINK_MSG_ID_44_LEN 4 + +#define MAVLINK_MSG_ID_MISSION_COUNT_CRC 221 +#define MAVLINK_MSG_ID_44_CRC 221 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \ + "MISSION_COUNT", \ + 3, \ + { { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_count message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param count Number of mission items in the sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN]; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#else + mavlink_mission_count_t packet; + packet.count = count; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif +} + +/** + * @brief Pack a mission_count message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param count Number of mission items in the sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN]; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#else + mavlink_mission_count_t packet; + packet.count = count; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif +} + +/** + * @brief Encode a mission_count struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_count C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count) +{ + return mavlink_msg_mission_count_pack(system_id, component_id, msg, mission_count->target_system, mission_count->target_component, mission_count->count); +} + +/** + * @brief Encode a mission_count struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_count C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_count_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count) +{ + return mavlink_msg_mission_count_pack_chan(system_id, component_id, chan, msg, mission_count->target_system, mission_count->target_component, mission_count->count); +} + +/** + * @brief Send a mission_count message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param count Number of mission items in the sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN]; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif +#else + mavlink_mission_count_t packet; + packet.count = count; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_COUNT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_count_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif +#else + mavlink_mission_count_t *packet = (mavlink_mission_count_t *)msgbuf; + packet->count = count; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_COUNT UNPACKING + + +/** + * @brief Get field target_system from mission_count message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_count_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from mission_count message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_count_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field count from mission_count message + * + * @return Number of mission items in the sequence + */ +static inline uint16_t mavlink_msg_mission_count_get_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_count message into a struct + * + * @param msg The message to decode + * @param mission_count C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_count_decode(const mavlink_message_t* msg, mavlink_mission_count_t* mission_count) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_count->count = mavlink_msg_mission_count_get_count(msg); + mission_count->target_system = mavlink_msg_mission_count_get_target_system(msg); + mission_count->target_component = mavlink_msg_mission_count_get_target_component(msg); +#else + memcpy(mission_count, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_current.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_current.h new file mode 100644 index 0000000..942d02f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_current.h @@ -0,0 +1,209 @@ +// MESSAGE MISSION_CURRENT PACKING + +#define MAVLINK_MSG_ID_MISSION_CURRENT 42 + +typedef struct __mavlink_mission_current_t +{ + uint16_t seq; /*< Sequence*/ +} mavlink_mission_current_t; + +#define MAVLINK_MSG_ID_MISSION_CURRENT_LEN 2 +#define MAVLINK_MSG_ID_42_LEN 2 + +#define MAVLINK_MSG_ID_MISSION_CURRENT_CRC 28 +#define MAVLINK_MSG_ID_42_CRC 28 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \ + "MISSION_CURRENT", \ + 1, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \ + } \ +} + + +/** + * @brief Pack a mission_current message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#else + mavlink_mission_current_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif +} + +/** + * @brief Pack a mission_current message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#else + mavlink_mission_current_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif +} + +/** + * @brief Encode a mission_current struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current) +{ + return mavlink_msg_mission_current_pack(system_id, component_id, msg, mission_current->seq); +} + +/** + * @brief Encode a mission_current struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current) +{ + return mavlink_msg_mission_current_pack_chan(system_id, component_id, chan, msg, mission_current->seq); +} + +/** + * @brief Send a mission_current message + * @param chan MAVLink channel to send the message + * + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_current_send(mavlink_channel_t chan, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif +#else + mavlink_mission_current_t packet; + packet.seq = seq; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_current_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, seq); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif +#else + mavlink_mission_current_t *packet = (mavlink_mission_current_t *)msgbuf; + packet->seq = seq; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_CURRENT UNPACKING + + +/** + * @brief Get field seq from mission_current message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_current_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_current message into a struct + * + * @param msg The message to decode + * @param mission_current C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_current_decode(const mavlink_message_t* msg, mavlink_mission_current_t* mission_current) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_current->seq = mavlink_msg_mission_current_get_seq(msg); +#else + memcpy(mission_current, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_item.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_item.h new file mode 100644 index 0000000..367c265 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_item.h @@ -0,0 +1,521 @@ +// MESSAGE MISSION_ITEM PACKING + +#define MAVLINK_MSG_ID_MISSION_ITEM 39 + +typedef struct __mavlink_mission_item_t +{ + float param1; /*< PARAM1, see MAV_CMD enum*/ + float param2; /*< PARAM2, see MAV_CMD enum*/ + float param3; /*< PARAM3, see MAV_CMD enum*/ + float param4; /*< PARAM4, see MAV_CMD enum*/ + float x; /*< PARAM5 / local: x position, global: latitude*/ + float y; /*< PARAM6 / y position: global: longitude*/ + float z; /*< PARAM7 / z position: global: altitude (relative or absolute, depending on frame.*/ + uint16_t seq; /*< Sequence*/ + uint16_t command; /*< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t frame; /*< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h*/ + uint8_t current; /*< false:0, true:1*/ + uint8_t autocontinue; /*< autocontinue to next wp*/ +} mavlink_mission_item_t; + +#define MAVLINK_MSG_ID_MISSION_ITEM_LEN 37 +#define MAVLINK_MSG_ID_39_LEN 37 + +#define MAVLINK_MSG_ID_MISSION_ITEM_CRC 254 +#define MAVLINK_MSG_ID_39_CRC 254 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \ + "MISSION_ITEM", \ + 14, \ + { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \ + } \ +} + + +/** + * @brief Pack a mission_item message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#else + mavlink_mission_item_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif +} + +/** + * @brief Pack a mission_item message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,float x,float y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#else + mavlink_mission_item_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif +} + +/** + * @brief Encode a mission_item struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_item C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item) +{ + return mavlink_msg_mission_item_pack(system_id, component_id, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z); +} + +/** + * @brief Encode a mission_item struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_item C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item) +{ + return mavlink_msg_mission_item_pack_chan(system_id, component_id, chan, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z); +} + +/** + * @brief Send a mission_item message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_item_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif +#else + mavlink_mission_item_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_ITEM_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_item_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif +#else + mavlink_mission_item_t *packet = (mavlink_mission_item_t *)msgbuf; + packet->param1 = param1; + packet->param2 = param2; + packet->param3 = param3; + packet->param4 = param4; + packet->x = x; + packet->y = y; + packet->z = z; + packet->seq = seq; + packet->command = command; + packet->target_system = target_system; + packet->target_component = target_component; + packet->frame = frame; + packet->current = current; + packet->autocontinue = autocontinue; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_ITEM UNPACKING + + +/** + * @brief Get field target_system from mission_item message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_item_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field target_component from mission_item message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_item_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field seq from mission_item message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_item_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field frame from mission_item message + * + * @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + */ +static inline uint8_t mavlink_msg_mission_item_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field command from mission_item message + * + * @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + */ +static inline uint16_t mavlink_msg_mission_item_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 30); +} + +/** + * @brief Get field current from mission_item message + * + * @return false:0, true:1 + */ +static inline uint8_t mavlink_msg_mission_item_get_current(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 35); +} + +/** + * @brief Get field autocontinue from mission_item message + * + * @return autocontinue to next wp + */ +static inline uint8_t mavlink_msg_mission_item_get_autocontinue(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Get field param1 from mission_item message + * + * @return PARAM1, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_get_param1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param2 from mission_item message + * + * @return PARAM2, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_get_param2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param3 from mission_item message + * + * @return PARAM3, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_get_param3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param4 from mission_item message + * + * @return PARAM4, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_get_param4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field x from mission_item message + * + * @return PARAM5 / local: x position, global: latitude + */ +static inline float mavlink_msg_mission_item_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field y from mission_item message + * + * @return PARAM6 / y position: global: longitude + */ +static inline float mavlink_msg_mission_item_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field z from mission_item message + * + * @return PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + */ +static inline float mavlink_msg_mission_item_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a mission_item message into a struct + * + * @param msg The message to decode + * @param mission_item C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_item_decode(const mavlink_message_t* msg, mavlink_mission_item_t* mission_item) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_item->param1 = mavlink_msg_mission_item_get_param1(msg); + mission_item->param2 = mavlink_msg_mission_item_get_param2(msg); + mission_item->param3 = mavlink_msg_mission_item_get_param3(msg); + mission_item->param4 = mavlink_msg_mission_item_get_param4(msg); + mission_item->x = mavlink_msg_mission_item_get_x(msg); + mission_item->y = mavlink_msg_mission_item_get_y(msg); + mission_item->z = mavlink_msg_mission_item_get_z(msg); + mission_item->seq = mavlink_msg_mission_item_get_seq(msg); + mission_item->command = mavlink_msg_mission_item_get_command(msg); + mission_item->target_system = mavlink_msg_mission_item_get_target_system(msg); + mission_item->target_component = mavlink_msg_mission_item_get_target_component(msg); + mission_item->frame = mavlink_msg_mission_item_get_frame(msg); + mission_item->current = mavlink_msg_mission_item_get_current(msg); + mission_item->autocontinue = mavlink_msg_mission_item_get_autocontinue(msg); +#else + memcpy(mission_item, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_item_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_item_int.h new file mode 100644 index 0000000..8d824be --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_item_int.h @@ -0,0 +1,521 @@ +// MESSAGE MISSION_ITEM_INT PACKING + +#define MAVLINK_MSG_ID_MISSION_ITEM_INT 73 + +typedef struct __mavlink_mission_item_int_t +{ + float param1; /*< PARAM1, see MAV_CMD enum*/ + float param2; /*< PARAM2, see MAV_CMD enum*/ + float param3; /*< PARAM3, see MAV_CMD enum*/ + float param4; /*< PARAM4, see MAV_CMD enum*/ + int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/ + int32_t y; /*< PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7*/ + float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/ + uint16_t seq; /*< Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).*/ + uint16_t command; /*< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t frame; /*< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h*/ + uint8_t current; /*< false:0, true:1*/ + uint8_t autocontinue; /*< autocontinue to next wp*/ +} mavlink_mission_item_int_t; + +#define MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN 37 +#define MAVLINK_MSG_ID_73_LEN 37 + +#define MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC 38 +#define MAVLINK_MSG_ID_73_CRC 38 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \ + "MISSION_ITEM_INT", \ + 14, \ + { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \ + { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \ + } \ +} + + +/** + * @brief Pack a mission_item_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#else + mavlink_mission_item_int_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif +} + +/** + * @brief Pack a mission_item_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,int32_t x,int32_t y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#else + mavlink_mission_item_int_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif +} + +/** + * @brief Encode a mission_item_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_item_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int) +{ + return mavlink_msg_mission_item_int_pack(system_id, component_id, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z); +} + +/** + * @brief Encode a mission_item_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_item_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int) +{ + return mavlink_msg_mission_item_int_pack_chan(system_id, component_id, chan, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z); +} + +/** + * @brief Send a mission_item_int message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_item_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif +#else + mavlink_mission_item_int_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_item_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif +#else + mavlink_mission_item_int_t *packet = (mavlink_mission_item_int_t *)msgbuf; + packet->param1 = param1; + packet->param2 = param2; + packet->param3 = param3; + packet->param4 = param4; + packet->x = x; + packet->y = y; + packet->z = z; + packet->seq = seq; + packet->command = command; + packet->target_system = target_system; + packet->target_component = target_component; + packet->frame = frame; + packet->current = current; + packet->autocontinue = autocontinue; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_ITEM_INT UNPACKING + + +/** + * @brief Get field target_system from mission_item_int message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_item_int_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field target_component from mission_item_int message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_item_int_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field seq from mission_item_int message + * + * @return Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + */ +static inline uint16_t mavlink_msg_mission_item_int_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field frame from mission_item_int message + * + * @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + */ +static inline uint8_t mavlink_msg_mission_item_int_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field command from mission_item_int message + * + * @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + */ +static inline uint16_t mavlink_msg_mission_item_int_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 30); +} + +/** + * @brief Get field current from mission_item_int message + * + * @return false:0, true:1 + */ +static inline uint8_t mavlink_msg_mission_item_int_get_current(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 35); +} + +/** + * @brief Get field autocontinue from mission_item_int message + * + * @return autocontinue to next wp + */ +static inline uint8_t mavlink_msg_mission_item_int_get_autocontinue(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Get field param1 from mission_item_int message + * + * @return PARAM1, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_int_get_param1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param2 from mission_item_int message + * + * @return PARAM2, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_int_get_param2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param3 from mission_item_int message + * + * @return PARAM3, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_int_get_param3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param4 from mission_item_int message + * + * @return PARAM4, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_int_get_param4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field x from mission_item_int message + * + * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + */ +static inline int32_t mavlink_msg_mission_item_int_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field y from mission_item_int message + * + * @return PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + */ +static inline int32_t mavlink_msg_mission_item_int_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 20); +} + +/** + * @brief Get field z from mission_item_int message + * + * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + */ +static inline float mavlink_msg_mission_item_int_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a mission_item_int message into a struct + * + * @param msg The message to decode + * @param mission_item_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_item_int_decode(const mavlink_message_t* msg, mavlink_mission_item_int_t* mission_item_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_item_int->param1 = mavlink_msg_mission_item_int_get_param1(msg); + mission_item_int->param2 = mavlink_msg_mission_item_int_get_param2(msg); + mission_item_int->param3 = mavlink_msg_mission_item_int_get_param3(msg); + mission_item_int->param4 = mavlink_msg_mission_item_int_get_param4(msg); + mission_item_int->x = mavlink_msg_mission_item_int_get_x(msg); + mission_item_int->y = mavlink_msg_mission_item_int_get_y(msg); + mission_item_int->z = mavlink_msg_mission_item_int_get_z(msg); + mission_item_int->seq = mavlink_msg_mission_item_int_get_seq(msg); + mission_item_int->command = mavlink_msg_mission_item_int_get_command(msg); + mission_item_int->target_system = mavlink_msg_mission_item_int_get_target_system(msg); + mission_item_int->target_component = mavlink_msg_mission_item_int_get_target_component(msg); + mission_item_int->frame = mavlink_msg_mission_item_int_get_frame(msg); + mission_item_int->current = mavlink_msg_mission_item_int_get_current(msg); + mission_item_int->autocontinue = mavlink_msg_mission_item_int_get_autocontinue(msg); +#else + memcpy(mission_item_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h new file mode 100644 index 0000000..88aa14c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h @@ -0,0 +1,209 @@ +// MESSAGE MISSION_ITEM_REACHED PACKING + +#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED 46 + +typedef struct __mavlink_mission_item_reached_t +{ + uint16_t seq; /*< Sequence*/ +} mavlink_mission_item_reached_t; + +#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN 2 +#define MAVLINK_MSG_ID_46_LEN 2 + +#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC 11 +#define MAVLINK_MSG_ID_46_CRC 11 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED { \ + "MISSION_ITEM_REACHED", \ + 1, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_item_reached_t, seq) }, \ + } \ +} + + +/** + * @brief Pack a mission_item_reached message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_reached_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#else + mavlink_mission_item_reached_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif +} + +/** + * @brief Pack a mission_item_reached message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#else + mavlink_mission_item_reached_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif +} + +/** + * @brief Encode a mission_item_reached struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_item_reached C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached) +{ + return mavlink_msg_mission_item_reached_pack(system_id, component_id, msg, mission_item_reached->seq); +} + +/** + * @brief Encode a mission_item_reached struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_item_reached C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_reached_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached) +{ + return mavlink_msg_mission_item_reached_pack_chan(system_id, component_id, chan, msg, mission_item_reached->seq); +} + +/** + * @brief Send a mission_item_reached message + * @param chan MAVLink channel to send the message + * + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_item_reached_send(mavlink_channel_t chan, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; + _mav_put_uint16_t(buf, 0, seq); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif +#else + mavlink_mission_item_reached_t packet; + packet.seq = seq; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_item_reached_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, seq); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif +#else + mavlink_mission_item_reached_t *packet = (mavlink_mission_item_reached_t *)msgbuf; + packet->seq = seq; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_ITEM_REACHED UNPACKING + + +/** + * @brief Get field seq from mission_item_reached message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_item_reached_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_item_reached message into a struct + * + * @param msg The message to decode + * @param mission_item_reached C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_item_reached_decode(const mavlink_message_t* msg, mavlink_mission_item_reached_t* mission_item_reached) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_item_reached->seq = mavlink_msg_mission_item_reached_get_seq(msg); +#else + memcpy(mission_item_reached, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_request.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_request.h new file mode 100644 index 0000000..d034047 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_request.h @@ -0,0 +1,257 @@ +// MESSAGE MISSION_REQUEST PACKING + +#define MAVLINK_MSG_ID_MISSION_REQUEST 40 + +typedef struct __mavlink_mission_request_t +{ + uint16_t seq; /*< Sequence*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_request_t; + +#define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4 +#define MAVLINK_MSG_ID_40_LEN 4 + +#define MAVLINK_MSG_ID_MISSION_REQUEST_CRC 230 +#define MAVLINK_MSG_ID_40_CRC 230 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \ + "MISSION_REQUEST", \ + 3, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_request message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#else + mavlink_mission_request_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif +} + +/** + * @brief Pack a mission_request message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#else + mavlink_mission_request_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif +} + +/** + * @brief Encode a mission_request struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request) +{ + return mavlink_msg_mission_request_pack(system_id, component_id, msg, mission_request->target_system, mission_request->target_component, mission_request->seq); +} + +/** + * @brief Encode a mission_request struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request) +{ + return mavlink_msg_mission_request_pack_chan(system_id, component_id, chan, msg, mission_request->target_system, mission_request->target_component, mission_request->seq); +} + +/** + * @brief Send a mission_request message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif +#else + mavlink_mission_request_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif +#else + mavlink_mission_request_t *packet = (mavlink_mission_request_t *)msgbuf; + packet->seq = seq; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_REQUEST UNPACKING + + +/** + * @brief Get field target_system from mission_request message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_request_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from mission_request message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_request_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field seq from mission_request message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_request_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_request message into a struct + * + * @param msg The message to decode + * @param mission_request C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_request_decode(const mavlink_message_t* msg, mavlink_mission_request_t* mission_request) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_request->seq = mavlink_msg_mission_request_get_seq(msg); + mission_request->target_system = mavlink_msg_mission_request_get_target_system(msg); + mission_request->target_component = mavlink_msg_mission_request_get_target_component(msg); +#else + memcpy(mission_request, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_request_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_request_int.h new file mode 100644 index 0000000..b44a486 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_request_int.h @@ -0,0 +1,257 @@ +// MESSAGE MISSION_REQUEST_INT PACKING + +#define MAVLINK_MSG_ID_MISSION_REQUEST_INT 51 + +typedef struct __mavlink_mission_request_int_t +{ + uint16_t seq; /*< Sequence*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_request_int_t; + +#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN 4 +#define MAVLINK_MSG_ID_51_LEN 4 + +#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC 196 +#define MAVLINK_MSG_ID_51_CRC 196 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT { \ + "MISSION_REQUEST_INT", \ + 3, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_request_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#else + mavlink_mission_request_int_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif +} + +/** + * @brief Pack a mission_request_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#else + mavlink_mission_request_int_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif +} + +/** + * @brief Encode a mission_request_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_request_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_int_t* mission_request_int) +{ + return mavlink_msg_mission_request_int_pack(system_id, component_id, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq); +} + +/** + * @brief Encode a mission_request_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_request_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_int_t* mission_request_int) +{ + return mavlink_msg_mission_request_int_pack_chan(system_id, component_id, chan, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq); +} + +/** + * @brief Send a mission_request_int message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_request_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif +#else + mavlink_mission_request_int_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_request_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif +#else + mavlink_mission_request_int_t *packet = (mavlink_mission_request_int_t *)msgbuf; + packet->seq = seq; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_REQUEST_INT UNPACKING + + +/** + * @brief Get field target_system from mission_request_int message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_request_int_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from mission_request_int message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_request_int_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field seq from mission_request_int message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_request_int_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_request_int message into a struct + * + * @param msg The message to decode + * @param mission_request_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_request_int_decode(const mavlink_message_t* msg, mavlink_mission_request_int_t* mission_request_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_request_int->seq = mavlink_msg_mission_request_int_get_seq(msg); + mission_request_int->target_system = mavlink_msg_mission_request_int_get_target_system(msg); + mission_request_int->target_component = mavlink_msg_mission_request_int_get_target_component(msg); +#else + memcpy(mission_request_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_request_list.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_request_list.h new file mode 100644 index 0000000..8ab2929 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_request_list.h @@ -0,0 +1,233 @@ +// MESSAGE MISSION_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST 43 + +typedef struct __mavlink_mission_request_list_t +{ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_request_list_t; + +#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 2 +#define MAVLINK_MSG_ID_43_LEN 2 + +#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC 132 +#define MAVLINK_MSG_ID_43_CRC 132 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST { \ + "MISSION_REQUEST_LIST", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_request_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_request_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_request_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#else + mavlink_mission_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif +} + +/** + * @brief Pack a mission_request_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#else + mavlink_mission_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif +} + +/** + * @brief Encode a mission_request_list struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list) +{ + return mavlink_msg_mission_request_list_pack(system_id, component_id, msg, mission_request_list->target_system, mission_request_list->target_component); +} + +/** + * @brief Encode a mission_request_list struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list) +{ + return mavlink_msg_mission_request_list_pack_chan(system_id, component_id, chan, msg, mission_request_list->target_system, mission_request_list->target_component); +} + +/** + * @brief Send a mission_request_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif +#else + mavlink_mission_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif +#else + mavlink_mission_request_list_t *packet = (mavlink_mission_request_list_t *)msgbuf; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_REQUEST_LIST UNPACKING + + +/** + * @brief Get field target_system from mission_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_request_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from mission_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_request_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a mission_request_list message into a struct + * + * @param msg The message to decode + * @param mission_request_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_request_list_decode(const mavlink_message_t* msg, mavlink_mission_request_list_t* mission_request_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_request_list->target_system = mavlink_msg_mission_request_list_get_target_system(msg); + mission_request_list->target_component = mavlink_msg_mission_request_list_get_target_component(msg); +#else + memcpy(mission_request_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h new file mode 100644 index 0000000..39d3cdf --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h @@ -0,0 +1,281 @@ +// MESSAGE MISSION_REQUEST_PARTIAL_LIST PACKING + +#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST 37 + +typedef struct __mavlink_mission_request_partial_list_t +{ + int16_t start_index; /*< Start index, 0 by default*/ + int16_t end_index; /*< End index, -1 by default (-1: send list to end). Else a valid index of the list*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_request_partial_list_t; + +#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 6 +#define MAVLINK_MSG_ID_37_LEN 6 + +#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC 212 +#define MAVLINK_MSG_ID_37_CRC 212 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \ + "MISSION_REQUEST_PARTIAL_LIST", \ + 4, \ + { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \ + { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_request_partial_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default + * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#else + mavlink_mission_request_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif +} + +/** + * @brief Pack a mission_request_partial_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default + * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#else + mavlink_mission_request_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif +} + +/** + * @brief Encode a mission_request_partial_list struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_request_partial_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list) +{ + return mavlink_msg_mission_request_partial_list_pack(system_id, component_id, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index); +} + +/** + * @brief Encode a mission_request_partial_list struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_request_partial_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list) +{ + return mavlink_msg_mission_request_partial_list_pack_chan(system_id, component_id, chan, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index); +} + +/** + * @brief Send a mission_request_partial_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default + * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_request_partial_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif +#else + mavlink_mission_request_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_request_partial_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif +#else + mavlink_mission_request_partial_list_t *packet = (mavlink_mission_request_partial_list_t *)msgbuf; + packet->start_index = start_index; + packet->end_index = end_index; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_REQUEST_PARTIAL_LIST UNPACKING + + +/** + * @brief Get field target_system from mission_request_partial_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from mission_request_partial_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field start_index from mission_request_partial_list message + * + * @return Start index, 0 by default + */ +static inline int16_t mavlink_msg_mission_request_partial_list_get_start_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Get field end_index from mission_request_partial_list message + * + * @return End index, -1 by default (-1: send list to end). Else a valid index of the list + */ +static inline int16_t mavlink_msg_mission_request_partial_list_get_end_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 2); +} + +/** + * @brief Decode a mission_request_partial_list message into a struct + * + * @param msg The message to decode + * @param mission_request_partial_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_request_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_request_partial_list_t* mission_request_partial_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_request_partial_list->start_index = mavlink_msg_mission_request_partial_list_get_start_index(msg); + mission_request_partial_list->end_index = mavlink_msg_mission_request_partial_list_get_end_index(msg); + mission_request_partial_list->target_system = mavlink_msg_mission_request_partial_list_get_target_system(msg); + mission_request_partial_list->target_component = mavlink_msg_mission_request_partial_list_get_target_component(msg); +#else + memcpy(mission_request_partial_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_set_current.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_set_current.h new file mode 100644 index 0000000..0934dad --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_set_current.h @@ -0,0 +1,257 @@ +// MESSAGE MISSION_SET_CURRENT PACKING + +#define MAVLINK_MSG_ID_MISSION_SET_CURRENT 41 + +typedef struct __mavlink_mission_set_current_t +{ + uint16_t seq; /*< Sequence*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_set_current_t; + +#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN 4 +#define MAVLINK_MSG_ID_41_LEN 4 + +#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC 28 +#define MAVLINK_MSG_ID_41_CRC 28 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT { \ + "MISSION_SET_CURRENT", \ + 3, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_set_current message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_set_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#else + mavlink_mission_set_current_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif +} + +/** + * @brief Pack a mission_set_current message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_set_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#else + mavlink_mission_set_current_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif +} + +/** + * @brief Encode a mission_set_current struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_set_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current) +{ + return mavlink_msg_mission_set_current_pack(system_id, component_id, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); +} + +/** + * @brief Encode a mission_set_current struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_set_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_set_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current) +{ + return mavlink_msg_mission_set_current_pack_chan(system_id, component_id, chan, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); +} + +/** + * @brief Send a mission_set_current message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_set_current_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif +#else + mavlink_mission_set_current_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_set_current_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif +#else + mavlink_mission_set_current_t *packet = (mavlink_mission_set_current_t *)msgbuf; + packet->seq = seq; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_SET_CURRENT UNPACKING + + +/** + * @brief Get field target_system from mission_set_current message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_set_current_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from mission_set_current message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_set_current_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field seq from mission_set_current message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_set_current_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_set_current message into a struct + * + * @param msg The message to decode + * @param mission_set_current C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_set_current_decode(const mavlink_message_t* msg, mavlink_mission_set_current_t* mission_set_current) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_set_current->seq = mavlink_msg_mission_set_current_get_seq(msg); + mission_set_current->target_system = mavlink_msg_mission_set_current_get_target_system(msg); + mission_set_current->target_component = mavlink_msg_mission_set_current_get_target_component(msg); +#else + memcpy(mission_set_current, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h new file mode 100644 index 0000000..8568c2b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h @@ -0,0 +1,281 @@ +// MESSAGE MISSION_WRITE_PARTIAL_LIST PACKING + +#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST 38 + +typedef struct __mavlink_mission_write_partial_list_t +{ + int16_t start_index; /*< Start index, 0 by default and smaller / equal to the largest index of the current onboard list.*/ + int16_t end_index; /*< End index, equal or greater than start index.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_write_partial_list_t; + +#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 6 +#define MAVLINK_MSG_ID_38_LEN 6 + +#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC 9 +#define MAVLINK_MSG_ID_38_CRC 9 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \ + "MISSION_WRITE_PARTIAL_LIST", \ + 4, \ + { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \ + { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_write_partial_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_write_partial_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + * @param end_index End index, equal or greater than start index. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#else + mavlink_mission_write_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif +} + +/** + * @brief Pack a mission_write_partial_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + * @param end_index End index, equal or greater than start index. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_write_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#else + mavlink_mission_write_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif +} + +/** + * @brief Encode a mission_write_partial_list struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_write_partial_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_write_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list) +{ + return mavlink_msg_mission_write_partial_list_pack(system_id, component_id, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index); +} + +/** + * @brief Encode a mission_write_partial_list struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_write_partial_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_write_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list) +{ + return mavlink_msg_mission_write_partial_list_pack_chan(system_id, component_id, chan, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index); +} + +/** + * @brief Send a mission_write_partial_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + * @param end_index End index, equal or greater than start index. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_write_partial_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif +#else + mavlink_mission_write_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_write_partial_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif +#else + mavlink_mission_write_partial_list_t *packet = (mavlink_mission_write_partial_list_t *)msgbuf; + packet->start_index = start_index; + packet->end_index = end_index; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_WRITE_PARTIAL_LIST UNPACKING + + +/** + * @brief Get field target_system from mission_write_partial_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from mission_write_partial_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field start_index from mission_write_partial_list message + * + * @return Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + */ +static inline int16_t mavlink_msg_mission_write_partial_list_get_start_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Get field end_index from mission_write_partial_list message + * + * @return End index, equal or greater than start index. + */ +static inline int16_t mavlink_msg_mission_write_partial_list_get_end_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 2); +} + +/** + * @brief Decode a mission_write_partial_list message into a struct + * + * @param msg The message to decode + * @param mission_write_partial_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_write_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_write_partial_list_t* mission_write_partial_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_write_partial_list->start_index = mavlink_msg_mission_write_partial_list_get_start_index(msg); + mission_write_partial_list->end_index = mavlink_msg_mission_write_partial_list_get_end_index(msg); + mission_write_partial_list->target_system = mavlink_msg_mission_write_partial_list_get_target_system(msg); + mission_write_partial_list->target_component = mavlink_msg_mission_write_partial_list_get_target_component(msg); +#else + memcpy(mission_write_partial_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_named_value_float.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_named_value_float.h new file mode 100644 index 0000000..a5c73a0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_named_value_float.h @@ -0,0 +1,249 @@ +// MESSAGE NAMED_VALUE_FLOAT PACKING + +#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251 + +typedef struct __mavlink_named_value_float_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float value; /*< Floating point value*/ + char name[10]; /*< Name of the debug variable*/ +} mavlink_named_value_float_t; + +#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18 +#define MAVLINK_MSG_ID_251_LEN 18 + +#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC 170 +#define MAVLINK_MSG_ID_251_CRC 170 + +#define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10 + +#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \ + "NAMED_VALUE_FLOAT", \ + 3, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \ + { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \ + } \ +} + + +/** + * @brief Pack a named_value_float message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Floating point value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, const char *name, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#else + mavlink_named_value_float_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif +} + +/** + * @brief Pack a named_value_float message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Floating point value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,const char *name,float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#else + mavlink_named_value_float_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif +} + +/** + * @brief Encode a named_value_float struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param named_value_float C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float) +{ + return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); +} + +/** + * @brief Encode a named_value_float struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param named_value_float C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_value_float_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float) +{ + return mavlink_msg_named_value_float_pack_chan(system_id, component_id, chan, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); +} + +/** + * @brief Send a named_value_float message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Floating point value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif +#else + mavlink_named_value_float_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_named_value_float_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif +#else + mavlink_named_value_float_t *packet = (mavlink_named_value_float_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->value = value; + mav_array_memcpy(packet->name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE NAMED_VALUE_FLOAT UNPACKING + + +/** + * @brief Get field time_boot_ms from named_value_float message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_named_value_float_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field name from named_value_float message + * + * @return Name of the debug variable + */ +static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 10, 8); +} + +/** + * @brief Get field value from named_value_float message + * + * @return Floating point value + */ +static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Decode a named_value_float message into a struct + * + * @param msg The message to decode + * @param named_value_float C-struct to decode the message contents into + */ +static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float) +{ +#if MAVLINK_NEED_BYTE_SWAP + named_value_float->time_boot_ms = mavlink_msg_named_value_float_get_time_boot_ms(msg); + named_value_float->value = mavlink_msg_named_value_float_get_value(msg); + mavlink_msg_named_value_float_get_name(msg, named_value_float->name); +#else + memcpy(named_value_float, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_named_value_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_named_value_int.h new file mode 100644 index 0000000..97177c7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_named_value_int.h @@ -0,0 +1,249 @@ +// MESSAGE NAMED_VALUE_INT PACKING + +#define MAVLINK_MSG_ID_NAMED_VALUE_INT 252 + +typedef struct __mavlink_named_value_int_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + int32_t value; /*< Signed integer value*/ + char name[10]; /*< Name of the debug variable*/ +} mavlink_named_value_int_t; + +#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18 +#define MAVLINK_MSG_ID_252_LEN 18 + +#define MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC 44 +#define MAVLINK_MSG_ID_252_CRC 44 + +#define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN 10 + +#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \ + "NAMED_VALUE_INT", \ + 3, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \ + { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \ + } \ +} + + +/** + * @brief Pack a named_value_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Signed integer value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, const char *name, int32_t value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#else + mavlink_named_value_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif +} + +/** + * @brief Pack a named_value_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Signed integer value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,const char *name,int32_t value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#else + mavlink_named_value_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif +} + +/** + * @brief Encode a named_value_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param named_value_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int) +{ + return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); +} + +/** + * @brief Encode a named_value_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param named_value_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_value_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int) +{ + return mavlink_msg_named_value_int_pack_chan(system_id, component_id, chan, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); +} + +/** + * @brief Send a named_value_int message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Signed integer value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, int32_t value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif +#else + mavlink_named_value_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_named_value_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, int32_t value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif +#else + mavlink_named_value_int_t *packet = (mavlink_named_value_int_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->value = value; + mav_array_memcpy(packet->name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE NAMED_VALUE_INT UNPACKING + + +/** + * @brief Get field time_boot_ms from named_value_int message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_named_value_int_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field name from named_value_int message + * + * @return Name of the debug variable + */ +static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 10, 8); +} + +/** + * @brief Get field value from named_value_int message + * + * @return Signed integer value + */ +static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Decode a named_value_int message into a struct + * + * @param msg The message to decode + * @param named_value_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* msg, mavlink_named_value_int_t* named_value_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + named_value_int->time_boot_ms = mavlink_msg_named_value_int_get_time_boot_ms(msg); + named_value_int->value = mavlink_msg_named_value_int_get_value(msg); + mavlink_msg_named_value_int_get_name(msg, named_value_int->name); +#else + memcpy(named_value_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h new file mode 100644 index 0000000..1691d58 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h @@ -0,0 +1,377 @@ +// MESSAGE NAV_CONTROLLER_OUTPUT PACKING + +#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62 + +typedef struct __mavlink_nav_controller_output_t +{ + float nav_roll; /*< Current desired roll in degrees*/ + float nav_pitch; /*< Current desired pitch in degrees*/ + float alt_error; /*< Current altitude error in meters*/ + float aspd_error; /*< Current airspeed error in meters/second*/ + float xtrack_error; /*< Current crosstrack error on x-y plane in meters*/ + int16_t nav_bearing; /*< Current desired heading in degrees*/ + int16_t target_bearing; /*< Bearing to current MISSION/target in degrees*/ + uint16_t wp_dist; /*< Distance to active MISSION in meters*/ +} mavlink_nav_controller_output_t; + +#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26 +#define MAVLINK_MSG_ID_62_LEN 26 + +#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC 183 +#define MAVLINK_MSG_ID_62_CRC 183 + + + +#define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \ + "NAV_CONTROLLER_OUTPUT", \ + 8, \ + { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ + { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ + { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ + { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ + { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ + { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ + { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ + { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ + } \ +} + + +/** + * @brief Pack a nav_controller_output message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param nav_roll Current desired roll in degrees + * @param nav_pitch Current desired pitch in degrees + * @param nav_bearing Current desired heading in degrees + * @param target_bearing Bearing to current MISSION/target in degrees + * @param wp_dist Distance to active MISSION in meters + * @param alt_error Current altitude error in meters + * @param aspd_error Current airspeed error in meters/second + * @param xtrack_error Current crosstrack error on x-y plane in meters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; + _mav_put_float(buf, 0, nav_roll); + _mav_put_float(buf, 4, nav_pitch); + _mav_put_float(buf, 8, alt_error); + _mav_put_float(buf, 12, aspd_error); + _mav_put_float(buf, 16, xtrack_error); + _mav_put_int16_t(buf, 20, nav_bearing); + _mav_put_int16_t(buf, 22, target_bearing); + _mav_put_uint16_t(buf, 24, wp_dist); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#else + mavlink_nav_controller_output_t packet; + packet.nav_roll = nav_roll; + packet.nav_pitch = nav_pitch; + packet.alt_error = alt_error; + packet.aspd_error = aspd_error; + packet.xtrack_error = xtrack_error; + packet.nav_bearing = nav_bearing; + packet.target_bearing = target_bearing; + packet.wp_dist = wp_dist; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif +} + +/** + * @brief Pack a nav_controller_output message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param nav_roll Current desired roll in degrees + * @param nav_pitch Current desired pitch in degrees + * @param nav_bearing Current desired heading in degrees + * @param target_bearing Bearing to current MISSION/target in degrees + * @param wp_dist Distance to active MISSION in meters + * @param alt_error Current altitude error in meters + * @param aspd_error Current airspeed error in meters/second + * @param xtrack_error Current crosstrack error on x-y plane in meters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float nav_roll,float nav_pitch,int16_t nav_bearing,int16_t target_bearing,uint16_t wp_dist,float alt_error,float aspd_error,float xtrack_error) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; + _mav_put_float(buf, 0, nav_roll); + _mav_put_float(buf, 4, nav_pitch); + _mav_put_float(buf, 8, alt_error); + _mav_put_float(buf, 12, aspd_error); + _mav_put_float(buf, 16, xtrack_error); + _mav_put_int16_t(buf, 20, nav_bearing); + _mav_put_int16_t(buf, 22, target_bearing); + _mav_put_uint16_t(buf, 24, wp_dist); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#else + mavlink_nav_controller_output_t packet; + packet.nav_roll = nav_roll; + packet.nav_pitch = nav_pitch; + packet.alt_error = alt_error; + packet.aspd_error = aspd_error; + packet.xtrack_error = xtrack_error; + packet.nav_bearing = nav_bearing; + packet.target_bearing = target_bearing; + packet.wp_dist = wp_dist; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif +} + +/** + * @brief Encode a nav_controller_output struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param nav_controller_output C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) +{ + return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); +} + +/** + * @brief Encode a nav_controller_output struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param nav_controller_output C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_nav_controller_output_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) +{ + return mavlink_msg_nav_controller_output_pack_chan(system_id, component_id, chan, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); +} + +/** + * @brief Send a nav_controller_output message + * @param chan MAVLink channel to send the message + * + * @param nav_roll Current desired roll in degrees + * @param nav_pitch Current desired pitch in degrees + * @param nav_bearing Current desired heading in degrees + * @param target_bearing Bearing to current MISSION/target in degrees + * @param wp_dist Distance to active MISSION in meters + * @param alt_error Current altitude error in meters + * @param aspd_error Current airspeed error in meters/second + * @param xtrack_error Current crosstrack error on x-y plane in meters + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; + _mav_put_float(buf, 0, nav_roll); + _mav_put_float(buf, 4, nav_pitch); + _mav_put_float(buf, 8, alt_error); + _mav_put_float(buf, 12, aspd_error); + _mav_put_float(buf, 16, xtrack_error); + _mav_put_int16_t(buf, 20, nav_bearing); + _mav_put_int16_t(buf, 22, target_bearing); + _mav_put_uint16_t(buf, 24, wp_dist); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif +#else + mavlink_nav_controller_output_t packet; + packet.nav_roll = nav_roll; + packet.nav_pitch = nav_pitch; + packet.alt_error = alt_error; + packet.aspd_error = aspd_error; + packet.xtrack_error = xtrack_error; + packet.nav_bearing = nav_bearing; + packet.target_bearing = target_bearing; + packet.wp_dist = wp_dist; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_nav_controller_output_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, nav_roll); + _mav_put_float(buf, 4, nav_pitch); + _mav_put_float(buf, 8, alt_error); + _mav_put_float(buf, 12, aspd_error); + _mav_put_float(buf, 16, xtrack_error); + _mav_put_int16_t(buf, 20, nav_bearing); + _mav_put_int16_t(buf, 22, target_bearing); + _mav_put_uint16_t(buf, 24, wp_dist); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif +#else + mavlink_nav_controller_output_t *packet = (mavlink_nav_controller_output_t *)msgbuf; + packet->nav_roll = nav_roll; + packet->nav_pitch = nav_pitch; + packet->alt_error = alt_error; + packet->aspd_error = aspd_error; + packet->xtrack_error = xtrack_error; + packet->nav_bearing = nav_bearing; + packet->target_bearing = target_bearing; + packet->wp_dist = wp_dist; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE NAV_CONTROLLER_OUTPUT UNPACKING + + +/** + * @brief Get field nav_roll from nav_controller_output message + * + * @return Current desired roll in degrees + */ +static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field nav_pitch from nav_controller_output message + * + * @return Current desired pitch in degrees + */ +static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field nav_bearing from nav_controller_output message + * + * @return Current desired heading in degrees + */ +static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field target_bearing from nav_controller_output message + * + * @return Bearing to current MISSION/target in degrees + */ +static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field wp_dist from nav_controller_output message + * + * @return Distance to active MISSION in meters + */ +static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field alt_error from nav_controller_output message + * + * @return Current altitude error in meters + */ +static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field aspd_error from nav_controller_output message + * + * @return Current airspeed error in meters/second + */ +static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field xtrack_error from nav_controller_output message + * + * @return Current crosstrack error on x-y plane in meters + */ +static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a nav_controller_output message into a struct + * + * @param msg The message to decode + * @param nav_controller_output C-struct to decode the message contents into + */ +static inline void mavlink_msg_nav_controller_output_decode(const mavlink_message_t* msg, mavlink_nav_controller_output_t* nav_controller_output) +{ +#if MAVLINK_NEED_BYTE_SWAP + nav_controller_output->nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg); + nav_controller_output->nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg); + nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg); + nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg); + nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg); + nav_controller_output->nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg); + nav_controller_output->target_bearing = mavlink_msg_nav_controller_output_get_target_bearing(msg); + nav_controller_output->wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg); +#else + memcpy(nav_controller_output, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_optical_flow.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_optical_flow.h new file mode 100644 index 0000000..69d8493 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_optical_flow.h @@ -0,0 +1,377 @@ +// MESSAGE OPTICAL_FLOW PACKING + +#define MAVLINK_MSG_ID_OPTICAL_FLOW 100 + +typedef struct __mavlink_optical_flow_t +{ + uint64_t time_usec; /*< Timestamp (UNIX)*/ + float flow_comp_m_x; /*< Flow in meters in x-sensor direction, angular-speed compensated*/ + float flow_comp_m_y; /*< Flow in meters in y-sensor direction, angular-speed compensated*/ + float ground_distance; /*< Ground distance in meters. Positive value: distance known. Negative value: Unknown distance*/ + int16_t flow_x; /*< Flow in pixels * 10 in x-sensor direction (dezi-pixels)*/ + int16_t flow_y; /*< Flow in pixels * 10 in y-sensor direction (dezi-pixels)*/ + uint8_t sensor_id; /*< Sensor ID*/ + uint8_t quality; /*< Optical flow quality / confidence. 0: bad, 255: maximum quality*/ +} mavlink_optical_flow_t; + +#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26 +#define MAVLINK_MSG_ID_100_LEN 26 + +#define MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175 +#define MAVLINK_MSG_ID_100_CRC 175 + + + +#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \ + "OPTICAL_FLOW", \ + 8, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \ + { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ + { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ + { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ + { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \ + { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ + { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \ + } \ +} + + +/** + * @brief Pack a optical_flow message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (UNIX) + * @param sensor_id Sensor ID + * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) + * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) + * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated + * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated + * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality + * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, flow_comp_m_x); + _mav_put_float(buf, 12, flow_comp_m_y); + _mav_put_float(buf, 16, ground_distance); + _mav_put_int16_t(buf, 20, flow_x); + _mav_put_int16_t(buf, 22, flow_y); + _mav_put_uint8_t(buf, 24, sensor_id); + _mav_put_uint8_t(buf, 25, quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#else + mavlink_optical_flow_t packet; + packet.time_usec = time_usec; + packet.flow_comp_m_x = flow_comp_m_x; + packet.flow_comp_m_y = flow_comp_m_y; + packet.ground_distance = ground_distance; + packet.flow_x = flow_x; + packet.flow_y = flow_y; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif +} + +/** + * @brief Pack a optical_flow message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (UNIX) + * @param sensor_id Sensor ID + * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) + * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) + * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated + * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated + * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality + * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,float flow_comp_m_x,float flow_comp_m_y,uint8_t quality,float ground_distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, flow_comp_m_x); + _mav_put_float(buf, 12, flow_comp_m_y); + _mav_put_float(buf, 16, ground_distance); + _mav_put_int16_t(buf, 20, flow_x); + _mav_put_int16_t(buf, 22, flow_y); + _mav_put_uint8_t(buf, 24, sensor_id); + _mav_put_uint8_t(buf, 25, quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#else + mavlink_optical_flow_t packet; + packet.time_usec = time_usec; + packet.flow_comp_m_x = flow_comp_m_x; + packet.flow_comp_m_y = flow_comp_m_y; + packet.ground_distance = ground_distance; + packet.flow_x = flow_x; + packet.flow_y = flow_y; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif +} + +/** + * @brief Encode a optical_flow struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param optical_flow C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow) +{ + return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance); +} + +/** + * @brief Encode a optical_flow struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param optical_flow C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow) +{ + return mavlink_msg_optical_flow_pack_chan(system_id, component_id, chan, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance); +} + +/** + * @brief Send a optical_flow message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (UNIX) + * @param sensor_id Sensor ID + * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) + * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) + * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated + * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated + * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality + * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, flow_comp_m_x); + _mav_put_float(buf, 12, flow_comp_m_y); + _mav_put_float(buf, 16, ground_distance); + _mav_put_int16_t(buf, 20, flow_x); + _mav_put_int16_t(buf, 22, flow_y); + _mav_put_uint8_t(buf, 24, sensor_id); + _mav_put_uint8_t(buf, 25, quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif +#else + mavlink_optical_flow_t packet; + packet.time_usec = time_usec; + packet.flow_comp_m_x = flow_comp_m_x; + packet.flow_comp_m_y = flow_comp_m_y; + packet.ground_distance = ground_distance; + packet.flow_x = flow_x; + packet.flow_y = flow_y; + packet.sensor_id = sensor_id; + packet.quality = quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, flow_comp_m_x); + _mav_put_float(buf, 12, flow_comp_m_y); + _mav_put_float(buf, 16, ground_distance); + _mav_put_int16_t(buf, 20, flow_x); + _mav_put_int16_t(buf, 22, flow_y); + _mav_put_uint8_t(buf, 24, sensor_id); + _mav_put_uint8_t(buf, 25, quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif +#else + mavlink_optical_flow_t *packet = (mavlink_optical_flow_t *)msgbuf; + packet->time_usec = time_usec; + packet->flow_comp_m_x = flow_comp_m_x; + packet->flow_comp_m_y = flow_comp_m_y; + packet->ground_distance = ground_distance; + packet->flow_x = flow_x; + packet->flow_y = flow_y; + packet->sensor_id = sensor_id; + packet->quality = quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE OPTICAL_FLOW UNPACKING + + +/** + * @brief Get field time_usec from optical_flow message + * + * @return Timestamp (UNIX) + */ +static inline uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field sensor_id from optical_flow message + * + * @return Sensor ID + */ +static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field flow_x from optical_flow message + * + * @return Flow in pixels * 10 in x-sensor direction (dezi-pixels) + */ +static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field flow_y from optical_flow message + * + * @return Flow in pixels * 10 in y-sensor direction (dezi-pixels) + */ +static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field flow_comp_m_x from optical_flow message + * + * @return Flow in meters in x-sensor direction, angular-speed compensated + */ +static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field flow_comp_m_y from optical_flow message + * + * @return Flow in meters in y-sensor direction, angular-speed compensated + */ +static inline float mavlink_msg_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field quality from optical_flow message + * + * @return Optical flow quality / confidence. 0: bad, 255: maximum quality + */ +static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 25); +} + +/** + * @brief Get field ground_distance from optical_flow message + * + * @return Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + */ +static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a optical_flow message into a struct + * + * @param msg The message to decode + * @param optical_flow C-struct to decode the message contents into + */ +static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, mavlink_optical_flow_t* optical_flow) +{ +#if MAVLINK_NEED_BYTE_SWAP + optical_flow->time_usec = mavlink_msg_optical_flow_get_time_usec(msg); + optical_flow->flow_comp_m_x = mavlink_msg_optical_flow_get_flow_comp_m_x(msg); + optical_flow->flow_comp_m_y = mavlink_msg_optical_flow_get_flow_comp_m_y(msg); + optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg); + optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg); + optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg); + optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg); + optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg); +#else + memcpy(optical_flow, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_optical_flow_rad.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_optical_flow_rad.h new file mode 100644 index 0000000..7d07703 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_optical_flow_rad.h @@ -0,0 +1,473 @@ +// MESSAGE OPTICAL_FLOW_RAD PACKING + +#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD 106 + +typedef struct __mavlink_optical_flow_rad_t +{ + uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + uint32_t integration_time_us; /*< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/ + float integrated_x; /*< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/ + float integrated_y; /*< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/ + float integrated_xgyro; /*< RH rotation around X axis (rad)*/ + float integrated_ygyro; /*< RH rotation around Y axis (rad)*/ + float integrated_zgyro; /*< RH rotation around Z axis (rad)*/ + uint32_t time_delta_distance_us; /*< Time in microseconds since the distance was sampled.*/ + float distance; /*< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.*/ + int16_t temperature; /*< Temperature * 100 in centi-degrees Celsius*/ + uint8_t sensor_id; /*< Sensor ID*/ + uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/ +} mavlink_optical_flow_rad_t; + +#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN 44 +#define MAVLINK_MSG_ID_106_LEN 44 + +#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC 138 +#define MAVLINK_MSG_ID_106_CRC 138 + + + +#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD { \ + "OPTICAL_FLOW_RAD", \ + 12, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_rad_t, time_usec) }, \ + { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_optical_flow_rad_t, integration_time_us) }, \ + { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_rad_t, integrated_x) }, \ + { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_rad_t, integrated_y) }, \ + { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_optical_flow_rad_t, integrated_xgyro) }, \ + { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_optical_flow_rad_t, integrated_ygyro) }, \ + { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_optical_flow_rad_t, integrated_zgyro) }, \ + { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_optical_flow_rad_t, time_delta_distance_us) }, \ + { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_optical_flow_rad_t, distance) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \ + { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \ + } \ +} + + +/** + * @brief Pack a optical_flow_rad message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param sensor_id Sensor ID + * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro RH rotation around X axis (rad) + * @param integrated_ygyro RH rotation around Y axis (rad) + * @param integrated_zgyro RH rotation around Z axis (rad) + * @param temperature Temperature * 100 in centi-degrees Celsius + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us Time in microseconds since the distance was sampled. + * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_optical_flow_rad_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#else + mavlink_optical_flow_rad_t packet; + packet.time_usec = time_usec; + packet.integration_time_us = integration_time_us; + packet.integrated_x = integrated_x; + packet.integrated_y = integrated_y; + packet.integrated_xgyro = integrated_xgyro; + packet.integrated_ygyro = integrated_ygyro; + packet.integrated_zgyro = integrated_zgyro; + packet.time_delta_distance_us = time_delta_distance_us; + packet.distance = distance; + packet.temperature = temperature; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW_RAD; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif +} + +/** + * @brief Pack a optical_flow_rad message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param sensor_id Sensor ID + * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro RH rotation around X axis (rad) + * @param integrated_ygyro RH rotation around Y axis (rad) + * @param integrated_zgyro RH rotation around Z axis (rad) + * @param temperature Temperature * 100 in centi-degrees Celsius + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us Time in microseconds since the distance was sampled. + * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_optical_flow_rad_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t sensor_id,uint32_t integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,int16_t temperature,uint8_t quality,uint32_t time_delta_distance_us,float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#else + mavlink_optical_flow_rad_t packet; + packet.time_usec = time_usec; + packet.integration_time_us = integration_time_us; + packet.integrated_x = integrated_x; + packet.integrated_y = integrated_y; + packet.integrated_xgyro = integrated_xgyro; + packet.integrated_ygyro = integrated_ygyro; + packet.integrated_zgyro = integrated_zgyro; + packet.time_delta_distance_us = time_delta_distance_us; + packet.distance = distance; + packet.temperature = temperature; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW_RAD; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif +} + +/** + * @brief Encode a optical_flow_rad struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param optical_flow_rad C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_optical_flow_rad_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_rad_t* optical_flow_rad) +{ + return mavlink_msg_optical_flow_rad_pack(system_id, component_id, msg, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance); +} + +/** + * @brief Encode a optical_flow_rad struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param optical_flow_rad C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_optical_flow_rad_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_rad_t* optical_flow_rad) +{ + return mavlink_msg_optical_flow_rad_pack_chan(system_id, component_id, chan, msg, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance); +} + +/** + * @brief Send a optical_flow_rad message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param sensor_id Sensor ID + * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro RH rotation around X axis (rad) + * @param integrated_ygyro RH rotation around Y axis (rad) + * @param integrated_zgyro RH rotation around Z axis (rad) + * @param temperature Temperature * 100 in centi-degrees Celsius + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us Time in microseconds since the distance was sampled. + * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_optical_flow_rad_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif +#else + mavlink_optical_flow_rad_t packet; + packet.time_usec = time_usec; + packet.integration_time_us = integration_time_us; + packet.integrated_x = integrated_x; + packet.integrated_y = integrated_y; + packet.integrated_xgyro = integrated_xgyro; + packet.integrated_ygyro = integrated_ygyro; + packet.integrated_zgyro = integrated_zgyro; + packet.time_delta_distance_us = time_delta_distance_us; + packet.distance = distance; + packet.temperature = temperature; + packet.sensor_id = sensor_id; + packet.quality = quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_optical_flow_rad_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif +#else + mavlink_optical_flow_rad_t *packet = (mavlink_optical_flow_rad_t *)msgbuf; + packet->time_usec = time_usec; + packet->integration_time_us = integration_time_us; + packet->integrated_x = integrated_x; + packet->integrated_y = integrated_y; + packet->integrated_xgyro = integrated_xgyro; + packet->integrated_ygyro = integrated_ygyro; + packet->integrated_zgyro = integrated_zgyro; + packet->time_delta_distance_us = time_delta_distance_us; + packet->distance = distance; + packet->temperature = temperature; + packet->sensor_id = sensor_id; + packet->quality = quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE OPTICAL_FLOW_RAD UNPACKING + + +/** + * @brief Get field time_usec from optical_flow_rad message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_optical_flow_rad_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field sensor_id from optical_flow_rad message + * + * @return Sensor ID + */ +static inline uint8_t mavlink_msg_optical_flow_rad_get_sensor_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 42); +} + +/** + * @brief Get field integration_time_us from optical_flow_rad message + * + * @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + */ +static inline uint32_t mavlink_msg_optical_flow_rad_get_integration_time_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field integrated_x from optical_flow_rad message + * + * @return Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + */ +static inline float mavlink_msg_optical_flow_rad_get_integrated_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field integrated_y from optical_flow_rad message + * + * @return Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + */ +static inline float mavlink_msg_optical_flow_rad_get_integrated_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field integrated_xgyro from optical_flow_rad message + * + * @return RH rotation around X axis (rad) + */ +static inline float mavlink_msg_optical_flow_rad_get_integrated_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field integrated_ygyro from optical_flow_rad message + * + * @return RH rotation around Y axis (rad) + */ +static inline float mavlink_msg_optical_flow_rad_get_integrated_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field integrated_zgyro from optical_flow_rad message + * + * @return RH rotation around Z axis (rad) + */ +static inline float mavlink_msg_optical_flow_rad_get_integrated_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field temperature from optical_flow_rad message + * + * @return Temperature * 100 in centi-degrees Celsius + */ +static inline int16_t mavlink_msg_optical_flow_rad_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 40); +} + +/** + * @brief Get field quality from optical_flow_rad message + * + * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + */ +static inline uint8_t mavlink_msg_optical_flow_rad_get_quality(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 43); +} + +/** + * @brief Get field time_delta_distance_us from optical_flow_rad message + * + * @return Time in microseconds since the distance was sampled. + */ +static inline uint32_t mavlink_msg_optical_flow_rad_get_time_delta_distance_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 32); +} + +/** + * @brief Get field distance from optical_flow_rad message + * + * @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + */ +static inline float mavlink_msg_optical_flow_rad_get_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Decode a optical_flow_rad message into a struct + * + * @param msg The message to decode + * @param optical_flow_rad C-struct to decode the message contents into + */ +static inline void mavlink_msg_optical_flow_rad_decode(const mavlink_message_t* msg, mavlink_optical_flow_rad_t* optical_flow_rad) +{ +#if MAVLINK_NEED_BYTE_SWAP + optical_flow_rad->time_usec = mavlink_msg_optical_flow_rad_get_time_usec(msg); + optical_flow_rad->integration_time_us = mavlink_msg_optical_flow_rad_get_integration_time_us(msg); + optical_flow_rad->integrated_x = mavlink_msg_optical_flow_rad_get_integrated_x(msg); + optical_flow_rad->integrated_y = mavlink_msg_optical_flow_rad_get_integrated_y(msg); + optical_flow_rad->integrated_xgyro = mavlink_msg_optical_flow_rad_get_integrated_xgyro(msg); + optical_flow_rad->integrated_ygyro = mavlink_msg_optical_flow_rad_get_integrated_ygyro(msg); + optical_flow_rad->integrated_zgyro = mavlink_msg_optical_flow_rad_get_integrated_zgyro(msg); + optical_flow_rad->time_delta_distance_us = mavlink_msg_optical_flow_rad_get_time_delta_distance_us(msg); + optical_flow_rad->distance = mavlink_msg_optical_flow_rad_get_distance(msg); + optical_flow_rad->temperature = mavlink_msg_optical_flow_rad_get_temperature(msg); + optical_flow_rad->sensor_id = mavlink_msg_optical_flow_rad_get_sensor_id(msg); + optical_flow_rad->quality = mavlink_msg_optical_flow_rad_get_quality(msg); +#else + memcpy(optical_flow_rad, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_param_map_rc.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_param_map_rc.h new file mode 100644 index 0000000..e4b7483 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_param_map_rc.h @@ -0,0 +1,393 @@ +// MESSAGE PARAM_MAP_RC PACKING + +#define MAVLINK_MSG_ID_PARAM_MAP_RC 50 + +typedef struct __mavlink_param_map_rc_t +{ + float param_value0; /*< Initial parameter value*/ + float scale; /*< Scale, maps the RC range [-1, 1] to a parameter value*/ + float param_value_min; /*< Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)*/ + float param_value_max; /*< Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)*/ + int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ + uint8_t parameter_rc_channel_index; /*< Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.*/ +} mavlink_param_map_rc_t; + +#define MAVLINK_MSG_ID_PARAM_MAP_RC_LEN 37 +#define MAVLINK_MSG_ID_50_LEN 37 + +#define MAVLINK_MSG_ID_PARAM_MAP_RC_CRC 78 +#define MAVLINK_MSG_ID_50_CRC 78 + +#define MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN 16 + +#define MAVLINK_MESSAGE_INFO_PARAM_MAP_RC { \ + "PARAM_MAP_RC", \ + 9, \ + { { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \ + { "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \ + { "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \ + { "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \ + { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \ + { "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \ + } \ +} + + +/** + * @brief Pack a param_map_rc message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. + * @param param_value0 Initial parameter value + * @param scale Scale, maps the RC range [-1, 1] to a parameter value + * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_map_rc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN]; + _mav_put_float(buf, 0, param_value0); + _mav_put_float(buf, 4, scale); + _mav_put_float(buf, 8, param_value_min); + _mav_put_float(buf, 12, param_value_max); + _mav_put_int16_t(buf, 16, param_index); + _mav_put_uint8_t(buf, 18, target_system); + _mav_put_uint8_t(buf, 19, target_component); + _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); + _mav_put_char_array(buf, 20, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#else + mavlink_param_map_rc_t packet; + packet.param_value0 = param_value0; + packet.scale = scale; + packet.param_value_min = param_value_min; + packet.param_value_max = param_value_max; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + packet.parameter_rc_channel_index = parameter_rc_channel_index; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_MAP_RC; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif +} + +/** + * @brief Pack a param_map_rc message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. + * @param param_value0 Initial parameter value + * @param scale Scale, maps the RC range [-1, 1] to a parameter value + * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_map_rc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index,uint8_t parameter_rc_channel_index,float param_value0,float scale,float param_value_min,float param_value_max) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN]; + _mav_put_float(buf, 0, param_value0); + _mav_put_float(buf, 4, scale); + _mav_put_float(buf, 8, param_value_min); + _mav_put_float(buf, 12, param_value_max); + _mav_put_int16_t(buf, 16, param_index); + _mav_put_uint8_t(buf, 18, target_system); + _mav_put_uint8_t(buf, 19, target_component); + _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); + _mav_put_char_array(buf, 20, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#else + mavlink_param_map_rc_t packet; + packet.param_value0 = param_value0; + packet.scale = scale; + packet.param_value_min = param_value_min; + packet.param_value_max = param_value_max; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + packet.parameter_rc_channel_index = parameter_rc_channel_index; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_MAP_RC; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif +} + +/** + * @brief Encode a param_map_rc struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_map_rc C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_map_rc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_map_rc_t* param_map_rc) +{ + return mavlink_msg_param_map_rc_pack(system_id, component_id, msg, param_map_rc->target_system, param_map_rc->target_component, param_map_rc->param_id, param_map_rc->param_index, param_map_rc->parameter_rc_channel_index, param_map_rc->param_value0, param_map_rc->scale, param_map_rc->param_value_min, param_map_rc->param_value_max); +} + +/** + * @brief Encode a param_map_rc struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param param_map_rc C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_map_rc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_map_rc_t* param_map_rc) +{ + return mavlink_msg_param_map_rc_pack_chan(system_id, component_id, chan, msg, param_map_rc->target_system, param_map_rc->target_component, param_map_rc->param_id, param_map_rc->param_index, param_map_rc->parameter_rc_channel_index, param_map_rc->param_value0, param_map_rc->scale, param_map_rc->param_value_min, param_map_rc->param_value_max); +} + +/** + * @brief Send a param_map_rc message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. + * @param param_value0 Initial parameter value + * @param scale Scale, maps the RC range [-1, 1] to a parameter value + * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_map_rc_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN]; + _mav_put_float(buf, 0, param_value0); + _mav_put_float(buf, 4, scale); + _mav_put_float(buf, 8, param_value_min); + _mav_put_float(buf, 12, param_value_max); + _mav_put_int16_t(buf, 16, param_index); + _mav_put_uint8_t(buf, 18, target_system); + _mav_put_uint8_t(buf, 19, target_component); + _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); + _mav_put_char_array(buf, 20, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif +#else + mavlink_param_map_rc_t packet; + packet.param_value0 = param_value0; + packet.scale = scale; + packet.param_value_min = param_value_min; + packet.param_value_max = param_value_max; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + packet.parameter_rc_channel_index = parameter_rc_channel_index; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)&packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)&packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_PARAM_MAP_RC_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_param_map_rc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, param_value0); + _mav_put_float(buf, 4, scale); + _mav_put_float(buf, 8, param_value_min); + _mav_put_float(buf, 12, param_value_max); + _mav_put_int16_t(buf, 16, param_index); + _mav_put_uint8_t(buf, 18, target_system); + _mav_put_uint8_t(buf, 19, target_component); + _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); + _mav_put_char_array(buf, 20, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif +#else + mavlink_param_map_rc_t *packet = (mavlink_param_map_rc_t *)msgbuf; + packet->param_value0 = param_value0; + packet->scale = scale; + packet->param_value_min = param_value_min; + packet->param_value_max = param_value_max; + packet->param_index = param_index; + packet->target_system = target_system; + packet->target_component = target_component; + packet->parameter_rc_channel_index = parameter_rc_channel_index; + mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE PARAM_MAP_RC UNPACKING + + +/** + * @brief Get field target_system from param_map_rc message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_map_rc_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 18); +} + +/** + * @brief Get field target_component from param_map_rc message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_map_rc_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 19); +} + +/** + * @brief Get field param_id from param_map_rc message + * + * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + */ +static inline uint16_t mavlink_msg_param_map_rc_get_param_id(const mavlink_message_t* msg, char *param_id) +{ + return _MAV_RETURN_char_array(msg, param_id, 16, 20); +} + +/** + * @brief Get field param_index from param_map_rc message + * + * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + */ +static inline int16_t mavlink_msg_param_map_rc_get_param_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field parameter_rc_channel_index from param_map_rc message + * + * @return Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. + */ +static inline uint8_t mavlink_msg_param_map_rc_get_parameter_rc_channel_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Get field param_value0 from param_map_rc message + * + * @return Initial parameter value + */ +static inline float mavlink_msg_param_map_rc_get_param_value0(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field scale from param_map_rc message + * + * @return Scale, maps the RC range [-1, 1] to a parameter value + */ +static inline float mavlink_msg_param_map_rc_get_scale(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param_value_min from param_map_rc message + * + * @return Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + */ +static inline float mavlink_msg_param_map_rc_get_param_value_min(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param_value_max from param_map_rc message + * + * @return Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + */ +static inline float mavlink_msg_param_map_rc_get_param_value_max(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a param_map_rc message into a struct + * + * @param msg The message to decode + * @param param_map_rc C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_map_rc_decode(const mavlink_message_t* msg, mavlink_param_map_rc_t* param_map_rc) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_map_rc->param_value0 = mavlink_msg_param_map_rc_get_param_value0(msg); + param_map_rc->scale = mavlink_msg_param_map_rc_get_scale(msg); + param_map_rc->param_value_min = mavlink_msg_param_map_rc_get_param_value_min(msg); + param_map_rc->param_value_max = mavlink_msg_param_map_rc_get_param_value_max(msg); + param_map_rc->param_index = mavlink_msg_param_map_rc_get_param_index(msg); + param_map_rc->target_system = mavlink_msg_param_map_rc_get_target_system(msg); + param_map_rc->target_component = mavlink_msg_param_map_rc_get_target_component(msg); + mavlink_msg_param_map_rc_get_param_id(msg, param_map_rc->param_id); + param_map_rc->parameter_rc_channel_index = mavlink_msg_param_map_rc_get_parameter_rc_channel_index(msg); +#else + memcpy(param_map_rc, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_param_request_list.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_param_request_list.h new file mode 100644 index 0000000..f78f049 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_param_request_list.h @@ -0,0 +1,233 @@ +// MESSAGE PARAM_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21 + +typedef struct __mavlink_param_request_list_t +{ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_param_request_list_t; + +#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2 +#define MAVLINK_MSG_ID_21_LEN 2 + +#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC 159 +#define MAVLINK_MSG_ID_21_CRC 159 + + + +#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \ + "PARAM_REQUEST_LIST", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a param_request_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#else + mavlink_param_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif +} + +/** + * @brief Pack a param_request_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#else + mavlink_param_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif +} + +/** + * @brief Encode a param_request_list struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) +{ + return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component); +} + +/** + * @brief Encode a param_request_list struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param param_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) +{ + return mavlink_msg_param_request_list_pack_chan(system_id, component_id, chan, msg, param_request_list->target_system, param_request_list->target_component); +} + +/** + * @brief Send a param_request_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif +#else + mavlink_param_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_param_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif +#else + mavlink_param_request_list_t *packet = (mavlink_param_request_list_t *)msgbuf; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE PARAM_REQUEST_LIST UNPACKING + + +/** + * @brief Get field target_system from param_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from param_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_request_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a param_request_list message into a struct + * + * @param msg The message to decode + * @param param_request_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t* msg, mavlink_param_request_list_t* param_request_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_request_list->target_system = mavlink_msg_param_request_list_get_target_system(msg); + param_request_list->target_component = mavlink_msg_param_request_list_get_target_component(msg); +#else + memcpy(param_request_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_param_request_read.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_param_request_read.h new file mode 100644 index 0000000..497f598 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_param_request_read.h @@ -0,0 +1,273 @@ +// MESSAGE PARAM_REQUEST_READ PACKING + +#define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20 + +typedef struct __mavlink_param_request_read_t +{ + int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ +} mavlink_param_request_read_t; + +#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20 +#define MAVLINK_MSG_ID_20_LEN 20 + +#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC 214 +#define MAVLINK_MSG_ID_20_CRC 214 + +#define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 16 + +#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \ + "PARAM_REQUEST_READ", \ + 4, \ + { { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \ + } \ +} + + +/** + * @brief Pack a param_request_read message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN]; + _mav_put_int16_t(buf, 0, param_index); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_char_array(buf, 4, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#else + mavlink_param_request_read_t packet; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif +} + +/** + * @brief Pack a param_request_read message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN]; + _mav_put_int16_t(buf, 0, param_index); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_char_array(buf, 4, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#else + mavlink_param_request_read_t packet; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif +} + +/** + * @brief Encode a param_request_read struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_request_read C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) +{ + return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); +} + +/** + * @brief Encode a param_request_read struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param param_request_read C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_request_read_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) +{ + return mavlink_msg_param_request_read_pack_chan(system_id, component_id, chan, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); +} + +/** + * @brief Send a param_request_read message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN]; + _mav_put_int16_t(buf, 0, param_index); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_char_array(buf, 4, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif +#else + mavlink_param_request_read_t packet; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_param_request_read_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int16_t(buf, 0, param_index); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_char_array(buf, 4, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif +#else + mavlink_param_request_read_t *packet = (mavlink_param_request_read_t *)msgbuf; + packet->param_index = param_index; + packet->target_system = target_system; + packet->target_component = target_component; + mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE PARAM_REQUEST_READ UNPACKING + + +/** + * @brief Get field target_system from param_request_read message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from param_request_read message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field param_id from param_request_read message + * + * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + */ +static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, char *param_id) +{ + return _MAV_RETURN_char_array(msg, param_id, 16, 4); +} + +/** + * @brief Get field param_index from param_request_read message + * + * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + */ +static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Decode a param_request_read message into a struct + * + * @param msg The message to decode + * @param param_request_read C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_request_read->param_index = mavlink_msg_param_request_read_get_param_index(msg); + param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg); + param_request_read->target_component = mavlink_msg_param_request_read_get_target_component(msg); + mavlink_msg_param_request_read_get_param_id(msg, param_request_read->param_id); +#else + memcpy(param_request_read, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_param_set.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_param_set.h new file mode 100644 index 0000000..471e674 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_param_set.h @@ -0,0 +1,297 @@ +// MESSAGE PARAM_SET PACKING + +#define MAVLINK_MSG_ID_PARAM_SET 23 + +typedef struct __mavlink_param_set_t +{ + float param_value; /*< Onboard parameter value*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ + uint8_t param_type; /*< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.*/ +} mavlink_param_set_t; + +#define MAVLINK_MSG_ID_PARAM_SET_LEN 23 +#define MAVLINK_MSG_ID_23_LEN 23 + +#define MAVLINK_MSG_ID_PARAM_SET_CRC 168 +#define MAVLINK_MSG_ID_23_CRC 168 + +#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 16 + +#define MAVLINK_MESSAGE_INFO_PARAM_SET { \ + "PARAM_SET", \ + 5, \ + { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \ + { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \ + } \ +} + + +/** + * @brief Pack a param_set message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_SET_LEN]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_char_array(buf, 6, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_SET_LEN); +#else + mavlink_param_set_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_SET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif +} + +/** + * @brief Pack a param_set message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,const char *param_id,float param_value,uint8_t param_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_SET_LEN]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_char_array(buf, 6, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_SET_LEN); +#else + mavlink_param_set_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_SET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif +} + +/** + * @brief Encode a param_set struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_set C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set) +{ + return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); +} + +/** + * @brief Encode a param_set struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param param_set C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_set_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_set_t* param_set) +{ + return mavlink_msg_param_set_pack_chan(system_id, component_id, chan, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); +} + +/** + * @brief Send a param_set message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_SET_LEN]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_char_array(buf, 6, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif +#else + mavlink_param_set_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_PARAM_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_param_set_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_char_array(buf, 6, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif +#else + mavlink_param_set_t *packet = (mavlink_param_set_t *)msgbuf; + packet->param_value = param_value; + packet->target_system = target_system; + packet->target_component = target_component; + packet->param_type = param_type; + mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE PARAM_SET UNPACKING + + +/** + * @brief Get field target_system from param_set message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from param_set message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field param_id from param_set message + * + * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + */ +static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, char *param_id) +{ + return _MAV_RETURN_char_array(msg, param_id, 16, 6); +} + +/** + * @brief Get field param_value from param_set message + * + * @return Onboard parameter value + */ +static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param_type from param_set message + * + * @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + */ +static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 22); +} + +/** + * @brief Decode a param_set message into a struct + * + * @param msg The message to decode + * @param param_set C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_set->param_value = mavlink_msg_param_set_get_param_value(msg); + param_set->target_system = mavlink_msg_param_set_get_target_system(msg); + param_set->target_component = mavlink_msg_param_set_get_target_component(msg); + mavlink_msg_param_set_get_param_id(msg, param_set->param_id); + param_set->param_type = mavlink_msg_param_set_get_param_type(msg); +#else + memcpy(param_set, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_param_value.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_param_value.h new file mode 100644 index 0000000..856fa5a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_param_value.h @@ -0,0 +1,297 @@ +// MESSAGE PARAM_VALUE PACKING + +#define MAVLINK_MSG_ID_PARAM_VALUE 22 + +typedef struct __mavlink_param_value_t +{ + float param_value; /*< Onboard parameter value*/ + uint16_t param_count; /*< Total number of onboard parameters*/ + uint16_t param_index; /*< Index of this onboard parameter*/ + char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ + uint8_t param_type; /*< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.*/ +} mavlink_param_value_t; + +#define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25 +#define MAVLINK_MSG_ID_22_LEN 25 + +#define MAVLINK_MSG_ID_PARAM_VALUE_CRC 220 +#define MAVLINK_MSG_ID_22_CRC 220 + +#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 16 + +#define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \ + "PARAM_VALUE", \ + 5, \ + { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \ + { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \ + { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \ + { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \ + } \ +} + + +/** + * @brief Pack a param_value message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint16_t(buf, 4, param_count); + _mav_put_uint16_t(buf, 6, param_index); + _mav_put_uint8_t(buf, 24, param_type); + _mav_put_char_array(buf, 8, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#else + mavlink_param_value_t packet; + packet.param_value = param_value; + packet.param_count = param_count; + packet.param_index = param_index; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif +} + +/** + * @brief Pack a param_value message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *param_id,float param_value,uint8_t param_type,uint16_t param_count,uint16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint16_t(buf, 4, param_count); + _mav_put_uint16_t(buf, 6, param_index); + _mav_put_uint8_t(buf, 24, param_type); + _mav_put_char_array(buf, 8, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#else + mavlink_param_value_t packet; + packet.param_value = param_value; + packet.param_count = param_count; + packet.param_index = param_index; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif +} + +/** + * @brief Encode a param_value struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_value C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value) +{ + return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); +} + +/** + * @brief Encode a param_value struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param param_value C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_value_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_value_t* param_value) +{ + return mavlink_msg_param_value_pack_chan(system_id, component_id, chan, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); +} + +/** + * @brief Send a param_value message + * @param chan MAVLink channel to send the message + * + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint16_t(buf, 4, param_count); + _mav_put_uint16_t(buf, 6, param_index); + _mav_put_uint8_t(buf, 24, param_type); + _mav_put_char_array(buf, 8, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif +#else + mavlink_param_value_t packet; + packet.param_value = param_value; + packet.param_count = param_count; + packet.param_index = param_index; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_PARAM_VALUE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_param_value_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, param_value); + _mav_put_uint16_t(buf, 4, param_count); + _mav_put_uint16_t(buf, 6, param_index); + _mav_put_uint8_t(buf, 24, param_type); + _mav_put_char_array(buf, 8, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif +#else + mavlink_param_value_t *packet = (mavlink_param_value_t *)msgbuf; + packet->param_value = param_value; + packet->param_count = param_count; + packet->param_index = param_index; + packet->param_type = param_type; + mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE PARAM_VALUE UNPACKING + + +/** + * @brief Get field param_id from param_value message + * + * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + */ +static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, char *param_id) +{ + return _MAV_RETURN_char_array(msg, param_id, 16, 8); +} + +/** + * @brief Get field param_value from param_value message + * + * @return Onboard parameter value + */ +static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param_type from param_value message + * + * @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + */ +static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field param_count from param_value message + * + * @return Total number of onboard parameters + */ +static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field param_index from param_value message + * + * @return Index of this onboard parameter + */ +static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Decode a param_value message into a struct + * + * @param msg The message to decode + * @param param_value C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_value->param_value = mavlink_msg_param_value_get_param_value(msg); + param_value->param_count = mavlink_msg_param_value_get_param_count(msg); + param_value->param_index = mavlink_msg_param_value_get_param_index(msg); + mavlink_msg_param_value_get_param_id(msg, param_value->param_id); + param_value->param_type = mavlink_msg_param_value_get_param_type(msg); +#else + memcpy(param_value, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_ping.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_ping.h new file mode 100644 index 0000000..8664675 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_ping.h @@ -0,0 +1,281 @@ +// MESSAGE PING PACKING + +#define MAVLINK_MSG_ID_PING 4 + +typedef struct __mavlink_ping_t +{ + uint64_t time_usec; /*< Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)*/ + uint32_t seq; /*< PING sequence*/ + uint8_t target_system; /*< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system*/ + uint8_t target_component; /*< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system*/ +} mavlink_ping_t; + +#define MAVLINK_MSG_ID_PING_LEN 14 +#define MAVLINK_MSG_ID_4_LEN 14 + +#define MAVLINK_MSG_ID_PING_CRC 237 +#define MAVLINK_MSG_ID_4_CRC 237 + + + +#define MAVLINK_MESSAGE_INFO_PING { \ + "PING", \ + 4, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time_usec) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ping_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ping_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ping_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a ping message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PING_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_LEN); +#else + mavlink_ping_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PING; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_LEN); +#endif +} + +/** + * @brief Pack a ping message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint32_t seq,uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PING_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_LEN); +#else + mavlink_ping_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PING; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_LEN); +#endif +} + +/** + * @brief Encode a ping struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param ping C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping) +{ + return mavlink_msg_ping_pack(system_id, component_id, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component); +} + +/** + * @brief Encode a ping struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param ping C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ping_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ping_t* ping) +{ + return mavlink_msg_ping_pack_chan(system_id, component_id, chan, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component); +} + +/** + * @brief Send a ping message + * @param chan MAVLink channel to send the message + * + * @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PING_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN); +#endif +#else + mavlink_ping_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, MAVLINK_MSG_ID_PING_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_PING_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_ping_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN); +#endif +#else + mavlink_ping_t *packet = (mavlink_ping_t *)msgbuf; + packet->time_usec = time_usec; + packet->seq = seq; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)packet, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)packet, MAVLINK_MSG_ID_PING_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE PING UNPACKING + + +/** + * @brief Get field time_usec from ping message + * + * @return Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) + */ +static inline uint64_t mavlink_msg_ping_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field seq from ping message + * + * @return PING sequence + */ +static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field target_system from ping message + * + * @return 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + */ +static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field target_component from ping message + * + * @return 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + */ +static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 13); +} + +/** + * @brief Decode a ping message into a struct + * + * @param msg The message to decode + * @param ping C-struct to decode the message contents into + */ +static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping) +{ +#if MAVLINK_NEED_BYTE_SWAP + ping->time_usec = mavlink_msg_ping_get_time_usec(msg); + ping->seq = mavlink_msg_ping_get_seq(msg); + ping->target_system = mavlink_msg_ping_get_target_system(msg); + ping->target_component = mavlink_msg_ping_get_target_component(msg); +#else + memcpy(ping, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PING_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_position_target_global_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_position_target_global_int.h new file mode 100644 index 0000000..8416362 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_position_target_global_int.h @@ -0,0 +1,521 @@ +// MESSAGE POSITION_TARGET_GLOBAL_INT PACKING + +#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT 87 + +typedef struct __mavlink_position_target_global_int_t +{ + uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/ + int32_t lat_int; /*< X Position in WGS84 frame in 1e7 * meters*/ + int32_t lon_int; /*< Y Position in WGS84 frame in 1e7 * meters*/ + float alt; /*< Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT*/ + float vx; /*< X velocity in NED frame in meter / s*/ + float vy; /*< Y velocity in NED frame in meter / s*/ + float vz; /*< Z velocity in NED frame in meter / s*/ + float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float yaw; /*< yaw setpoint in rad*/ + float yaw_rate; /*< yaw rate setpoint in rad/s*/ + uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ + uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/ +} mavlink_position_target_global_int_t; + +#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 51 +#define MAVLINK_MSG_ID_87_LEN 51 + +#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC 150 +#define MAVLINK_MSG_ID_87_CRC 150 + + + +#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \ + "POSITION_TARGET_GLOBAL_INT", \ + 14, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \ + { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \ + { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_global_int_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_global_int_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_global_int_t, vz) }, \ + { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_global_int_t, afx) }, \ + { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_global_int_t, afy) }, \ + { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \ + { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a position_target_global_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param lat_int X Position in WGS84 frame in 1e7 * meters + * @param lon_int Y Position in WGS84 frame in 1e7 * meters + * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#else + mavlink_position_target_global_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat_int = lat_int; + packet.lon_int = lon_int; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +} + +/** + * @brief Pack a position_target_global_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param lat_int X Position in WGS84 frame in 1e7 * meters + * @param lon_int Y Position in WGS84 frame in 1e7 * meters + * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#else + mavlink_position_target_global_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat_int = lat_int; + packet.lon_int = lon_int; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +} + +/** + * @brief Encode a position_target_global_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param position_target_global_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int) +{ + return mavlink_msg_position_target_global_int_pack(system_id, component_id, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate); +} + +/** + * @brief Encode a position_target_global_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param position_target_global_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int) +{ + return mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, chan, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate); +} + +/** + * @brief Send a position_target_global_int message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param lat_int X Position in WGS84 frame in 1e7 * meters + * @param lon_int Y Position in WGS84 frame in 1e7 * meters + * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#else + mavlink_position_target_global_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat_int = lat_int; + packet.lon_int = lon_int; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#else + mavlink_position_target_global_int_t *packet = (mavlink_position_target_global_int_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->lat_int = lat_int; + packet->lon_int = lon_int; + packet->alt = alt; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->afx = afx; + packet->afy = afy; + packet->afz = afz; + packet->yaw = yaw; + packet->yaw_rate = yaw_rate; + packet->type_mask = type_mask; + packet->coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE POSITION_TARGET_GLOBAL_INT UNPACKING + + +/** + * @brief Get field time_boot_ms from position_target_global_int message + * + * @return Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + */ +static inline uint32_t mavlink_msg_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field coordinate_frame from position_target_global_int message + * + * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + */ +static inline uint8_t mavlink_msg_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 50); +} + +/** + * @brief Get field type_mask from position_target_global_int message + * + * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + */ +static inline uint16_t mavlink_msg_position_target_global_int_get_type_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 48); +} + +/** + * @brief Get field lat_int from position_target_global_int message + * + * @return X Position in WGS84 frame in 1e7 * meters + */ +static inline int32_t mavlink_msg_position_target_global_int_get_lat_int(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field lon_int from position_target_global_int message + * + * @return Y Position in WGS84 frame in 1e7 * meters + */ +static inline int32_t mavlink_msg_position_target_global_int_get_lon_int(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field alt from position_target_global_int message + * + * @return Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + */ +static inline float mavlink_msg_position_target_global_int_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vx from position_target_global_int message + * + * @return X velocity in NED frame in meter / s + */ +static inline float mavlink_msg_position_target_global_int_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vy from position_target_global_int message + * + * @return Y velocity in NED frame in meter / s + */ +static inline float mavlink_msg_position_target_global_int_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vz from position_target_global_int message + * + * @return Z velocity in NED frame in meter / s + */ +static inline float mavlink_msg_position_target_global_int_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field afx from position_target_global_int message + * + * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_position_target_global_int_get_afx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field afy from position_target_global_int message + * + * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_position_target_global_int_get_afy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field afz from position_target_global_int message + * + * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_position_target_global_int_get_afz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field yaw from position_target_global_int message + * + * @return yaw setpoint in rad + */ +static inline float mavlink_msg_position_target_global_int_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field yaw_rate from position_target_global_int message + * + * @return yaw rate setpoint in rad/s + */ +static inline float mavlink_msg_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Decode a position_target_global_int message into a struct + * + * @param msg The message to decode + * @param position_target_global_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_position_target_global_int_decode(const mavlink_message_t* msg, mavlink_position_target_global_int_t* position_target_global_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + position_target_global_int->time_boot_ms = mavlink_msg_position_target_global_int_get_time_boot_ms(msg); + position_target_global_int->lat_int = mavlink_msg_position_target_global_int_get_lat_int(msg); + position_target_global_int->lon_int = mavlink_msg_position_target_global_int_get_lon_int(msg); + position_target_global_int->alt = mavlink_msg_position_target_global_int_get_alt(msg); + position_target_global_int->vx = mavlink_msg_position_target_global_int_get_vx(msg); + position_target_global_int->vy = mavlink_msg_position_target_global_int_get_vy(msg); + position_target_global_int->vz = mavlink_msg_position_target_global_int_get_vz(msg); + position_target_global_int->afx = mavlink_msg_position_target_global_int_get_afx(msg); + position_target_global_int->afy = mavlink_msg_position_target_global_int_get_afy(msg); + position_target_global_int->afz = mavlink_msg_position_target_global_int_get_afz(msg); + position_target_global_int->yaw = mavlink_msg_position_target_global_int_get_yaw(msg); + position_target_global_int->yaw_rate = mavlink_msg_position_target_global_int_get_yaw_rate(msg); + position_target_global_int->type_mask = mavlink_msg_position_target_global_int_get_type_mask(msg); + position_target_global_int->coordinate_frame = mavlink_msg_position_target_global_int_get_coordinate_frame(msg); +#else + memcpy(position_target_global_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_position_target_local_ned.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_position_target_local_ned.h new file mode 100644 index 0000000..9099159 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_position_target_local_ned.h @@ -0,0 +1,521 @@ +// MESSAGE POSITION_TARGET_LOCAL_NED PACKING + +#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED 85 + +typedef struct __mavlink_position_target_local_ned_t +{ + uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ + float x; /*< X Position in NED frame in meters*/ + float y; /*< Y Position in NED frame in meters*/ + float z; /*< Z Position in NED frame in meters (note, altitude is negative in NED)*/ + float vx; /*< X velocity in NED frame in meter / s*/ + float vy; /*< Y velocity in NED frame in meter / s*/ + float vz; /*< Z velocity in NED frame in meter / s*/ + float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float yaw; /*< yaw setpoint in rad*/ + float yaw_rate; /*< yaw rate setpoint in rad/s*/ + uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ + uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/ +} mavlink_position_target_local_ned_t; + +#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN 51 +#define MAVLINK_MSG_ID_85_LEN 51 + +#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC 140 +#define MAVLINK_MSG_ID_85_CRC 140 + + + +#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED { \ + "POSITION_TARGET_LOCAL_NED", \ + 14, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_local_ned_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_local_ned_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_local_ned_t, z) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_local_ned_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_local_ned_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_local_ned_t, vz) }, \ + { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_local_ned_t, afx) }, \ + { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_local_ned_t, afy) }, \ + { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \ + { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a position_target_local_ned message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param x X Position in NED frame in meters + * @param y Y Position in NED frame in meters + * @param z Z Position in NED frame in meters (note, altitude is negative in NED) + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#else + mavlink_position_target_local_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif +} + +/** + * @brief Pack a position_target_local_ned message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param x X Position in NED frame in meters + * @param y Y Position in NED frame in meters + * @param z Z Position in NED frame in meters (note, altitude is negative in NED) + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#else + mavlink_position_target_local_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif +} + +/** + * @brief Encode a position_target_local_ned struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param position_target_local_ned C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned) +{ + return mavlink_msg_position_target_local_ned_pack(system_id, component_id, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate); +} + +/** + * @brief Encode a position_target_local_ned struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param position_target_local_ned C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned) +{ + return mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate); +} + +/** + * @brief Send a position_target_local_ned message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param x X Position in NED frame in meters + * @param y Y Position in NED frame in meters + * @param z Z Position in NED frame in meters (note, altitude is negative in NED) + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#else + mavlink_position_target_local_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#else + mavlink_position_target_local_ned_t *packet = (mavlink_position_target_local_ned_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->x = x; + packet->y = y; + packet->z = z; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->afx = afx; + packet->afy = afy; + packet->afz = afz; + packet->yaw = yaw; + packet->yaw_rate = yaw_rate; + packet->type_mask = type_mask; + packet->coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE POSITION_TARGET_LOCAL_NED UNPACKING + + +/** + * @brief Get field time_boot_ms from position_target_local_ned message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field coordinate_frame from position_target_local_ned message + * + * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + */ +static inline uint8_t mavlink_msg_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 50); +} + +/** + * @brief Get field type_mask from position_target_local_ned message + * + * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + */ +static inline uint16_t mavlink_msg_position_target_local_ned_get_type_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 48); +} + +/** + * @brief Get field x from position_target_local_ned message + * + * @return X Position in NED frame in meters + */ +static inline float mavlink_msg_position_target_local_ned_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field y from position_target_local_ned message + * + * @return Y Position in NED frame in meters + */ +static inline float mavlink_msg_position_target_local_ned_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field z from position_target_local_ned message + * + * @return Z Position in NED frame in meters (note, altitude is negative in NED) + */ +static inline float mavlink_msg_position_target_local_ned_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vx from position_target_local_ned message + * + * @return X velocity in NED frame in meter / s + */ +static inline float mavlink_msg_position_target_local_ned_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vy from position_target_local_ned message + * + * @return Y velocity in NED frame in meter / s + */ +static inline float mavlink_msg_position_target_local_ned_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vz from position_target_local_ned message + * + * @return Z velocity in NED frame in meter / s + */ +static inline float mavlink_msg_position_target_local_ned_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field afx from position_target_local_ned message + * + * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_position_target_local_ned_get_afx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field afy from position_target_local_ned message + * + * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_position_target_local_ned_get_afy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field afz from position_target_local_ned message + * + * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_position_target_local_ned_get_afz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field yaw from position_target_local_ned message + * + * @return yaw setpoint in rad + */ +static inline float mavlink_msg_position_target_local_ned_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field yaw_rate from position_target_local_ned message + * + * @return yaw rate setpoint in rad/s + */ +static inline float mavlink_msg_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Decode a position_target_local_ned message into a struct + * + * @param msg The message to decode + * @param position_target_local_ned C-struct to decode the message contents into + */ +static inline void mavlink_msg_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_position_target_local_ned_t* position_target_local_ned) +{ +#if MAVLINK_NEED_BYTE_SWAP + position_target_local_ned->time_boot_ms = mavlink_msg_position_target_local_ned_get_time_boot_ms(msg); + position_target_local_ned->x = mavlink_msg_position_target_local_ned_get_x(msg); + position_target_local_ned->y = mavlink_msg_position_target_local_ned_get_y(msg); + position_target_local_ned->z = mavlink_msg_position_target_local_ned_get_z(msg); + position_target_local_ned->vx = mavlink_msg_position_target_local_ned_get_vx(msg); + position_target_local_ned->vy = mavlink_msg_position_target_local_ned_get_vy(msg); + position_target_local_ned->vz = mavlink_msg_position_target_local_ned_get_vz(msg); + position_target_local_ned->afx = mavlink_msg_position_target_local_ned_get_afx(msg); + position_target_local_ned->afy = mavlink_msg_position_target_local_ned_get_afy(msg); + position_target_local_ned->afz = mavlink_msg_position_target_local_ned_get_afz(msg); + position_target_local_ned->yaw = mavlink_msg_position_target_local_ned_get_yaw(msg); + position_target_local_ned->yaw_rate = mavlink_msg_position_target_local_ned_get_yaw_rate(msg); + position_target_local_ned->type_mask = mavlink_msg_position_target_local_ned_get_type_mask(msg); + position_target_local_ned->coordinate_frame = mavlink_msg_position_target_local_ned_get_coordinate_frame(msg); +#else + memcpy(position_target_local_ned, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_power_status.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_power_status.h new file mode 100644 index 0000000..ffe8c84 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_power_status.h @@ -0,0 +1,257 @@ +// MESSAGE POWER_STATUS PACKING + +#define MAVLINK_MSG_ID_POWER_STATUS 125 + +typedef struct __mavlink_power_status_t +{ + uint16_t Vcc; /*< 5V rail voltage in millivolts*/ + uint16_t Vservo; /*< servo rail voltage in millivolts*/ + uint16_t flags; /*< power supply status flags (see MAV_POWER_STATUS enum)*/ +} mavlink_power_status_t; + +#define MAVLINK_MSG_ID_POWER_STATUS_LEN 6 +#define MAVLINK_MSG_ID_125_LEN 6 + +#define MAVLINK_MSG_ID_POWER_STATUS_CRC 203 +#define MAVLINK_MSG_ID_125_CRC 203 + + + +#define MAVLINK_MESSAGE_INFO_POWER_STATUS { \ + "POWER_STATUS", \ + 3, \ + { { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_power_status_t, Vcc) }, \ + { "Vservo", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_power_status_t, Vservo) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_power_status_t, flags) }, \ + } \ +} + + +/** + * @brief Pack a power_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param Vcc 5V rail voltage in millivolts + * @param Vservo servo rail voltage in millivolts + * @param flags power supply status flags (see MAV_POWER_STATUS enum) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_power_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t Vcc, uint16_t Vservo, uint16_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; + _mav_put_uint16_t(buf, 0, Vcc); + _mav_put_uint16_t(buf, 2, Vservo); + _mav_put_uint16_t(buf, 4, flags); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#else + mavlink_power_status_t packet; + packet.Vcc = Vcc; + packet.Vservo = Vservo; + packet.flags = flags; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_POWER_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif +} + +/** + * @brief Pack a power_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param Vcc 5V rail voltage in millivolts + * @param Vservo servo rail voltage in millivolts + * @param flags power supply status flags (see MAV_POWER_STATUS enum) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_power_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t Vcc,uint16_t Vservo,uint16_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; + _mav_put_uint16_t(buf, 0, Vcc); + _mav_put_uint16_t(buf, 2, Vservo); + _mav_put_uint16_t(buf, 4, flags); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#else + mavlink_power_status_t packet; + packet.Vcc = Vcc; + packet.Vservo = Vservo; + packet.flags = flags; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_POWER_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif +} + +/** + * @brief Encode a power_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param power_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_power_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_power_status_t* power_status) +{ + return mavlink_msg_power_status_pack(system_id, component_id, msg, power_status->Vcc, power_status->Vservo, power_status->flags); +} + +/** + * @brief Encode a power_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param power_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_power_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_power_status_t* power_status) +{ + return mavlink_msg_power_status_pack_chan(system_id, component_id, chan, msg, power_status->Vcc, power_status->Vservo, power_status->flags); +} + +/** + * @brief Send a power_status message + * @param chan MAVLink channel to send the message + * + * @param Vcc 5V rail voltage in millivolts + * @param Vservo servo rail voltage in millivolts + * @param flags power supply status flags (see MAV_POWER_STATUS enum) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_power_status_send(mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; + _mav_put_uint16_t(buf, 0, Vcc); + _mav_put_uint16_t(buf, 2, Vservo); + _mav_put_uint16_t(buf, 4, flags); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif +#else + mavlink_power_status_t packet; + packet.Vcc = Vcc; + packet.Vservo = Vservo; + packet.flags = flags; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_POWER_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_power_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, Vcc); + _mav_put_uint16_t(buf, 2, Vservo); + _mav_put_uint16_t(buf, 4, flags); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif +#else + mavlink_power_status_t *packet = (mavlink_power_status_t *)msgbuf; + packet->Vcc = Vcc; + packet->Vservo = Vservo; + packet->flags = flags; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)packet, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE POWER_STATUS UNPACKING + + +/** + * @brief Get field Vcc from power_status message + * + * @return 5V rail voltage in millivolts + */ +static inline uint16_t mavlink_msg_power_status_get_Vcc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field Vservo from power_status message + * + * @return servo rail voltage in millivolts + */ +static inline uint16_t mavlink_msg_power_status_get_Vservo(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Get field flags from power_status message + * + * @return power supply status flags (see MAV_POWER_STATUS enum) + */ +static inline uint16_t mavlink_msg_power_status_get_flags(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Decode a power_status message into a struct + * + * @param msg The message to decode + * @param power_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_power_status_decode(const mavlink_message_t* msg, mavlink_power_status_t* power_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + power_status->Vcc = mavlink_msg_power_status_get_Vcc(msg); + power_status->Vservo = mavlink_msg_power_status_get_Vservo(msg); + power_status->flags = mavlink_msg_power_status_get_flags(msg); +#else + memcpy(power_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_radio_status.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_radio_status.h new file mode 100644 index 0000000..ebb8b67 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_radio_status.h @@ -0,0 +1,353 @@ +// MESSAGE RADIO_STATUS PACKING + +#define MAVLINK_MSG_ID_RADIO_STATUS 109 + +typedef struct __mavlink_radio_status_t +{ + uint16_t rxerrors; /*< Receive errors*/ + uint16_t fixed; /*< Count of error corrected packets*/ + uint8_t rssi; /*< Local signal strength*/ + uint8_t remrssi; /*< Remote signal strength*/ + uint8_t txbuf; /*< Remaining free buffer space in percent.*/ + uint8_t noise; /*< Background noise level*/ + uint8_t remnoise; /*< Remote background noise level*/ +} mavlink_radio_status_t; + +#define MAVLINK_MSG_ID_RADIO_STATUS_LEN 9 +#define MAVLINK_MSG_ID_109_LEN 9 + +#define MAVLINK_MSG_ID_RADIO_STATUS_CRC 185 +#define MAVLINK_MSG_ID_109_CRC 185 + + + +#define MAVLINK_MESSAGE_INFO_RADIO_STATUS { \ + "RADIO_STATUS", \ + 7, \ + { { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \ + { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \ + { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_status_t, remrssi) }, \ + { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_status_t, txbuf) }, \ + { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_status_t, noise) }, \ + { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_status_t, remnoise) }, \ + } \ +} + + +/** + * @brief Pack a radio_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param rssi Local signal strength + * @param remrssi Remote signal strength + * @param txbuf Remaining free buffer space in percent. + * @param noise Background noise level + * @param remnoise Remote background noise level + * @param rxerrors Receive errors + * @param fixed Count of error corrected packets + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_radio_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN]; + _mav_put_uint16_t(buf, 0, rxerrors); + _mav_put_uint16_t(buf, 2, fixed); + _mav_put_uint8_t(buf, 4, rssi); + _mav_put_uint8_t(buf, 5, remrssi); + _mav_put_uint8_t(buf, 6, txbuf); + _mav_put_uint8_t(buf, 7, noise); + _mav_put_uint8_t(buf, 8, remnoise); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#else + mavlink_radio_status_t packet; + packet.rxerrors = rxerrors; + packet.fixed = fixed; + packet.rssi = rssi; + packet.remrssi = remrssi; + packet.txbuf = txbuf; + packet.noise = noise; + packet.remnoise = remnoise; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RADIO_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +} + +/** + * @brief Pack a radio_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rssi Local signal strength + * @param remrssi Remote signal strength + * @param txbuf Remaining free buffer space in percent. + * @param noise Background noise level + * @param remnoise Remote background noise level + * @param rxerrors Receive errors + * @param fixed Count of error corrected packets + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_radio_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN]; + _mav_put_uint16_t(buf, 0, rxerrors); + _mav_put_uint16_t(buf, 2, fixed); + _mav_put_uint8_t(buf, 4, rssi); + _mav_put_uint8_t(buf, 5, remrssi); + _mav_put_uint8_t(buf, 6, txbuf); + _mav_put_uint8_t(buf, 7, noise); + _mav_put_uint8_t(buf, 8, remnoise); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#else + mavlink_radio_status_t packet; + packet.rxerrors = rxerrors; + packet.fixed = fixed; + packet.rssi = rssi; + packet.remrssi = remrssi; + packet.txbuf = txbuf; + packet.noise = noise; + packet.remnoise = remnoise; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RADIO_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +} + +/** + * @brief Encode a radio_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param radio_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_radio_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_status_t* radio_status) +{ + return mavlink_msg_radio_status_pack(system_id, component_id, msg, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed); +} + +/** + * @brief Encode a radio_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param radio_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_radio_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_radio_status_t* radio_status) +{ + return mavlink_msg_radio_status_pack_chan(system_id, component_id, chan, msg, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed); +} + +/** + * @brief Send a radio_status message + * @param chan MAVLink channel to send the message + * + * @param rssi Local signal strength + * @param remrssi Remote signal strength + * @param txbuf Remaining free buffer space in percent. + * @param noise Background noise level + * @param remnoise Remote background noise level + * @param rxerrors Receive errors + * @param fixed Count of error corrected packets + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_radio_status_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN]; + _mav_put_uint16_t(buf, 0, rxerrors); + _mav_put_uint16_t(buf, 2, fixed); + _mav_put_uint8_t(buf, 4, rssi); + _mav_put_uint8_t(buf, 5, remrssi); + _mav_put_uint8_t(buf, 6, txbuf); + _mav_put_uint8_t(buf, 7, noise); + _mav_put_uint8_t(buf, 8, remnoise); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +#else + mavlink_radio_status_t packet; + packet.rxerrors = rxerrors; + packet.fixed = fixed; + packet.rssi = rssi; + packet.remrssi = remrssi; + packet.txbuf = txbuf; + packet.noise = noise; + packet.remnoise = remnoise; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)&packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)&packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RADIO_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_radio_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, rxerrors); + _mav_put_uint16_t(buf, 2, fixed); + _mav_put_uint8_t(buf, 4, rssi); + _mav_put_uint8_t(buf, 5, remrssi); + _mav_put_uint8_t(buf, 6, txbuf); + _mav_put_uint8_t(buf, 7, noise); + _mav_put_uint8_t(buf, 8, remnoise); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +#else + mavlink_radio_status_t *packet = (mavlink_radio_status_t *)msgbuf; + packet->rxerrors = rxerrors; + packet->fixed = fixed; + packet->rssi = rssi; + packet->remrssi = remrssi; + packet->txbuf = txbuf; + packet->noise = noise; + packet->remnoise = remnoise; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RADIO_STATUS UNPACKING + + +/** + * @brief Get field rssi from radio_status message + * + * @return Local signal strength + */ +static inline uint8_t mavlink_msg_radio_status_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field remrssi from radio_status message + * + * @return Remote signal strength + */ +static inline uint8_t mavlink_msg_radio_status_get_remrssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field txbuf from radio_status message + * + * @return Remaining free buffer space in percent. + */ +static inline uint8_t mavlink_msg_radio_status_get_txbuf(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field noise from radio_status message + * + * @return Background noise level + */ +static inline uint8_t mavlink_msg_radio_status_get_noise(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field remnoise from radio_status message + * + * @return Remote background noise level + */ +static inline uint8_t mavlink_msg_radio_status_get_remnoise(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field rxerrors from radio_status message + * + * @return Receive errors + */ +static inline uint16_t mavlink_msg_radio_status_get_rxerrors(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field fixed from radio_status message + * + * @return Count of error corrected packets + */ +static inline uint16_t mavlink_msg_radio_status_get_fixed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Decode a radio_status message into a struct + * + * @param msg The message to decode + * @param radio_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_radio_status_decode(const mavlink_message_t* msg, mavlink_radio_status_t* radio_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + radio_status->rxerrors = mavlink_msg_radio_status_get_rxerrors(msg); + radio_status->fixed = mavlink_msg_radio_status_get_fixed(msg); + radio_status->rssi = mavlink_msg_radio_status_get_rssi(msg); + radio_status->remrssi = mavlink_msg_radio_status_get_remrssi(msg); + radio_status->txbuf = mavlink_msg_radio_status_get_txbuf(msg); + radio_status->noise = mavlink_msg_radio_status_get_noise(msg); + radio_status->remnoise = mavlink_msg_radio_status_get_remnoise(msg); +#else + memcpy(radio_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_raw_imu.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_raw_imu.h new file mode 100644 index 0000000..212ad73 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_raw_imu.h @@ -0,0 +1,425 @@ +// MESSAGE RAW_IMU PACKING + +#define MAVLINK_MSG_ID_RAW_IMU 27 + +typedef struct __mavlink_raw_imu_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + int16_t xacc; /*< X acceleration (raw)*/ + int16_t yacc; /*< Y acceleration (raw)*/ + int16_t zacc; /*< Z acceleration (raw)*/ + int16_t xgyro; /*< Angular speed around X axis (raw)*/ + int16_t ygyro; /*< Angular speed around Y axis (raw)*/ + int16_t zgyro; /*< Angular speed around Z axis (raw)*/ + int16_t xmag; /*< X Magnetic field (raw)*/ + int16_t ymag; /*< Y Magnetic field (raw)*/ + int16_t zmag; /*< Z Magnetic field (raw)*/ +} mavlink_raw_imu_t; + +#define MAVLINK_MSG_ID_RAW_IMU_LEN 26 +#define MAVLINK_MSG_ID_27_LEN 26 + +#define MAVLINK_MSG_ID_RAW_IMU_CRC 144 +#define MAVLINK_MSG_ID_27_CRC 144 + + + +#define MAVLINK_MESSAGE_INFO_RAW_IMU { \ + "RAW_IMU", \ + 10, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \ + } \ +} + + +/** + * @brief Pack a raw_imu message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RAW_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, xacc); + _mav_put_int16_t(buf, 10, yacc); + _mav_put_int16_t(buf, 12, zacc); + _mav_put_int16_t(buf, 14, xgyro); + _mav_put_int16_t(buf, 16, ygyro); + _mav_put_int16_t(buf, 18, zgyro); + _mav_put_int16_t(buf, 20, xmag); + _mav_put_int16_t(buf, 22, ymag); + _mav_put_int16_t(buf, 24, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN); +#else + mavlink_raw_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif +} + +/** + * @brief Pack a raw_imu message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RAW_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, xacc); + _mav_put_int16_t(buf, 10, yacc); + _mav_put_int16_t(buf, 12, zacc); + _mav_put_int16_t(buf, 14, xgyro); + _mav_put_int16_t(buf, 16, ygyro); + _mav_put_int16_t(buf, 18, zgyro); + _mav_put_int16_t(buf, 20, xmag); + _mav_put_int16_t(buf, 22, ymag); + _mav_put_int16_t(buf, 24, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN); +#else + mavlink_raw_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif +} + +/** + * @brief Encode a raw_imu struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param raw_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) +{ + return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); +} + +/** + * @brief Encode a raw_imu struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param raw_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) +{ + return mavlink_msg_raw_imu_pack_chan(system_id, component_id, chan, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); +} + +/** + * @brief Send a raw_imu message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RAW_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, xacc); + _mav_put_int16_t(buf, 10, yacc); + _mav_put_int16_t(buf, 12, zacc); + _mav_put_int16_t(buf, 14, xgyro); + _mav_put_int16_t(buf, 16, ygyro); + _mav_put_int16_t(buf, 18, zgyro); + _mav_put_int16_t(buf, 20, xmag); + _mav_put_int16_t(buf, 22, ymag); + _mav_put_int16_t(buf, 24, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif +#else + mavlink_raw_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RAW_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_raw_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, xacc); + _mav_put_int16_t(buf, 10, yacc); + _mav_put_int16_t(buf, 12, zacc); + _mav_put_int16_t(buf, 14, xgyro); + _mav_put_int16_t(buf, 16, ygyro); + _mav_put_int16_t(buf, 18, zgyro); + _mav_put_int16_t(buf, 20, xmag); + _mav_put_int16_t(buf, 22, ymag); + _mav_put_int16_t(buf, 24, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif +#else + mavlink_raw_imu_t *packet = (mavlink_raw_imu_t *)msgbuf; + packet->time_usec = time_usec; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->xmag = xmag; + packet->ymag = ymag; + packet->zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)packet, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)packet, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RAW_IMU UNPACKING + + +/** + * @brief Get field time_usec from raw_imu message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_raw_imu_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field xacc from raw_imu message + * + * @return X acceleration (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field yacc from raw_imu message + * + * @return Y acceleration (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field zacc from raw_imu message + * + * @return Z acceleration (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field xgyro from raw_imu message + * + * @return Angular speed around X axis (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field ygyro from raw_imu message + * + * @return Angular speed around Y axis (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field zgyro from raw_imu message + * + * @return Angular speed around Z axis (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field xmag from raw_imu message + * + * @return X Magnetic field (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field ymag from raw_imu message + * + * @return Y Magnetic field (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field zmag from raw_imu message + * + * @return Z Magnetic field (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 24); +} + +/** + * @brief Decode a raw_imu message into a struct + * + * @param msg The message to decode + * @param raw_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu) +{ +#if MAVLINK_NEED_BYTE_SWAP + raw_imu->time_usec = mavlink_msg_raw_imu_get_time_usec(msg); + raw_imu->xacc = mavlink_msg_raw_imu_get_xacc(msg); + raw_imu->yacc = mavlink_msg_raw_imu_get_yacc(msg); + raw_imu->zacc = mavlink_msg_raw_imu_get_zacc(msg); + raw_imu->xgyro = mavlink_msg_raw_imu_get_xgyro(msg); + raw_imu->ygyro = mavlink_msg_raw_imu_get_ygyro(msg); + raw_imu->zgyro = mavlink_msg_raw_imu_get_zgyro(msg); + raw_imu->xmag = mavlink_msg_raw_imu_get_xmag(msg); + raw_imu->ymag = mavlink_msg_raw_imu_get_ymag(msg); + raw_imu->zmag = mavlink_msg_raw_imu_get_zmag(msg); +#else + memcpy(raw_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_raw_pressure.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_raw_pressure.h new file mode 100644 index 0000000..f17ad48 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_raw_pressure.h @@ -0,0 +1,305 @@ +// MESSAGE RAW_PRESSURE PACKING + +#define MAVLINK_MSG_ID_RAW_PRESSURE 28 + +typedef struct __mavlink_raw_pressure_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + int16_t press_abs; /*< Absolute pressure (raw)*/ + int16_t press_diff1; /*< Differential pressure 1 (raw, 0 if nonexistant)*/ + int16_t press_diff2; /*< Differential pressure 2 (raw, 0 if nonexistant)*/ + int16_t temperature; /*< Raw Temperature measurement (raw)*/ +} mavlink_raw_pressure_t; + +#define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16 +#define MAVLINK_MSG_ID_28_LEN 16 + +#define MAVLINK_MSG_ID_RAW_PRESSURE_CRC 67 +#define MAVLINK_MSG_ID_28_CRC 67 + + + +#define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \ + "RAW_PRESSURE", \ + 5, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \ + { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \ + { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \ + { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a raw_pressure message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistant) + * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistant) + * @param temperature Raw Temperature measurement (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, press_abs); + _mav_put_int16_t(buf, 10, press_diff1); + _mav_put_int16_t(buf, 12, press_diff2); + _mav_put_int16_t(buf, 14, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#else + mavlink_raw_pressure_t packet; + packet.time_usec = time_usec; + packet.press_abs = press_abs; + packet.press_diff1 = press_diff1; + packet.press_diff2 = press_diff2; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif +} + +/** + * @brief Pack a raw_pressure message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistant) + * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistant) + * @param temperature Raw Temperature measurement (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,int16_t press_abs,int16_t press_diff1,int16_t press_diff2,int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, press_abs); + _mav_put_int16_t(buf, 10, press_diff1); + _mav_put_int16_t(buf, 12, press_diff2); + _mav_put_int16_t(buf, 14, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#else + mavlink_raw_pressure_t packet; + packet.time_usec = time_usec; + packet.press_abs = press_abs; + packet.press_diff1 = press_diff1; + packet.press_diff2 = press_diff2; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif +} + +/** + * @brief Encode a raw_pressure struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param raw_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) +{ + return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); +} + +/** + * @brief Encode a raw_pressure struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param raw_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) +{ + return mavlink_msg_raw_pressure_pack_chan(system_id, component_id, chan, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); +} + +/** + * @brief Send a raw_pressure message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistant) + * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistant) + * @param temperature Raw Temperature measurement (raw) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, press_abs); + _mav_put_int16_t(buf, 10, press_diff1); + _mav_put_int16_t(buf, 12, press_diff2); + _mav_put_int16_t(buf, 14, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif +#else + mavlink_raw_pressure_t packet; + packet.time_usec = time_usec; + packet.press_abs = press_abs; + packet.press_diff1 = press_diff1; + packet.press_diff2 = press_diff2; + packet.temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RAW_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_raw_pressure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, press_abs); + _mav_put_int16_t(buf, 10, press_diff1); + _mav_put_int16_t(buf, 12, press_diff2); + _mav_put_int16_t(buf, 14, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif +#else + mavlink_raw_pressure_t *packet = (mavlink_raw_pressure_t *)msgbuf; + packet->time_usec = time_usec; + packet->press_abs = press_abs; + packet->press_diff1 = press_diff1; + packet->press_diff2 = press_diff2; + packet->temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RAW_PRESSURE UNPACKING + + +/** + * @brief Get field time_usec from raw_pressure message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field press_abs from raw_pressure message + * + * @return Absolute pressure (raw) + */ +static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field press_diff1 from raw_pressure message + * + * @return Differential pressure 1 (raw, 0 if nonexistant) + */ +static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field press_diff2 from raw_pressure message + * + * @return Differential pressure 2 (raw, 0 if nonexistant) + */ +static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field temperature from raw_pressure message + * + * @return Raw Temperature measurement (raw) + */ +static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Decode a raw_pressure message into a struct + * + * @param msg The message to decode + * @param raw_pressure C-struct to decode the message contents into + */ +static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure) +{ +#if MAVLINK_NEED_BYTE_SWAP + raw_pressure->time_usec = mavlink_msg_raw_pressure_get_time_usec(msg); + raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg); + raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg); + raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg); + raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg); +#else + memcpy(raw_pressure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_rc_channels.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_rc_channels.h new file mode 100644 index 0000000..b4ece26 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_rc_channels.h @@ -0,0 +1,689 @@ +// MESSAGE RC_CHANNELS PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS 65 + +typedef struct __mavlink_rc_channels_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan9_raw; /*< RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan10_raw; /*< RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan11_raw; /*< RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan12_raw; /*< RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan13_raw; /*< RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan14_raw; /*< RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan15_raw; /*< RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan16_raw; /*< RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan17_raw; /*< RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan18_raw; /*< RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint8_t chancount; /*< Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.*/ + uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/ +} mavlink_rc_channels_t; + +#define MAVLINK_MSG_ID_RC_CHANNELS_LEN 42 +#define MAVLINK_MSG_ID_65_LEN 42 + +#define MAVLINK_MSG_ID_RC_CHANNELS_CRC 118 +#define MAVLINK_MSG_ID_65_CRC 118 + + + +#define MAVLINK_MESSAGE_INFO_RC_CHANNELS { \ + "RC_CHANNELS", \ + 21, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \ + { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \ + { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \ + { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \ + { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \ + { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \ + { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \ + { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \ + { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \ + { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \ + { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \ + { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \ + { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \ + } \ +} + + +/** + * @brief Pack a rc_channels message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint16_t(buf, 20, chan9_raw); + _mav_put_uint16_t(buf, 22, chan10_raw); + _mav_put_uint16_t(buf, 24, chan11_raw); + _mav_put_uint16_t(buf, 26, chan12_raw); + _mav_put_uint16_t(buf, 28, chan13_raw); + _mav_put_uint16_t(buf, 30, chan14_raw); + _mav_put_uint16_t(buf, 32, chan15_raw); + _mav_put_uint16_t(buf, 34, chan16_raw); + _mav_put_uint16_t(buf, 36, chan17_raw); + _mav_put_uint16_t(buf, 38, chan18_raw); + _mav_put_uint8_t(buf, 40, chancount); + _mav_put_uint8_t(buf, 41, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#else + mavlink_rc_channels_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.chan13_raw = chan13_raw; + packet.chan14_raw = chan14_raw; + packet.chan15_raw = chan15_raw; + packet.chan16_raw = chan16_raw; + packet.chan17_raw = chan17_raw; + packet.chan18_raw = chan18_raw; + packet.chancount = chancount; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif +} + +/** + * @brief Pack a rc_channels message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t chancount,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint16_t chan13_raw,uint16_t chan14_raw,uint16_t chan15_raw,uint16_t chan16_raw,uint16_t chan17_raw,uint16_t chan18_raw,uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint16_t(buf, 20, chan9_raw); + _mav_put_uint16_t(buf, 22, chan10_raw); + _mav_put_uint16_t(buf, 24, chan11_raw); + _mav_put_uint16_t(buf, 26, chan12_raw); + _mav_put_uint16_t(buf, 28, chan13_raw); + _mav_put_uint16_t(buf, 30, chan14_raw); + _mav_put_uint16_t(buf, 32, chan15_raw); + _mav_put_uint16_t(buf, 34, chan16_raw); + _mav_put_uint16_t(buf, 36, chan17_raw); + _mav_put_uint16_t(buf, 38, chan18_raw); + _mav_put_uint8_t(buf, 40, chancount); + _mav_put_uint8_t(buf, 41, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#else + mavlink_rc_channels_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.chan13_raw = chan13_raw; + packet.chan14_raw = chan14_raw; + packet.chan15_raw = chan15_raw; + packet.chan16_raw = chan16_raw; + packet.chan17_raw = chan17_raw; + packet.chan18_raw = chan18_raw; + packet.chancount = chancount; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif +} + +/** + * @brief Encode a rc_channels struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rc_channels C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels) +{ + return mavlink_msg_rc_channels_pack(system_id, component_id, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi); +} + +/** + * @brief Encode a rc_channels struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rc_channels C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels) +{ + return mavlink_msg_rc_channels_pack_chan(system_id, component_id, chan, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi); +} + +/** + * @brief Send a rc_channels message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint16_t(buf, 20, chan9_raw); + _mav_put_uint16_t(buf, 22, chan10_raw); + _mav_put_uint16_t(buf, 24, chan11_raw); + _mav_put_uint16_t(buf, 26, chan12_raw); + _mav_put_uint16_t(buf, 28, chan13_raw); + _mav_put_uint16_t(buf, 30, chan14_raw); + _mav_put_uint16_t(buf, 32, chan15_raw); + _mav_put_uint16_t(buf, 34, chan16_raw); + _mav_put_uint16_t(buf, 36, chan17_raw); + _mav_put_uint16_t(buf, 38, chan18_raw); + _mav_put_uint8_t(buf, 40, chancount); + _mav_put_uint8_t(buf, 41, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif +#else + mavlink_rc_channels_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.chan13_raw = chan13_raw; + packet.chan14_raw = chan14_raw; + packet.chan15_raw = chan15_raw; + packet.chan16_raw = chan16_raw; + packet.chan17_raw = chan17_raw; + packet.chan18_raw = chan18_raw; + packet.chancount = chancount; + packet.rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RC_CHANNELS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rc_channels_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint16_t(buf, 20, chan9_raw); + _mav_put_uint16_t(buf, 22, chan10_raw); + _mav_put_uint16_t(buf, 24, chan11_raw); + _mav_put_uint16_t(buf, 26, chan12_raw); + _mav_put_uint16_t(buf, 28, chan13_raw); + _mav_put_uint16_t(buf, 30, chan14_raw); + _mav_put_uint16_t(buf, 32, chan15_raw); + _mav_put_uint16_t(buf, 34, chan16_raw); + _mav_put_uint16_t(buf, 36, chan17_raw); + _mav_put_uint16_t(buf, 38, chan18_raw); + _mav_put_uint8_t(buf, 40, chancount); + _mav_put_uint8_t(buf, 41, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif +#else + mavlink_rc_channels_t *packet = (mavlink_rc_channels_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->chan1_raw = chan1_raw; + packet->chan2_raw = chan2_raw; + packet->chan3_raw = chan3_raw; + packet->chan4_raw = chan4_raw; + packet->chan5_raw = chan5_raw; + packet->chan6_raw = chan6_raw; + packet->chan7_raw = chan7_raw; + packet->chan8_raw = chan8_raw; + packet->chan9_raw = chan9_raw; + packet->chan10_raw = chan10_raw; + packet->chan11_raw = chan11_raw; + packet->chan12_raw = chan12_raw; + packet->chan13_raw = chan13_raw; + packet->chan14_raw = chan14_raw; + packet->chan15_raw = chan15_raw; + packet->chan16_raw = chan16_raw; + packet->chan17_raw = chan17_raw; + packet->chan18_raw = chan18_raw; + packet->chancount = chancount; + packet->rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RC_CHANNELS UNPACKING + + +/** + * @brief Get field time_boot_ms from rc_channels message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_rc_channels_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field chancount from rc_channels message + * + * @return Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + */ +static inline uint8_t mavlink_msg_rc_channels_get_chancount(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 40); +} + +/** + * @brief Get field chan1_raw from rc_channels message + * + * @return RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field chan2_raw from rc_channels message + * + * @return RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field chan3_raw from rc_channels message + * + * @return RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field chan4_raw from rc_channels message + * + * @return RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field chan5_raw from rc_channels message + * + * @return RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field chan6_raw from rc_channels message + * + * @return RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field chan7_raw from rc_channels message + * + * @return RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field chan8_raw from rc_channels message + * + * @return RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field chan9_raw from rc_channels message + * + * @return RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan9_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field chan10_raw from rc_channels message + * + * @return RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan10_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field chan11_raw from rc_channels message + * + * @return RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan11_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field chan12_raw from rc_channels message + * + * @return RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan12_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field chan13_raw from rc_channels message + * + * @return RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan13_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field chan14_raw from rc_channels message + * + * @return RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan14_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 30); +} + +/** + * @brief Get field chan15_raw from rc_channels message + * + * @return RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan15_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 32); +} + +/** + * @brief Get field chan16_raw from rc_channels message + * + * @return RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan16_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 34); +} + +/** + * @brief Get field chan17_raw from rc_channels message + * + * @return RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan17_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 36); +} + +/** + * @brief Get field chan18_raw from rc_channels message + * + * @return RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan18_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 38); +} + +/** + * @brief Get field rssi from rc_channels message + * + * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + */ +static inline uint8_t mavlink_msg_rc_channels_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 41); +} + +/** + * @brief Decode a rc_channels message into a struct + * + * @param msg The message to decode + * @param rc_channels C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_decode(const mavlink_message_t* msg, mavlink_rc_channels_t* rc_channels) +{ +#if MAVLINK_NEED_BYTE_SWAP + rc_channels->time_boot_ms = mavlink_msg_rc_channels_get_time_boot_ms(msg); + rc_channels->chan1_raw = mavlink_msg_rc_channels_get_chan1_raw(msg); + rc_channels->chan2_raw = mavlink_msg_rc_channels_get_chan2_raw(msg); + rc_channels->chan3_raw = mavlink_msg_rc_channels_get_chan3_raw(msg); + rc_channels->chan4_raw = mavlink_msg_rc_channels_get_chan4_raw(msg); + rc_channels->chan5_raw = mavlink_msg_rc_channels_get_chan5_raw(msg); + rc_channels->chan6_raw = mavlink_msg_rc_channels_get_chan6_raw(msg); + rc_channels->chan7_raw = mavlink_msg_rc_channels_get_chan7_raw(msg); + rc_channels->chan8_raw = mavlink_msg_rc_channels_get_chan8_raw(msg); + rc_channels->chan9_raw = mavlink_msg_rc_channels_get_chan9_raw(msg); + rc_channels->chan10_raw = mavlink_msg_rc_channels_get_chan10_raw(msg); + rc_channels->chan11_raw = mavlink_msg_rc_channels_get_chan11_raw(msg); + rc_channels->chan12_raw = mavlink_msg_rc_channels_get_chan12_raw(msg); + rc_channels->chan13_raw = mavlink_msg_rc_channels_get_chan13_raw(msg); + rc_channels->chan14_raw = mavlink_msg_rc_channels_get_chan14_raw(msg); + rc_channels->chan15_raw = mavlink_msg_rc_channels_get_chan15_raw(msg); + rc_channels->chan16_raw = mavlink_msg_rc_channels_get_chan16_raw(msg); + rc_channels->chan17_raw = mavlink_msg_rc_channels_get_chan17_raw(msg); + rc_channels->chan18_raw = mavlink_msg_rc_channels_get_chan18_raw(msg); + rc_channels->chancount = mavlink_msg_rc_channels_get_chancount(msg); + rc_channels->rssi = mavlink_msg_rc_channels_get_rssi(msg); +#else + memcpy(rc_channels, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h new file mode 100644 index 0000000..0324706 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h @@ -0,0 +1,425 @@ +// MESSAGE RC_CHANNELS_OVERRIDE PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70 + +typedef struct __mavlink_rc_channels_override_t +{ + uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_rc_channels_override_t; + +#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18 +#define MAVLINK_MSG_ID_70_LEN 18 + +#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC 124 +#define MAVLINK_MSG_ID_70_CRC 124 + + + +#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \ + "RC_CHANNELS_OVERRIDE", \ + 10, \ + { { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a rc_channels_override message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN]; + _mav_put_uint16_t(buf, 0, chan1_raw); + _mav_put_uint16_t(buf, 2, chan2_raw); + _mav_put_uint16_t(buf, 4, chan3_raw); + _mav_put_uint16_t(buf, 6, chan4_raw); + _mav_put_uint16_t(buf, 8, chan5_raw); + _mav_put_uint16_t(buf, 10, chan6_raw); + _mav_put_uint16_t(buf, 12, chan7_raw); + _mav_put_uint16_t(buf, 14, chan8_raw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#else + mavlink_rc_channels_override_t packet; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif +} + +/** + * @brief Pack a rc_channels_override message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN]; + _mav_put_uint16_t(buf, 0, chan1_raw); + _mav_put_uint16_t(buf, 2, chan2_raw); + _mav_put_uint16_t(buf, 4, chan3_raw); + _mav_put_uint16_t(buf, 6, chan4_raw); + _mav_put_uint16_t(buf, 8, chan5_raw); + _mav_put_uint16_t(buf, 10, chan6_raw); + _mav_put_uint16_t(buf, 12, chan7_raw); + _mav_put_uint16_t(buf, 14, chan8_raw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#else + mavlink_rc_channels_override_t packet; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif +} + +/** + * @brief Encode a rc_channels_override struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rc_channels_override C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override) +{ + return mavlink_msg_rc_channels_override_pack(system_id, component_id, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw); +} + +/** + * @brief Encode a rc_channels_override struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rc_channels_override C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_override_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override) +{ + return mavlink_msg_rc_channels_override_pack_chan(system_id, component_id, chan, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw); +} + +/** + * @brief Send a rc_channels_override message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_override_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN]; + _mav_put_uint16_t(buf, 0, chan1_raw); + _mav_put_uint16_t(buf, 2, chan2_raw); + _mav_put_uint16_t(buf, 4, chan3_raw); + _mav_put_uint16_t(buf, 6, chan4_raw); + _mav_put_uint16_t(buf, 8, chan5_raw); + _mav_put_uint16_t(buf, 10, chan6_raw); + _mav_put_uint16_t(buf, 12, chan7_raw); + _mav_put_uint16_t(buf, 14, chan8_raw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif +#else + mavlink_rc_channels_override_t packet; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rc_channels_override_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, chan1_raw); + _mav_put_uint16_t(buf, 2, chan2_raw); + _mav_put_uint16_t(buf, 4, chan3_raw); + _mav_put_uint16_t(buf, 6, chan4_raw); + _mav_put_uint16_t(buf, 8, chan5_raw); + _mav_put_uint16_t(buf, 10, chan6_raw); + _mav_put_uint16_t(buf, 12, chan7_raw); + _mav_put_uint16_t(buf, 14, chan8_raw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif +#else + mavlink_rc_channels_override_t *packet = (mavlink_rc_channels_override_t *)msgbuf; + packet->chan1_raw = chan1_raw; + packet->chan2_raw = chan2_raw; + packet->chan3_raw = chan3_raw; + packet->chan4_raw = chan4_raw; + packet->chan5_raw = chan5_raw; + packet->chan6_raw = chan6_raw; + packet->chan7_raw = chan7_raw; + packet->chan8_raw = chan8_raw; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RC_CHANNELS_OVERRIDE UNPACKING + + +/** + * @brief Get field target_system from rc_channels_override message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_rc_channels_override_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field target_component from rc_channels_override message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field chan1_raw from rc_channels_override message + * + * @return RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field chan2_raw from rc_channels_override message + * + * @return RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Get field chan3_raw from rc_channels_override message + * + * @return RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field chan4_raw from rc_channels_override message + * + * @return RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field chan5_raw from rc_channels_override message + * + * @return RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field chan6_raw from rc_channels_override message + * + * @return RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field chan7_raw from rc_channels_override message + * + * @return RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field chan8_raw from rc_channels_override message + * + * @return RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Decode a rc_channels_override message into a struct + * + * @param msg The message to decode + * @param rc_channels_override C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_override_decode(const mavlink_message_t* msg, mavlink_rc_channels_override_t* rc_channels_override) +{ +#if MAVLINK_NEED_BYTE_SWAP + rc_channels_override->chan1_raw = mavlink_msg_rc_channels_override_get_chan1_raw(msg); + rc_channels_override->chan2_raw = mavlink_msg_rc_channels_override_get_chan2_raw(msg); + rc_channels_override->chan3_raw = mavlink_msg_rc_channels_override_get_chan3_raw(msg); + rc_channels_override->chan4_raw = mavlink_msg_rc_channels_override_get_chan4_raw(msg); + rc_channels_override->chan5_raw = mavlink_msg_rc_channels_override_get_chan5_raw(msg); + rc_channels_override->chan6_raw = mavlink_msg_rc_channels_override_get_chan6_raw(msg); + rc_channels_override->chan7_raw = mavlink_msg_rc_channels_override_get_chan7_raw(msg); + rc_channels_override->chan8_raw = mavlink_msg_rc_channels_override_get_chan8_raw(msg); + rc_channels_override->target_system = mavlink_msg_rc_channels_override_get_target_system(msg); + rc_channels_override->target_component = mavlink_msg_rc_channels_override_get_target_component(msg); +#else + memcpy(rc_channels_override, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h new file mode 100644 index 0000000..d9ba874 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h @@ -0,0 +1,449 @@ +// MESSAGE RC_CHANNELS_RAW PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35 + +typedef struct __mavlink_rc_channels_raw_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.*/ + uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/ +} mavlink_rc_channels_raw_t; + +#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22 +#define MAVLINK_MSG_ID_35_LEN 22 + +#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC 244 +#define MAVLINK_MSG_ID_35_CRC 244 + + + +#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \ + "RC_CHANNELS_RAW", \ + 11, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, time_boot_ms) }, \ + { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_raw_t, rssi) }, \ + } \ +} + + +/** + * @brief Pack a rc_channels_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#else + mavlink_rc_channels_raw_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif +} + +/** + * @brief Pack a rc_channels_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t port,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#else + mavlink_rc_channels_raw_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif +} + +/** + * @brief Encode a rc_channels_raw struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rc_channels_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) +{ + return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); +} + +/** + * @brief Encode a rc_channels_raw struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rc_channels_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) +{ + return mavlink_msg_rc_channels_raw_pack_chan(system_id, component_id, chan, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); +} + +/** + * @brief Send a rc_channels_raw message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif +#else + mavlink_rc_channels_raw_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.port = port; + packet.rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rc_channels_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif +#else + mavlink_rc_channels_raw_t *packet = (mavlink_rc_channels_raw_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->chan1_raw = chan1_raw; + packet->chan2_raw = chan2_raw; + packet->chan3_raw = chan3_raw; + packet->chan4_raw = chan4_raw; + packet->chan5_raw = chan5_raw; + packet->chan6_raw = chan6_raw; + packet->chan7_raw = chan7_raw; + packet->chan8_raw = chan8_raw; + packet->port = port; + packet->rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RC_CHANNELS_RAW UNPACKING + + +/** + * @brief Get field time_boot_ms from rc_channels_raw message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_rc_channels_raw_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field port from rc_channels_raw message + * + * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + */ +static inline uint8_t mavlink_msg_rc_channels_raw_get_port(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field chan1_raw from rc_channels_raw message + * + * @return RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field chan2_raw from rc_channels_raw message + * + * @return RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field chan3_raw from rc_channels_raw message + * + * @return RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field chan4_raw from rc_channels_raw message + * + * @return RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field chan5_raw from rc_channels_raw message + * + * @return RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field chan6_raw from rc_channels_raw message + * + * @return RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field chan7_raw from rc_channels_raw message + * + * @return RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field chan8_raw from rc_channels_raw message + * + * @return RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field rssi from rc_channels_raw message + * + * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + */ +static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 21); +} + +/** + * @brief Decode a rc_channels_raw message into a struct + * + * @param msg The message to decode + * @param rc_channels_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + rc_channels_raw->time_boot_ms = mavlink_msg_rc_channels_raw_get_time_boot_ms(msg); + rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg); + rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg); + rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg); + rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg); + rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg); + rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg); + rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg); + rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg); + rc_channels_raw->port = mavlink_msg_rc_channels_raw_get_port(msg); + rc_channels_raw->rssi = mavlink_msg_rc_channels_raw_get_rssi(msg); +#else + memcpy(rc_channels_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h new file mode 100644 index 0000000..c9d0c17 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h @@ -0,0 +1,449 @@ +// MESSAGE RC_CHANNELS_SCALED PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED 34 + +typedef struct __mavlink_rc_channels_scaled_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + int16_t chan1_scaled; /*< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + int16_t chan2_scaled; /*< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + int16_t chan3_scaled; /*< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + int16_t chan4_scaled; /*< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + int16_t chan5_scaled; /*< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + int16_t chan6_scaled; /*< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + int16_t chan7_scaled; /*< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + int16_t chan8_scaled; /*< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.*/ + uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/ +} mavlink_rc_channels_scaled_t; + +#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22 +#define MAVLINK_MSG_ID_34_LEN 22 + +#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC 237 +#define MAVLINK_MSG_ID_34_CRC 237 + + + +#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \ + "RC_CHANNELS_SCALED", \ + 11, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \ + { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \ + { "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \ + { "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \ + { "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \ + { "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \ + { "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \ + { "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \ + { "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \ + } \ +} + + +/** + * @brief Pack a rc_channels_scaled message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, chan1_scaled); + _mav_put_int16_t(buf, 6, chan2_scaled); + _mav_put_int16_t(buf, 8, chan3_scaled); + _mav_put_int16_t(buf, 10, chan4_scaled); + _mav_put_int16_t(buf, 12, chan5_scaled); + _mav_put_int16_t(buf, 14, chan6_scaled); + _mav_put_int16_t(buf, 16, chan7_scaled); + _mav_put_int16_t(buf, 18, chan8_scaled); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#else + mavlink_rc_channels_scaled_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_scaled = chan1_scaled; + packet.chan2_scaled = chan2_scaled; + packet.chan3_scaled = chan3_scaled; + packet.chan4_scaled = chan4_scaled; + packet.chan5_scaled = chan5_scaled; + packet.chan6_scaled = chan6_scaled; + packet.chan7_scaled = chan7_scaled; + packet.chan8_scaled = chan8_scaled; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif +} + +/** + * @brief Pack a rc_channels_scaled message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t port,int16_t chan1_scaled,int16_t chan2_scaled,int16_t chan3_scaled,int16_t chan4_scaled,int16_t chan5_scaled,int16_t chan6_scaled,int16_t chan7_scaled,int16_t chan8_scaled,uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, chan1_scaled); + _mav_put_int16_t(buf, 6, chan2_scaled); + _mav_put_int16_t(buf, 8, chan3_scaled); + _mav_put_int16_t(buf, 10, chan4_scaled); + _mav_put_int16_t(buf, 12, chan5_scaled); + _mav_put_int16_t(buf, 14, chan6_scaled); + _mav_put_int16_t(buf, 16, chan7_scaled); + _mav_put_int16_t(buf, 18, chan8_scaled); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#else + mavlink_rc_channels_scaled_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_scaled = chan1_scaled; + packet.chan2_scaled = chan2_scaled; + packet.chan3_scaled = chan3_scaled; + packet.chan4_scaled = chan4_scaled; + packet.chan5_scaled = chan5_scaled; + packet.chan6_scaled = chan6_scaled; + packet.chan7_scaled = chan7_scaled; + packet.chan8_scaled = chan8_scaled; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif +} + +/** + * @brief Encode a rc_channels_scaled struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rc_channels_scaled C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) +{ + return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); +} + +/** + * @brief Encode a rc_channels_scaled struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rc_channels_scaled C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) +{ + return mavlink_msg_rc_channels_scaled_pack_chan(system_id, component_id, chan, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); +} + +/** + * @brief Send a rc_channels_scaled message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, chan1_scaled); + _mav_put_int16_t(buf, 6, chan2_scaled); + _mav_put_int16_t(buf, 8, chan3_scaled); + _mav_put_int16_t(buf, 10, chan4_scaled); + _mav_put_int16_t(buf, 12, chan5_scaled); + _mav_put_int16_t(buf, 14, chan6_scaled); + _mav_put_int16_t(buf, 16, chan7_scaled); + _mav_put_int16_t(buf, 18, chan8_scaled); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif +#else + mavlink_rc_channels_scaled_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_scaled = chan1_scaled; + packet.chan2_scaled = chan2_scaled; + packet.chan3_scaled = chan3_scaled; + packet.chan4_scaled = chan4_scaled; + packet.chan5_scaled = chan5_scaled; + packet.chan6_scaled = chan6_scaled; + packet.chan7_scaled = chan7_scaled; + packet.chan8_scaled = chan8_scaled; + packet.port = port; + packet.rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rc_channels_scaled_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, chan1_scaled); + _mav_put_int16_t(buf, 6, chan2_scaled); + _mav_put_int16_t(buf, 8, chan3_scaled); + _mav_put_int16_t(buf, 10, chan4_scaled); + _mav_put_int16_t(buf, 12, chan5_scaled); + _mav_put_int16_t(buf, 14, chan6_scaled); + _mav_put_int16_t(buf, 16, chan7_scaled); + _mav_put_int16_t(buf, 18, chan8_scaled); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif +#else + mavlink_rc_channels_scaled_t *packet = (mavlink_rc_channels_scaled_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->chan1_scaled = chan1_scaled; + packet->chan2_scaled = chan2_scaled; + packet->chan3_scaled = chan3_scaled; + packet->chan4_scaled = chan4_scaled; + packet->chan5_scaled = chan5_scaled; + packet->chan6_scaled = chan6_scaled; + packet->chan7_scaled = chan7_scaled; + packet->chan8_scaled = chan8_scaled; + packet->port = port; + packet->rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RC_CHANNELS_SCALED UNPACKING + + +/** + * @brief Get field time_boot_ms from rc_channels_scaled message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_rc_channels_scaled_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field port from rc_channels_scaled message + * + * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + */ +static inline uint8_t mavlink_msg_rc_channels_scaled_get_port(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field chan1_scaled from rc_channels_scaled message + * + * @return RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Get field chan2_scaled from rc_channels_scaled message + * + * @return RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 6); +} + +/** + * @brief Get field chan3_scaled from rc_channels_scaled message + * + * @return RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field chan4_scaled from rc_channels_scaled message + * + * @return RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field chan5_scaled from rc_channels_scaled message + * + * @return RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field chan6_scaled from rc_channels_scaled message + * + * @return RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field chan7_scaled from rc_channels_scaled message + * + * @return RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field chan8_scaled from rc_channels_scaled message + * + * @return RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field rssi from rc_channels_scaled message + * + * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + */ +static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 21); +} + +/** + * @brief Decode a rc_channels_scaled message into a struct + * + * @param msg The message to decode + * @param rc_channels_scaled C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t* msg, mavlink_rc_channels_scaled_t* rc_channels_scaled) +{ +#if MAVLINK_NEED_BYTE_SWAP + rc_channels_scaled->time_boot_ms = mavlink_msg_rc_channels_scaled_get_time_boot_ms(msg); + rc_channels_scaled->chan1_scaled = mavlink_msg_rc_channels_scaled_get_chan1_scaled(msg); + rc_channels_scaled->chan2_scaled = mavlink_msg_rc_channels_scaled_get_chan2_scaled(msg); + rc_channels_scaled->chan3_scaled = mavlink_msg_rc_channels_scaled_get_chan3_scaled(msg); + rc_channels_scaled->chan4_scaled = mavlink_msg_rc_channels_scaled_get_chan4_scaled(msg); + rc_channels_scaled->chan5_scaled = mavlink_msg_rc_channels_scaled_get_chan5_scaled(msg); + rc_channels_scaled->chan6_scaled = mavlink_msg_rc_channels_scaled_get_chan6_scaled(msg); + rc_channels_scaled->chan7_scaled = mavlink_msg_rc_channels_scaled_get_chan7_scaled(msg); + rc_channels_scaled->chan8_scaled = mavlink_msg_rc_channels_scaled_get_chan8_scaled(msg); + rc_channels_scaled->port = mavlink_msg_rc_channels_scaled_get_port(msg); + rc_channels_scaled->rssi = mavlink_msg_rc_channels_scaled_get_rssi(msg); +#else + memcpy(rc_channels_scaled, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_request_data_stream.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_request_data_stream.h new file mode 100644 index 0000000..c03c76a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_request_data_stream.h @@ -0,0 +1,305 @@ +// MESSAGE REQUEST_DATA_STREAM PACKING + +#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66 + +typedef struct __mavlink_request_data_stream_t +{ + uint16_t req_message_rate; /*< The requested message rate*/ + uint8_t target_system; /*< The target requested to send the message stream.*/ + uint8_t target_component; /*< The target requested to send the message stream.*/ + uint8_t req_stream_id; /*< The ID of the requested data stream*/ + uint8_t start_stop; /*< 1 to start sending, 0 to stop sending.*/ +} mavlink_request_data_stream_t; + +#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6 +#define MAVLINK_MSG_ID_66_LEN 6 + +#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC 148 +#define MAVLINK_MSG_ID_66_CRC 148 + + + +#define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \ + "REQUEST_DATA_STREAM", \ + 5, \ + { { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \ + { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \ + { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \ + } \ +} + + +/** + * @brief Pack a request_data_stream message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested data stream + * @param req_message_rate The requested message rate + * @param start_stop 1 to start sending, 0 to stop sending. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN]; + _mav_put_uint16_t(buf, 0, req_message_rate); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, req_stream_id); + _mav_put_uint8_t(buf, 5, start_stop); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#else + mavlink_request_data_stream_t packet; + packet.req_message_rate = req_message_rate; + packet.target_system = target_system; + packet.target_component = target_component; + packet.req_stream_id = req_stream_id; + packet.start_stop = start_stop; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif +} + +/** + * @brief Pack a request_data_stream message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested data stream + * @param req_message_rate The requested message rate + * @param start_stop 1 to start sending, 0 to stop sending. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t req_stream_id,uint16_t req_message_rate,uint8_t start_stop) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN]; + _mav_put_uint16_t(buf, 0, req_message_rate); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, req_stream_id); + _mav_put_uint8_t(buf, 5, start_stop); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#else + mavlink_request_data_stream_t packet; + packet.req_message_rate = req_message_rate; + packet.target_system = target_system; + packet.target_component = target_component; + packet.req_stream_id = req_stream_id; + packet.start_stop = start_stop; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif +} + +/** + * @brief Encode a request_data_stream struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param request_data_stream C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) +{ + return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); +} + +/** + * @brief Encode a request_data_stream struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param request_data_stream C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_request_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) +{ + return mavlink_msg_request_data_stream_pack_chan(system_id, component_id, chan, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); +} + +/** + * @brief Send a request_data_stream message + * @param chan MAVLink channel to send the message + * + * @param target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested data stream + * @param req_message_rate The requested message rate + * @param start_stop 1 to start sending, 0 to stop sending. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN]; + _mav_put_uint16_t(buf, 0, req_message_rate); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, req_stream_id); + _mav_put_uint8_t(buf, 5, start_stop); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif +#else + mavlink_request_data_stream_t packet; + packet.req_message_rate = req_message_rate; + packet.target_system = target_system; + packet.target_component = target_component; + packet.req_stream_id = req_stream_id; + packet.start_stop = start_stop; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_request_data_stream_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, req_message_rate); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, req_stream_id); + _mav_put_uint8_t(buf, 5, start_stop); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif +#else + mavlink_request_data_stream_t *packet = (mavlink_request_data_stream_t *)msgbuf; + packet->req_message_rate = req_message_rate; + packet->target_system = target_system; + packet->target_component = target_component; + packet->req_stream_id = req_stream_id; + packet->start_stop = start_stop; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE REQUEST_DATA_STREAM UNPACKING + + +/** + * @brief Get field target_system from request_data_stream message + * + * @return The target requested to send the message stream. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from request_data_stream message + * + * @return The target requested to send the message stream. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field req_stream_id from request_data_stream message + * + * @return The ID of the requested data stream + */ +static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field req_message_rate from request_data_stream message + * + * @return The requested message rate + */ +static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field start_stop from request_data_stream message + * + * @return 1 to start sending, 0 to stop sending. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Decode a request_data_stream message into a struct + * + * @param msg The message to decode + * @param request_data_stream C-struct to decode the message contents into + */ +static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream) +{ +#if MAVLINK_NEED_BYTE_SWAP + request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg); + request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg); + request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg); + request_data_stream->req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg); + request_data_stream->start_stop = mavlink_msg_request_data_stream_get_start_stop(msg); +#else + memcpy(request_data_stream, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_resource_request.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_resource_request.h new file mode 100644 index 0000000..3cbb560 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_resource_request.h @@ -0,0 +1,298 @@ +// MESSAGE RESOURCE_REQUEST PACKING + +#define MAVLINK_MSG_ID_RESOURCE_REQUEST 142 + +typedef struct __mavlink_resource_request_t +{ + uint8_t request_id; /*< Request ID. This ID should be re-used when sending back URI contents*/ + uint8_t uri_type; /*< The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary*/ + uint8_t uri[120]; /*< The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)*/ + uint8_t transfer_type; /*< The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream.*/ + uint8_t storage[120]; /*< The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP).*/ +} mavlink_resource_request_t; + +#define MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN 243 +#define MAVLINK_MSG_ID_142_LEN 243 + +#define MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC 72 +#define MAVLINK_MSG_ID_142_CRC 72 + +#define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_URI_LEN 120 +#define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_STORAGE_LEN 120 + +#define MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST { \ + "RESOURCE_REQUEST", \ + 5, \ + { { "request_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_resource_request_t, request_id) }, \ + { "uri_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_resource_request_t, uri_type) }, \ + { "uri", NULL, MAVLINK_TYPE_UINT8_T, 120, 2, offsetof(mavlink_resource_request_t, uri) }, \ + { "transfer_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 122, offsetof(mavlink_resource_request_t, transfer_type) }, \ + { "storage", NULL, MAVLINK_TYPE_UINT8_T, 120, 123, offsetof(mavlink_resource_request_t, storage) }, \ + } \ +} + + +/** + * @brief Pack a resource_request message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param request_id Request ID. This ID should be re-used when sending back URI contents + * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_resource_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN]; + _mav_put_uint8_t(buf, 0, request_id); + _mav_put_uint8_t(buf, 1, uri_type); + _mav_put_uint8_t(buf, 122, transfer_type); + _mav_put_uint8_t_array(buf, 2, uri, 120); + _mav_put_uint8_t_array(buf, 123, storage, 120); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#else + mavlink_resource_request_t packet; + packet.request_id = request_id; + packet.uri_type = uri_type; + packet.transfer_type = transfer_type; + mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120); + mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RESOURCE_REQUEST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif +} + +/** + * @brief Pack a resource_request message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param request_id Request ID. This ID should be re-used when sending back URI contents + * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_resource_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t request_id,uint8_t uri_type,const uint8_t *uri,uint8_t transfer_type,const uint8_t *storage) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN]; + _mav_put_uint8_t(buf, 0, request_id); + _mav_put_uint8_t(buf, 1, uri_type); + _mav_put_uint8_t(buf, 122, transfer_type); + _mav_put_uint8_t_array(buf, 2, uri, 120); + _mav_put_uint8_t_array(buf, 123, storage, 120); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#else + mavlink_resource_request_t packet; + packet.request_id = request_id; + packet.uri_type = uri_type; + packet.transfer_type = transfer_type; + mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120); + mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RESOURCE_REQUEST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif +} + +/** + * @brief Encode a resource_request struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param resource_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_resource_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_resource_request_t* resource_request) +{ + return mavlink_msg_resource_request_pack(system_id, component_id, msg, resource_request->request_id, resource_request->uri_type, resource_request->uri, resource_request->transfer_type, resource_request->storage); +} + +/** + * @brief Encode a resource_request struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param resource_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_resource_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_resource_request_t* resource_request) +{ + return mavlink_msg_resource_request_pack_chan(system_id, component_id, chan, msg, resource_request->request_id, resource_request->uri_type, resource_request->uri, resource_request->transfer_type, resource_request->storage); +} + +/** + * @brief Send a resource_request message + * @param chan MAVLink channel to send the message + * + * @param request_id Request ID. This ID should be re-used when sending back URI contents + * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_resource_request_send(mavlink_channel_t chan, uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN]; + _mav_put_uint8_t(buf, 0, request_id); + _mav_put_uint8_t(buf, 1, uri_type); + _mav_put_uint8_t(buf, 122, transfer_type); + _mav_put_uint8_t_array(buf, 2, uri, 120); + _mav_put_uint8_t_array(buf, 123, storage, 120); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif +#else + mavlink_resource_request_t packet; + packet.request_id = request_id; + packet.uri_type = uri_type; + packet.transfer_type = transfer_type; + mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120); + mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_resource_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, request_id); + _mav_put_uint8_t(buf, 1, uri_type); + _mav_put_uint8_t(buf, 122, transfer_type); + _mav_put_uint8_t_array(buf, 2, uri, 120); + _mav_put_uint8_t_array(buf, 123, storage, 120); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif +#else + mavlink_resource_request_t *packet = (mavlink_resource_request_t *)msgbuf; + packet->request_id = request_id; + packet->uri_type = uri_type; + packet->transfer_type = transfer_type; + mav_array_memcpy(packet->uri, uri, sizeof(uint8_t)*120); + mav_array_memcpy(packet->storage, storage, sizeof(uint8_t)*120); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RESOURCE_REQUEST UNPACKING + + +/** + * @brief Get field request_id from resource_request message + * + * @return Request ID. This ID should be re-used when sending back URI contents + */ +static inline uint8_t mavlink_msg_resource_request_get_request_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field uri_type from resource_request message + * + * @return The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + */ +static inline uint8_t mavlink_msg_resource_request_get_uri_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field uri from resource_request message + * + * @return The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + */ +static inline uint16_t mavlink_msg_resource_request_get_uri(const mavlink_message_t* msg, uint8_t *uri) +{ + return _MAV_RETURN_uint8_t_array(msg, uri, 120, 2); +} + +/** + * @brief Get field transfer_type from resource_request message + * + * @return The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + */ +static inline uint8_t mavlink_msg_resource_request_get_transfer_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 122); +} + +/** + * @brief Get field storage from resource_request message + * + * @return The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + */ +static inline uint16_t mavlink_msg_resource_request_get_storage(const mavlink_message_t* msg, uint8_t *storage) +{ + return _MAV_RETURN_uint8_t_array(msg, storage, 120, 123); +} + +/** + * @brief Decode a resource_request message into a struct + * + * @param msg The message to decode + * @param resource_request C-struct to decode the message contents into + */ +static inline void mavlink_msg_resource_request_decode(const mavlink_message_t* msg, mavlink_resource_request_t* resource_request) +{ +#if MAVLINK_NEED_BYTE_SWAP + resource_request->request_id = mavlink_msg_resource_request_get_request_id(msg); + resource_request->uri_type = mavlink_msg_resource_request_get_uri_type(msg); + mavlink_msg_resource_request_get_uri(msg, resource_request->uri); + resource_request->transfer_type = mavlink_msg_resource_request_get_transfer_type(msg); + mavlink_msg_resource_request_get_storage(msg, resource_request->storage); +#else + memcpy(resource_request, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h new file mode 100644 index 0000000..e0722c1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h @@ -0,0 +1,353 @@ +// MESSAGE SAFETY_ALLOWED_AREA PACKING + +#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55 + +typedef struct __mavlink_safety_allowed_area_t +{ + float p1x; /*< x position 1 / Latitude 1*/ + float p1y; /*< y position 1 / Longitude 1*/ + float p1z; /*< z position 1 / Altitude 1*/ + float p2x; /*< x position 2 / Latitude 2*/ + float p2y; /*< y position 2 / Longitude 2*/ + float p2z; /*< z position 2 / Altitude 2*/ + uint8_t frame; /*< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.*/ +} mavlink_safety_allowed_area_t; + +#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25 +#define MAVLINK_MSG_ID_55_LEN 25 + +#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC 3 +#define MAVLINK_MSG_ID_55_CRC 3 + + + +#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \ + "SAFETY_ALLOWED_AREA", \ + 7, \ + { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ + { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ + { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ + { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ + { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ + { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ + } \ +} + + +/** + * @brief Pack a safety_allowed_area message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#else + mavlink_safety_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif +} + +/** + * @brief Pack a safety_allowed_area message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#else + mavlink_safety_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif +} + +/** + * @brief Encode a safety_allowed_area struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param safety_allowed_area C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) +{ + return mavlink_msg_safety_allowed_area_pack(system_id, component_id, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); +} + +/** + * @brief Encode a safety_allowed_area struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param safety_allowed_area C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_safety_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) +{ + return mavlink_msg_safety_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); +} + +/** + * @brief Send a safety_allowed_area message + * @param chan MAVLink channel to send the message + * + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif +#else + mavlink_safety_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.frame = frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_safety_allowed_area_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif +#else + mavlink_safety_allowed_area_t *packet = (mavlink_safety_allowed_area_t *)msgbuf; + packet->p1x = p1x; + packet->p1y = p1y; + packet->p1z = p1z; + packet->p2x = p2x; + packet->p2y = p2y; + packet->p2z = p2z; + packet->frame = frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SAFETY_ALLOWED_AREA UNPACKING + + +/** + * @brief Get field frame from safety_allowed_area message + * + * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + */ +static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field p1x from safety_allowed_area message + * + * @return x position 1 / Latitude 1 + */ +static inline float mavlink_msg_safety_allowed_area_get_p1x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field p1y from safety_allowed_area message + * + * @return y position 1 / Longitude 1 + */ +static inline float mavlink_msg_safety_allowed_area_get_p1y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field p1z from safety_allowed_area message + * + * @return z position 1 / Altitude 1 + */ +static inline float mavlink_msg_safety_allowed_area_get_p1z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field p2x from safety_allowed_area message + * + * @return x position 2 / Latitude 2 + */ +static inline float mavlink_msg_safety_allowed_area_get_p2x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field p2y from safety_allowed_area message + * + * @return y position 2 / Longitude 2 + */ +static inline float mavlink_msg_safety_allowed_area_get_p2y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field p2z from safety_allowed_area message + * + * @return z position 2 / Altitude 2 + */ +static inline float mavlink_msg_safety_allowed_area_get_p2z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Decode a safety_allowed_area message into a struct + * + * @param msg The message to decode + * @param safety_allowed_area C-struct to decode the message contents into + */ +static inline void mavlink_msg_safety_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_allowed_area_t* safety_allowed_area) +{ +#if MAVLINK_NEED_BYTE_SWAP + safety_allowed_area->p1x = mavlink_msg_safety_allowed_area_get_p1x(msg); + safety_allowed_area->p1y = mavlink_msg_safety_allowed_area_get_p1y(msg); + safety_allowed_area->p1z = mavlink_msg_safety_allowed_area_get_p1z(msg); + safety_allowed_area->p2x = mavlink_msg_safety_allowed_area_get_p2x(msg); + safety_allowed_area->p2y = mavlink_msg_safety_allowed_area_get_p2y(msg); + safety_allowed_area->p2z = mavlink_msg_safety_allowed_area_get_p2z(msg); + safety_allowed_area->frame = mavlink_msg_safety_allowed_area_get_frame(msg); +#else + memcpy(safety_allowed_area, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h new file mode 100644 index 0000000..1fdfc77 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h @@ -0,0 +1,401 @@ +// MESSAGE SAFETY_SET_ALLOWED_AREA PACKING + +#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54 + +typedef struct __mavlink_safety_set_allowed_area_t +{ + float p1x; /*< x position 1 / Latitude 1*/ + float p1y; /*< y position 1 / Longitude 1*/ + float p1z; /*< z position 1 / Altitude 1*/ + float p2x; /*< x position 2 / Latitude 2*/ + float p2y; /*< y position 2 / Longitude 2*/ + float p2z; /*< z position 2 / Altitude 2*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t frame; /*< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.*/ +} mavlink_safety_set_allowed_area_t; + +#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27 +#define MAVLINK_MSG_ID_54_LEN 27 + +#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC 15 +#define MAVLINK_MSG_ID_54_CRC 15 + + + +#define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \ + "SAFETY_SET_ALLOWED_AREA", \ + 9, \ + { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ + { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \ + { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \ + { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \ + { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \ + { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ + } \ +} + + +/** + * @brief Pack a safety_set_allowed_area message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, target_system); + _mav_put_uint8_t(buf, 25, target_component); + _mav_put_uint8_t(buf, 26, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#else + mavlink_safety_set_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif +} + +/** + * @brief Pack a safety_set_allowed_area message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, target_system); + _mav_put_uint8_t(buf, 25, target_component); + _mav_put_uint8_t(buf, 26, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#else + mavlink_safety_set_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif +} + +/** + * @brief Encode a safety_set_allowed_area struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param safety_set_allowed_area C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) +{ + return mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); +} + +/** + * @brief Encode a safety_set_allowed_area struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param safety_set_allowed_area C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) +{ + return mavlink_msg_safety_set_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); +} + +/** + * @brief Send a safety_set_allowed_area message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_safety_set_allowed_area_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, target_system); + _mav_put_uint8_t(buf, 25, target_component); + _mav_put_uint8_t(buf, 26, frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif +#else + mavlink_safety_set_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_safety_set_allowed_area_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, target_system); + _mav_put_uint8_t(buf, 25, target_component); + _mav_put_uint8_t(buf, 26, frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif +#else + mavlink_safety_set_allowed_area_t *packet = (mavlink_safety_set_allowed_area_t *)msgbuf; + packet->p1x = p1x; + packet->p1y = p1y; + packet->p1z = p1z; + packet->p2x = p2x; + packet->p2y = p2y; + packet->p2z = p2z; + packet->target_system = target_system; + packet->target_component = target_component; + packet->frame = frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SAFETY_SET_ALLOWED_AREA UNPACKING + + +/** + * @brief Get field target_system from safety_set_allowed_area message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field target_component from safety_set_allowed_area message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 25); +} + +/** + * @brief Get field frame from safety_set_allowed_area message + * + * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + */ +static inline uint8_t mavlink_msg_safety_set_allowed_area_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 26); +} + +/** + * @brief Get field p1x from safety_set_allowed_area message + * + * @return x position 1 / Latitude 1 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p1x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field p1y from safety_set_allowed_area message + * + * @return y position 1 / Longitude 1 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p1y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field p1z from safety_set_allowed_area message + * + * @return z position 1 / Altitude 1 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p1z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field p2x from safety_set_allowed_area message + * + * @return x position 2 / Latitude 2 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p2x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field p2y from safety_set_allowed_area message + * + * @return y position 2 / Longitude 2 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p2y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field p2z from safety_set_allowed_area message + * + * @return z position 2 / Altitude 2 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p2z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Decode a safety_set_allowed_area message into a struct + * + * @param msg The message to decode + * @param safety_set_allowed_area C-struct to decode the message contents into + */ +static inline void mavlink_msg_safety_set_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_set_allowed_area_t* safety_set_allowed_area) +{ +#if MAVLINK_NEED_BYTE_SWAP + safety_set_allowed_area->p1x = mavlink_msg_safety_set_allowed_area_get_p1x(msg); + safety_set_allowed_area->p1y = mavlink_msg_safety_set_allowed_area_get_p1y(msg); + safety_set_allowed_area->p1z = mavlink_msg_safety_set_allowed_area_get_p1z(msg); + safety_set_allowed_area->p2x = mavlink_msg_safety_set_allowed_area_get_p2x(msg); + safety_set_allowed_area->p2y = mavlink_msg_safety_set_allowed_area_get_p2y(msg); + safety_set_allowed_area->p2z = mavlink_msg_safety_set_allowed_area_get_p2z(msg); + safety_set_allowed_area->target_system = mavlink_msg_safety_set_allowed_area_get_target_system(msg); + safety_set_allowed_area->target_component = mavlink_msg_safety_set_allowed_area_get_target_component(msg); + safety_set_allowed_area->frame = mavlink_msg_safety_set_allowed_area_get_frame(msg); +#else + memcpy(safety_set_allowed_area, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_imu.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_imu.h new file mode 100644 index 0000000..b828030 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_imu.h @@ -0,0 +1,425 @@ +// MESSAGE SCALED_IMU PACKING + +#define MAVLINK_MSG_ID_SCALED_IMU 26 + +typedef struct __mavlink_scaled_imu_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + int16_t xacc; /*< X acceleration (mg)*/ + int16_t yacc; /*< Y acceleration (mg)*/ + int16_t zacc; /*< Z acceleration (mg)*/ + int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/ + int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/ + int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/ + int16_t xmag; /*< X Magnetic field (milli tesla)*/ + int16_t ymag; /*< Y Magnetic field (milli tesla)*/ + int16_t zmag; /*< Z Magnetic field (milli tesla)*/ +} mavlink_scaled_imu_t; + +#define MAVLINK_MSG_ID_SCALED_IMU_LEN 22 +#define MAVLINK_MSG_ID_26_LEN 22 + +#define MAVLINK_MSG_ID_SCALED_IMU_CRC 170 +#define MAVLINK_MSG_ID_26_CRC 170 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \ + "SCALED_IMU", \ + 10, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \ + } \ +} + + +/** + * @brief Pack a scaled_imu message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#else + mavlink_scaled_imu_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif +} + +/** + * @brief Pack a scaled_imu message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#else + mavlink_scaled_imu_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif +} + +/** + * @brief Encode a scaled_imu struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param scaled_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu) +{ + return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag); +} + +/** + * @brief Encode a scaled_imu struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param scaled_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu) +{ + return mavlink_msg_scaled_imu_pack_chan(system_id, component_id, chan, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag); +} + +/** + * @brief Send a scaled_imu message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif +#else + mavlink_scaled_imu_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SCALED_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_scaled_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif +#else + mavlink_scaled_imu_t *packet = (mavlink_scaled_imu_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->xmag = xmag; + packet->ymag = ymag; + packet->zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SCALED_IMU UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_imu message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_imu_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field xacc from scaled_imu message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Get field yacc from scaled_imu message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 6); +} + +/** + * @brief Get field zacc from scaled_imu message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field xgyro from scaled_imu message + * + * @return Angular speed around X axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field ygyro from scaled_imu message + * + * @return Angular speed around Y axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field zgyro from scaled_imu message + * + * @return Angular speed around Z axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field xmag from scaled_imu message + * + * @return X Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field ymag from scaled_imu message + * + * @return Y Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field zmag from scaled_imu message + * + * @return Z Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Decode a scaled_imu message into a struct + * + * @param msg The message to decode + * @param scaled_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_imu_decode(const mavlink_message_t* msg, mavlink_scaled_imu_t* scaled_imu) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_imu->time_boot_ms = mavlink_msg_scaled_imu_get_time_boot_ms(msg); + scaled_imu->xacc = mavlink_msg_scaled_imu_get_xacc(msg); + scaled_imu->yacc = mavlink_msg_scaled_imu_get_yacc(msg); + scaled_imu->zacc = mavlink_msg_scaled_imu_get_zacc(msg); + scaled_imu->xgyro = mavlink_msg_scaled_imu_get_xgyro(msg); + scaled_imu->ygyro = mavlink_msg_scaled_imu_get_ygyro(msg); + scaled_imu->zgyro = mavlink_msg_scaled_imu_get_zgyro(msg); + scaled_imu->xmag = mavlink_msg_scaled_imu_get_xmag(msg); + scaled_imu->ymag = mavlink_msg_scaled_imu_get_ymag(msg); + scaled_imu->zmag = mavlink_msg_scaled_imu_get_zmag(msg); +#else + memcpy(scaled_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h new file mode 100644 index 0000000..1d8fa32 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h @@ -0,0 +1,425 @@ +// MESSAGE SCALED_IMU2 PACKING + +#define MAVLINK_MSG_ID_SCALED_IMU2 116 + +typedef struct __mavlink_scaled_imu2_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + int16_t xacc; /*< X acceleration (mg)*/ + int16_t yacc; /*< Y acceleration (mg)*/ + int16_t zacc; /*< Z acceleration (mg)*/ + int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/ + int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/ + int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/ + int16_t xmag; /*< X Magnetic field (milli tesla)*/ + int16_t ymag; /*< Y Magnetic field (milli tesla)*/ + int16_t zmag; /*< Z Magnetic field (milli tesla)*/ +} mavlink_scaled_imu2_t; + +#define MAVLINK_MSG_ID_SCALED_IMU2_LEN 22 +#define MAVLINK_MSG_ID_116_LEN 22 + +#define MAVLINK_MSG_ID_SCALED_IMU2_CRC 76 +#define MAVLINK_MSG_ID_116_CRC 76 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_IMU2 { \ + "SCALED_IMU2", \ + 10, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu2_t, time_boot_ms) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu2_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu2_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu2_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu2_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu2_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu2_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu2_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu2_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu2_t, zmag) }, \ + } \ +} + + +/** + * @brief Pack a scaled_imu2 message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#else + mavlink_scaled_imu2_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +} + +/** + * @brief Pack a scaled_imu2 message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#else + mavlink_scaled_imu2_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +} + +/** + * @brief Encode a scaled_imu2 struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param scaled_imu2 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2) +{ + return mavlink_msg_scaled_imu2_pack(system_id, component_id, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag); +} + +/** + * @brief Encode a scaled_imu2 struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param scaled_imu2 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2) +{ + return mavlink_msg_scaled_imu2_pack_chan(system_id, component_id, chan, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag); +} + +/** + * @brief Send a scaled_imu2 message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_imu2_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +#else + mavlink_scaled_imu2_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SCALED_IMU2_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_scaled_imu2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +#else + mavlink_scaled_imu2_t *packet = (mavlink_scaled_imu2_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->xmag = xmag; + packet->ymag = ymag; + packet->zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SCALED_IMU2 UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_imu2 message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_imu2_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field xacc from scaled_imu2 message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Get field yacc from scaled_imu2 message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 6); +} + +/** + * @brief Get field zacc from scaled_imu2 message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field xgyro from scaled_imu2 message + * + * @return Angular speed around X axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field ygyro from scaled_imu2 message + * + * @return Angular speed around Y axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field zgyro from scaled_imu2 message + * + * @return Angular speed around Z axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field xmag from scaled_imu2 message + * + * @return X Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field ymag from scaled_imu2 message + * + * @return Y Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field zmag from scaled_imu2 message + * + * @return Z Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Decode a scaled_imu2 message into a struct + * + * @param msg The message to decode + * @param scaled_imu2 C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_imu2_decode(const mavlink_message_t* msg, mavlink_scaled_imu2_t* scaled_imu2) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_imu2->time_boot_ms = mavlink_msg_scaled_imu2_get_time_boot_ms(msg); + scaled_imu2->xacc = mavlink_msg_scaled_imu2_get_xacc(msg); + scaled_imu2->yacc = mavlink_msg_scaled_imu2_get_yacc(msg); + scaled_imu2->zacc = mavlink_msg_scaled_imu2_get_zacc(msg); + scaled_imu2->xgyro = mavlink_msg_scaled_imu2_get_xgyro(msg); + scaled_imu2->ygyro = mavlink_msg_scaled_imu2_get_ygyro(msg); + scaled_imu2->zgyro = mavlink_msg_scaled_imu2_get_zgyro(msg); + scaled_imu2->xmag = mavlink_msg_scaled_imu2_get_xmag(msg); + scaled_imu2->ymag = mavlink_msg_scaled_imu2_get_ymag(msg); + scaled_imu2->zmag = mavlink_msg_scaled_imu2_get_zmag(msg); +#else + memcpy(scaled_imu2, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_imu3.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_imu3.h new file mode 100644 index 0000000..2ae3093 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_imu3.h @@ -0,0 +1,425 @@ +// MESSAGE SCALED_IMU3 PACKING + +#define MAVLINK_MSG_ID_SCALED_IMU3 129 + +typedef struct __mavlink_scaled_imu3_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + int16_t xacc; /*< X acceleration (mg)*/ + int16_t yacc; /*< Y acceleration (mg)*/ + int16_t zacc; /*< Z acceleration (mg)*/ + int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/ + int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/ + int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/ + int16_t xmag; /*< X Magnetic field (milli tesla)*/ + int16_t ymag; /*< Y Magnetic field (milli tesla)*/ + int16_t zmag; /*< Z Magnetic field (milli tesla)*/ +} mavlink_scaled_imu3_t; + +#define MAVLINK_MSG_ID_SCALED_IMU3_LEN 22 +#define MAVLINK_MSG_ID_129_LEN 22 + +#define MAVLINK_MSG_ID_SCALED_IMU3_CRC 46 +#define MAVLINK_MSG_ID_129_CRC 46 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_IMU3 { \ + "SCALED_IMU3", \ + 10, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu3_t, time_boot_ms) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu3_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu3_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu3_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu3_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu3_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu3_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu3_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu3_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu3_t, zmag) }, \ + } \ +} + + +/** + * @brief Pack a scaled_imu3 message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu3_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU3_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#else + mavlink_scaled_imu3_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU3; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif +} + +/** + * @brief Pack a scaled_imu3 message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu3_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU3_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#else + mavlink_scaled_imu3_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU3; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif +} + +/** + * @brief Encode a scaled_imu3 struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param scaled_imu3 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu3_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu3_t* scaled_imu3) +{ + return mavlink_msg_scaled_imu3_pack(system_id, component_id, msg, scaled_imu3->time_boot_ms, scaled_imu3->xacc, scaled_imu3->yacc, scaled_imu3->zacc, scaled_imu3->xgyro, scaled_imu3->ygyro, scaled_imu3->zgyro, scaled_imu3->xmag, scaled_imu3->ymag, scaled_imu3->zmag); +} + +/** + * @brief Encode a scaled_imu3 struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param scaled_imu3 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu3_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu3_t* scaled_imu3) +{ + return mavlink_msg_scaled_imu3_pack_chan(system_id, component_id, chan, msg, scaled_imu3->time_boot_ms, scaled_imu3->xacc, scaled_imu3->yacc, scaled_imu3->zacc, scaled_imu3->xgyro, scaled_imu3->ygyro, scaled_imu3->zgyro, scaled_imu3->xmag, scaled_imu3->ymag, scaled_imu3->zmag); +} + +/** + * @brief Send a scaled_imu3 message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_imu3_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU3_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif +#else + mavlink_scaled_imu3_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SCALED_IMU3_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_scaled_imu3_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif +#else + mavlink_scaled_imu3_t *packet = (mavlink_scaled_imu3_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->xmag = xmag; + packet->ymag = ymag; + packet->zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SCALED_IMU3 UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_imu3 message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_imu3_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field xacc from scaled_imu3 message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Get field yacc from scaled_imu3 message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 6); +} + +/** + * @brief Get field zacc from scaled_imu3 message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field xgyro from scaled_imu3 message + * + * @return Angular speed around X axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field ygyro from scaled_imu3 message + * + * @return Angular speed around Y axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field zgyro from scaled_imu3 message + * + * @return Angular speed around Z axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field xmag from scaled_imu3 message + * + * @return X Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field ymag from scaled_imu3 message + * + * @return Y Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field zmag from scaled_imu3 message + * + * @return Z Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Decode a scaled_imu3 message into a struct + * + * @param msg The message to decode + * @param scaled_imu3 C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_imu3_decode(const mavlink_message_t* msg, mavlink_scaled_imu3_t* scaled_imu3) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_imu3->time_boot_ms = mavlink_msg_scaled_imu3_get_time_boot_ms(msg); + scaled_imu3->xacc = mavlink_msg_scaled_imu3_get_xacc(msg); + scaled_imu3->yacc = mavlink_msg_scaled_imu3_get_yacc(msg); + scaled_imu3->zacc = mavlink_msg_scaled_imu3_get_zacc(msg); + scaled_imu3->xgyro = mavlink_msg_scaled_imu3_get_xgyro(msg); + scaled_imu3->ygyro = mavlink_msg_scaled_imu3_get_ygyro(msg); + scaled_imu3->zgyro = mavlink_msg_scaled_imu3_get_zgyro(msg); + scaled_imu3->xmag = mavlink_msg_scaled_imu3_get_xmag(msg); + scaled_imu3->ymag = mavlink_msg_scaled_imu3_get_ymag(msg); + scaled_imu3->zmag = mavlink_msg_scaled_imu3_get_zmag(msg); +#else + memcpy(scaled_imu3, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h new file mode 100644 index 0000000..5ddad6d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h @@ -0,0 +1,281 @@ +// MESSAGE SCALED_PRESSURE PACKING + +#define MAVLINK_MSG_ID_SCALED_PRESSURE 29 + +typedef struct __mavlink_scaled_pressure_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float press_abs; /*< Absolute pressure (hectopascal)*/ + float press_diff; /*< Differential pressure 1 (hectopascal)*/ + int16_t temperature; /*< Temperature measurement (0.01 degrees celsius)*/ +} mavlink_scaled_pressure_t; + +#define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 14 +#define MAVLINK_MSG_ID_29_LEN 14 + +#define MAVLINK_MSG_ID_SCALED_PRESSURE_CRC 115 +#define MAVLINK_MSG_ID_29_CRC 115 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \ + "SCALED_PRESSURE", \ + 4, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \ + { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \ + { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a scaled_pressure message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#else + mavlink_scaled_pressure_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif +} + +/** + * @brief Pack a scaled_pressure message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#else + mavlink_scaled_pressure_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif +} + +/** + * @brief Encode a scaled_pressure struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param scaled_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) +{ + return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); +} + +/** + * @brief Encode a scaled_pressure struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param scaled_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) +{ + return mavlink_msg_scaled_pressure_pack_chan(system_id, component_id, chan, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); +} + +/** + * @brief Send a scaled_pressure message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif +#else + mavlink_scaled_pressure_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SCALED_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_scaled_pressure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif +#else + mavlink_scaled_pressure_t *packet = (mavlink_scaled_pressure_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->press_abs = press_abs; + packet->press_diff = press_diff; + packet->temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SCALED_PRESSURE UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_pressure message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_pressure_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field press_abs from scaled_pressure message + * + * @return Absolute pressure (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field press_diff from scaled_pressure message + * + * @return Differential pressure 1 (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field temperature from scaled_pressure message + * + * @return Temperature measurement (0.01 degrees celsius) + */ +static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Decode a scaled_pressure message into a struct + * + * @param msg The message to decode + * @param scaled_pressure C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_pressure->time_boot_ms = mavlink_msg_scaled_pressure_get_time_boot_ms(msg); + scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg); + scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg); + scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg); +#else + memcpy(scaled_pressure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_pressure2.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_pressure2.h new file mode 100644 index 0000000..c9ca5dc --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_pressure2.h @@ -0,0 +1,281 @@ +// MESSAGE SCALED_PRESSURE2 PACKING + +#define MAVLINK_MSG_ID_SCALED_PRESSURE2 137 + +typedef struct __mavlink_scaled_pressure2_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float press_abs; /*< Absolute pressure (hectopascal)*/ + float press_diff; /*< Differential pressure 1 (hectopascal)*/ + int16_t temperature; /*< Temperature measurement (0.01 degrees celsius)*/ +} mavlink_scaled_pressure2_t; + +#define MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN 14 +#define MAVLINK_MSG_ID_137_LEN 14 + +#define MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC 195 +#define MAVLINK_MSG_ID_137_CRC 195 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2 { \ + "SCALED_PRESSURE2", \ + 4, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure2_t, time_boot_ms) }, \ + { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure2_t, press_abs) }, \ + { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure2_t, press_diff) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure2_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a scaled_pressure2 message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#else + mavlink_scaled_pressure2_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE2; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif +} + +/** + * @brief Pack a scaled_pressure2 message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#else + mavlink_scaled_pressure2_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE2; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif +} + +/** + * @brief Encode a scaled_pressure2 struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param scaled_pressure2 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure2_t* scaled_pressure2) +{ + return mavlink_msg_scaled_pressure2_pack(system_id, component_id, msg, scaled_pressure2->time_boot_ms, scaled_pressure2->press_abs, scaled_pressure2->press_diff, scaled_pressure2->temperature); +} + +/** + * @brief Encode a scaled_pressure2 struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param scaled_pressure2 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure2_t* scaled_pressure2) +{ + return mavlink_msg_scaled_pressure2_pack_chan(system_id, component_id, chan, msg, scaled_pressure2->time_boot_ms, scaled_pressure2->press_abs, scaled_pressure2->press_diff, scaled_pressure2->temperature); +} + +/** + * @brief Send a scaled_pressure2 message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_pressure2_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif +#else + mavlink_scaled_pressure2_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_scaled_pressure2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif +#else + mavlink_scaled_pressure2_t *packet = (mavlink_scaled_pressure2_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->press_abs = press_abs; + packet->press_diff = press_diff; + packet->temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SCALED_PRESSURE2 UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_pressure2 message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_pressure2_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field press_abs from scaled_pressure2 message + * + * @return Absolute pressure (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure2_get_press_abs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field press_diff from scaled_pressure2 message + * + * @return Differential pressure 1 (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure2_get_press_diff(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field temperature from scaled_pressure2 message + * + * @return Temperature measurement (0.01 degrees celsius) + */ +static inline int16_t mavlink_msg_scaled_pressure2_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Decode a scaled_pressure2 message into a struct + * + * @param msg The message to decode + * @param scaled_pressure2 C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_pressure2_decode(const mavlink_message_t* msg, mavlink_scaled_pressure2_t* scaled_pressure2) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_pressure2->time_boot_ms = mavlink_msg_scaled_pressure2_get_time_boot_ms(msg); + scaled_pressure2->press_abs = mavlink_msg_scaled_pressure2_get_press_abs(msg); + scaled_pressure2->press_diff = mavlink_msg_scaled_pressure2_get_press_diff(msg); + scaled_pressure2->temperature = mavlink_msg_scaled_pressure2_get_temperature(msg); +#else + memcpy(scaled_pressure2, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_pressure3.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_pressure3.h new file mode 100644 index 0000000..62d46ae --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_scaled_pressure3.h @@ -0,0 +1,281 @@ +// MESSAGE SCALED_PRESSURE3 PACKING + +#define MAVLINK_MSG_ID_SCALED_PRESSURE3 143 + +typedef struct __mavlink_scaled_pressure3_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float press_abs; /*< Absolute pressure (hectopascal)*/ + float press_diff; /*< Differential pressure 1 (hectopascal)*/ + int16_t temperature; /*< Temperature measurement (0.01 degrees celsius)*/ +} mavlink_scaled_pressure3_t; + +#define MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN 14 +#define MAVLINK_MSG_ID_143_LEN 14 + +#define MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC 131 +#define MAVLINK_MSG_ID_143_CRC 131 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3 { \ + "SCALED_PRESSURE3", \ + 4, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure3_t, time_boot_ms) }, \ + { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure3_t, press_abs) }, \ + { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure3_t, press_diff) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure3_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a scaled_pressure3 message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure3_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#else + mavlink_scaled_pressure3_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE3; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif +} + +/** + * @brief Pack a scaled_pressure3 message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure3_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#else + mavlink_scaled_pressure3_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE3; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif +} + +/** + * @brief Encode a scaled_pressure3 struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param scaled_pressure3 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure3_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure3_t* scaled_pressure3) +{ + return mavlink_msg_scaled_pressure3_pack(system_id, component_id, msg, scaled_pressure3->time_boot_ms, scaled_pressure3->press_abs, scaled_pressure3->press_diff, scaled_pressure3->temperature); +} + +/** + * @brief Encode a scaled_pressure3 struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param scaled_pressure3 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure3_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure3_t* scaled_pressure3) +{ + return mavlink_msg_scaled_pressure3_pack_chan(system_id, component_id, chan, msg, scaled_pressure3->time_boot_ms, scaled_pressure3->press_abs, scaled_pressure3->press_diff, scaled_pressure3->temperature); +} + +/** + * @brief Send a scaled_pressure3 message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_pressure3_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif +#else + mavlink_scaled_pressure3_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_scaled_pressure3_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif +#else + mavlink_scaled_pressure3_t *packet = (mavlink_scaled_pressure3_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->press_abs = press_abs; + packet->press_diff = press_diff; + packet->temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SCALED_PRESSURE3 UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_pressure3 message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_pressure3_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field press_abs from scaled_pressure3 message + * + * @return Absolute pressure (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure3_get_press_abs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field press_diff from scaled_pressure3 message + * + * @return Differential pressure 1 (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure3_get_press_diff(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field temperature from scaled_pressure3 message + * + * @return Temperature measurement (0.01 degrees celsius) + */ +static inline int16_t mavlink_msg_scaled_pressure3_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Decode a scaled_pressure3 message into a struct + * + * @param msg The message to decode + * @param scaled_pressure3 C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_pressure3_decode(const mavlink_message_t* msg, mavlink_scaled_pressure3_t* scaled_pressure3) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_pressure3->time_boot_ms = mavlink_msg_scaled_pressure3_get_time_boot_ms(msg); + scaled_pressure3->press_abs = mavlink_msg_scaled_pressure3_get_press_abs(msg); + scaled_pressure3->press_diff = mavlink_msg_scaled_pressure3_get_press_diff(msg); + scaled_pressure3->temperature = mavlink_msg_scaled_pressure3_get_temperature(msg); +#else + memcpy(scaled_pressure3, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_serial_control.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_serial_control.h new file mode 100644 index 0000000..ab4f10f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_serial_control.h @@ -0,0 +1,321 @@ +// MESSAGE SERIAL_CONTROL PACKING + +#define MAVLINK_MSG_ID_SERIAL_CONTROL 126 + +typedef struct __mavlink_serial_control_t +{ + uint32_t baudrate; /*< Baudrate of transfer. Zero means no change.*/ + uint16_t timeout; /*< Timeout for reply data in milliseconds*/ + uint8_t device; /*< See SERIAL_CONTROL_DEV enum*/ + uint8_t flags; /*< See SERIAL_CONTROL_FLAG enum*/ + uint8_t count; /*< how many bytes in this transfer*/ + uint8_t data[70]; /*< serial data*/ +} mavlink_serial_control_t; + +#define MAVLINK_MSG_ID_SERIAL_CONTROL_LEN 79 +#define MAVLINK_MSG_ID_126_LEN 79 + +#define MAVLINK_MSG_ID_SERIAL_CONTROL_CRC 220 +#define MAVLINK_MSG_ID_126_CRC 220 + +#define MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN 70 + +#define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL { \ + "SERIAL_CONTROL", \ + 6, \ + { { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \ + { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \ + { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \ + { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \ + { "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \ + } \ +} + + +/** + * @brief Pack a serial_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param device See SERIAL_CONTROL_DEV enum + * @param flags See SERIAL_CONTROL_FLAG enum + * @param timeout Timeout for reply data in milliseconds + * @param baudrate Baudrate of transfer. Zero means no change. + * @param count how many bytes in this transfer + * @param data serial data + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_serial_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; + _mav_put_uint32_t(buf, 0, baudrate); + _mav_put_uint16_t(buf, 4, timeout); + _mav_put_uint8_t(buf, 6, device); + _mav_put_uint8_t(buf, 7, flags); + _mav_put_uint8_t(buf, 8, count); + _mav_put_uint8_t_array(buf, 9, data, 70); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#else + mavlink_serial_control_t packet; + packet.baudrate = baudrate; + packet.timeout = timeout; + packet.device = device; + packet.flags = flags; + packet.count = count; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif +} + +/** + * @brief Pack a serial_control message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param device See SERIAL_CONTROL_DEV enum + * @param flags See SERIAL_CONTROL_FLAG enum + * @param timeout Timeout for reply data in milliseconds + * @param baudrate Baudrate of transfer. Zero means no change. + * @param count how many bytes in this transfer + * @param data serial data + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_serial_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t device,uint8_t flags,uint16_t timeout,uint32_t baudrate,uint8_t count,const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; + _mav_put_uint32_t(buf, 0, baudrate); + _mav_put_uint16_t(buf, 4, timeout); + _mav_put_uint8_t(buf, 6, device); + _mav_put_uint8_t(buf, 7, flags); + _mav_put_uint8_t(buf, 8, count); + _mav_put_uint8_t_array(buf, 9, data, 70); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#else + mavlink_serial_control_t packet; + packet.baudrate = baudrate; + packet.timeout = timeout; + packet.device = device; + packet.flags = flags; + packet.count = count; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif +} + +/** + * @brief Encode a serial_control struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param serial_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_serial_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control) +{ + return mavlink_msg_serial_control_pack(system_id, component_id, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data); +} + +/** + * @brief Encode a serial_control struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param serial_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_serial_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control) +{ + return mavlink_msg_serial_control_pack_chan(system_id, component_id, chan, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data); +} + +/** + * @brief Send a serial_control message + * @param chan MAVLink channel to send the message + * + * @param device See SERIAL_CONTROL_DEV enum + * @param flags See SERIAL_CONTROL_FLAG enum + * @param timeout Timeout for reply data in milliseconds + * @param baudrate Baudrate of transfer. Zero means no change. + * @param count how many bytes in this transfer + * @param data serial data + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_serial_control_send(mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; + _mav_put_uint32_t(buf, 0, baudrate); + _mav_put_uint16_t(buf, 4, timeout); + _mav_put_uint8_t(buf, 6, device); + _mav_put_uint8_t(buf, 7, flags); + _mav_put_uint8_t(buf, 8, count); + _mav_put_uint8_t_array(buf, 9, data, 70); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif +#else + mavlink_serial_control_t packet; + packet.baudrate = baudrate; + packet.timeout = timeout; + packet.device = device; + packet.flags = flags; + packet.count = count; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SERIAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_serial_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, baudrate); + _mav_put_uint16_t(buf, 4, timeout); + _mav_put_uint8_t(buf, 6, device); + _mav_put_uint8_t(buf, 7, flags); + _mav_put_uint8_t(buf, 8, count); + _mav_put_uint8_t_array(buf, 9, data, 70); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif +#else + mavlink_serial_control_t *packet = (mavlink_serial_control_t *)msgbuf; + packet->baudrate = baudrate; + packet->timeout = timeout; + packet->device = device; + packet->flags = flags; + packet->count = count; + mav_array_memcpy(packet->data, data, sizeof(uint8_t)*70); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SERIAL_CONTROL UNPACKING + + +/** + * @brief Get field device from serial_control message + * + * @return See SERIAL_CONTROL_DEV enum + */ +static inline uint8_t mavlink_msg_serial_control_get_device(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field flags from serial_control message + * + * @return See SERIAL_CONTROL_FLAG enum + */ +static inline uint8_t mavlink_msg_serial_control_get_flags(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field timeout from serial_control message + * + * @return Timeout for reply data in milliseconds + */ +static inline uint16_t mavlink_msg_serial_control_get_timeout(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field baudrate from serial_control message + * + * @return Baudrate of transfer. Zero means no change. + */ +static inline uint32_t mavlink_msg_serial_control_get_baudrate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field count from serial_control message + * + * @return how many bytes in this transfer + */ +static inline uint8_t mavlink_msg_serial_control_get_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field data from serial_control message + * + * @return serial data + */ +static inline uint16_t mavlink_msg_serial_control_get_data(const mavlink_message_t* msg, uint8_t *data) +{ + return _MAV_RETURN_uint8_t_array(msg, data, 70, 9); +} + +/** + * @brief Decode a serial_control message into a struct + * + * @param msg The message to decode + * @param serial_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_serial_control_decode(const mavlink_message_t* msg, mavlink_serial_control_t* serial_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + serial_control->baudrate = mavlink_msg_serial_control_get_baudrate(msg); + serial_control->timeout = mavlink_msg_serial_control_get_timeout(msg); + serial_control->device = mavlink_msg_serial_control_get_device(msg); + serial_control->flags = mavlink_msg_serial_control_get_flags(msg); + serial_control->count = mavlink_msg_serial_control_get_count(msg); + mavlink_msg_serial_control_get_data(msg, serial_control->data); +#else + memcpy(serial_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h new file mode 100644 index 0000000..d6952d0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h @@ -0,0 +1,425 @@ +// MESSAGE SERVO_OUTPUT_RAW PACKING + +#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 36 + +typedef struct __mavlink_servo_output_raw_t +{ + uint32_t time_usec; /*< Timestamp (microseconds since system boot)*/ + uint16_t servo1_raw; /*< Servo output 1 value, in microseconds*/ + uint16_t servo2_raw; /*< Servo output 2 value, in microseconds*/ + uint16_t servo3_raw; /*< Servo output 3 value, in microseconds*/ + uint16_t servo4_raw; /*< Servo output 4 value, in microseconds*/ + uint16_t servo5_raw; /*< Servo output 5 value, in microseconds*/ + uint16_t servo6_raw; /*< Servo output 6 value, in microseconds*/ + uint16_t servo7_raw; /*< Servo output 7 value, in microseconds*/ + uint16_t servo8_raw; /*< Servo output 8 value, in microseconds*/ + uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.*/ +} mavlink_servo_output_raw_t; + +#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 21 +#define MAVLINK_MSG_ID_36_LEN 21 + +#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC 222 +#define MAVLINK_MSG_ID_36_CRC 222 + + + +#define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \ + "SERVO_OUTPUT_RAW", \ + 10, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \ + { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \ + { "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \ + { "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \ + { "servo4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \ + { "servo5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \ + { "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \ + { "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \ + { "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \ + } \ +} + + +/** + * @brief Pack a servo_output_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param servo1_raw Servo output 1 value, in microseconds + * @param servo2_raw Servo output 2 value, in microseconds + * @param servo3_raw Servo output 3 value, in microseconds + * @param servo4_raw Servo output 4 value, in microseconds + * @param servo5_raw Servo output 5 value, in microseconds + * @param servo6_raw Servo output 6 value, in microseconds + * @param servo7_raw Servo output 7 value, in microseconds + * @param servo8_raw Servo output 8 value, in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN]; + _mav_put_uint32_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 4, servo1_raw); + _mav_put_uint16_t(buf, 6, servo2_raw); + _mav_put_uint16_t(buf, 8, servo3_raw); + _mav_put_uint16_t(buf, 10, servo4_raw); + _mav_put_uint16_t(buf, 12, servo5_raw); + _mav_put_uint16_t(buf, 14, servo6_raw); + _mav_put_uint16_t(buf, 16, servo7_raw); + _mav_put_uint16_t(buf, 18, servo8_raw); + _mav_put_uint8_t(buf, 20, port); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#else + mavlink_servo_output_raw_t packet; + packet.time_usec = time_usec; + packet.servo1_raw = servo1_raw; + packet.servo2_raw = servo2_raw; + packet.servo3_raw = servo3_raw; + packet.servo4_raw = servo4_raw; + packet.servo5_raw = servo5_raw; + packet.servo6_raw = servo6_raw; + packet.servo7_raw = servo7_raw; + packet.servo8_raw = servo8_raw; + packet.port = port; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif +} + +/** + * @brief Pack a servo_output_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param servo1_raw Servo output 1 value, in microseconds + * @param servo2_raw Servo output 2 value, in microseconds + * @param servo3_raw Servo output 3 value, in microseconds + * @param servo4_raw Servo output 4 value, in microseconds + * @param servo5_raw Servo output 5 value, in microseconds + * @param servo6_raw Servo output 6 value, in microseconds + * @param servo7_raw Servo output 7 value, in microseconds + * @param servo8_raw Servo output 8 value, in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_usec,uint8_t port,uint16_t servo1_raw,uint16_t servo2_raw,uint16_t servo3_raw,uint16_t servo4_raw,uint16_t servo5_raw,uint16_t servo6_raw,uint16_t servo7_raw,uint16_t servo8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN]; + _mav_put_uint32_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 4, servo1_raw); + _mav_put_uint16_t(buf, 6, servo2_raw); + _mav_put_uint16_t(buf, 8, servo3_raw); + _mav_put_uint16_t(buf, 10, servo4_raw); + _mav_put_uint16_t(buf, 12, servo5_raw); + _mav_put_uint16_t(buf, 14, servo6_raw); + _mav_put_uint16_t(buf, 16, servo7_raw); + _mav_put_uint16_t(buf, 18, servo8_raw); + _mav_put_uint8_t(buf, 20, port); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#else + mavlink_servo_output_raw_t packet; + packet.time_usec = time_usec; + packet.servo1_raw = servo1_raw; + packet.servo2_raw = servo2_raw; + packet.servo3_raw = servo3_raw; + packet.servo4_raw = servo4_raw; + packet.servo5_raw = servo5_raw; + packet.servo6_raw = servo6_raw; + packet.servo7_raw = servo7_raw; + packet.servo8_raw = servo8_raw; + packet.port = port; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif +} + +/** + * @brief Encode a servo_output_raw struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param servo_output_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw) +{ + return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw); +} + +/** + * @brief Encode a servo_output_raw struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param servo_output_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_servo_output_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw) +{ + return mavlink_msg_servo_output_raw_pack_chan(system_id, component_id, chan, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw); +} + +/** + * @brief Send a servo_output_raw message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param servo1_raw Servo output 1 value, in microseconds + * @param servo2_raw Servo output 2 value, in microseconds + * @param servo3_raw Servo output 3 value, in microseconds + * @param servo4_raw Servo output 4 value, in microseconds + * @param servo5_raw Servo output 5 value, in microseconds + * @param servo6_raw Servo output 6 value, in microseconds + * @param servo7_raw Servo output 7 value, in microseconds + * @param servo8_raw Servo output 8 value, in microseconds + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN]; + _mav_put_uint32_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 4, servo1_raw); + _mav_put_uint16_t(buf, 6, servo2_raw); + _mav_put_uint16_t(buf, 8, servo3_raw); + _mav_put_uint16_t(buf, 10, servo4_raw); + _mav_put_uint16_t(buf, 12, servo5_raw); + _mav_put_uint16_t(buf, 14, servo6_raw); + _mav_put_uint16_t(buf, 16, servo7_raw); + _mav_put_uint16_t(buf, 18, servo8_raw); + _mav_put_uint8_t(buf, 20, port); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif +#else + mavlink_servo_output_raw_t packet; + packet.time_usec = time_usec; + packet.servo1_raw = servo1_raw; + packet.servo2_raw = servo2_raw; + packet.servo3_raw = servo3_raw; + packet.servo4_raw = servo4_raw; + packet.servo5_raw = servo5_raw; + packet.servo6_raw = servo6_raw; + packet.servo7_raw = servo7_raw; + packet.servo8_raw = servo8_raw; + packet.port = port; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_servo_output_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 4, servo1_raw); + _mav_put_uint16_t(buf, 6, servo2_raw); + _mav_put_uint16_t(buf, 8, servo3_raw); + _mav_put_uint16_t(buf, 10, servo4_raw); + _mav_put_uint16_t(buf, 12, servo5_raw); + _mav_put_uint16_t(buf, 14, servo6_raw); + _mav_put_uint16_t(buf, 16, servo7_raw); + _mav_put_uint16_t(buf, 18, servo8_raw); + _mav_put_uint8_t(buf, 20, port); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif +#else + mavlink_servo_output_raw_t *packet = (mavlink_servo_output_raw_t *)msgbuf; + packet->time_usec = time_usec; + packet->servo1_raw = servo1_raw; + packet->servo2_raw = servo2_raw; + packet->servo3_raw = servo3_raw; + packet->servo4_raw = servo4_raw; + packet->servo5_raw = servo5_raw; + packet->servo6_raw = servo6_raw; + packet->servo7_raw = servo7_raw; + packet->servo8_raw = servo8_raw; + packet->port = port; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SERVO_OUTPUT_RAW UNPACKING + + +/** + * @brief Get field time_usec from servo_output_raw message + * + * @return Timestamp (microseconds since system boot) + */ +static inline uint32_t mavlink_msg_servo_output_raw_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field port from servo_output_raw message + * + * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + */ +static inline uint8_t mavlink_msg_servo_output_raw_get_port(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field servo1_raw from servo_output_raw message + * + * @return Servo output 1 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field servo2_raw from servo_output_raw message + * + * @return Servo output 2 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field servo3_raw from servo_output_raw message + * + * @return Servo output 3 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field servo4_raw from servo_output_raw message + * + * @return Servo output 4 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field servo5_raw from servo_output_raw message + * + * @return Servo output 5 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field servo6_raw from servo_output_raw message + * + * @return Servo output 6 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field servo7_raw from servo_output_raw message + * + * @return Servo output 7 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field servo8_raw from servo_output_raw message + * + * @return Servo output 8 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Decode a servo_output_raw message into a struct + * + * @param msg The message to decode + * @param servo_output_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* msg, mavlink_servo_output_raw_t* servo_output_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + servo_output_raw->time_usec = mavlink_msg_servo_output_raw_get_time_usec(msg); + servo_output_raw->servo1_raw = mavlink_msg_servo_output_raw_get_servo1_raw(msg); + servo_output_raw->servo2_raw = mavlink_msg_servo_output_raw_get_servo2_raw(msg); + servo_output_raw->servo3_raw = mavlink_msg_servo_output_raw_get_servo3_raw(msg); + servo_output_raw->servo4_raw = mavlink_msg_servo_output_raw_get_servo4_raw(msg); + servo_output_raw->servo5_raw = mavlink_msg_servo_output_raw_get_servo5_raw(msg); + servo_output_raw->servo6_raw = mavlink_msg_servo_output_raw_get_servo6_raw(msg); + servo_output_raw->servo7_raw = mavlink_msg_servo_output_raw_get_servo7_raw(msg); + servo_output_raw->servo8_raw = mavlink_msg_servo_output_raw_get_servo8_raw(msg); + servo_output_raw->port = mavlink_msg_servo_output_raw_get_port(msg); +#else + memcpy(servo_output_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_actuator_control_target.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_actuator_control_target.h new file mode 100644 index 0000000..5632dba --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_actuator_control_target.h @@ -0,0 +1,297 @@ +// MESSAGE SET_ACTUATOR_CONTROL_TARGET PACKING + +#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET 139 + +typedef struct __mavlink_set_actuator_control_target_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/ + uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_set_actuator_control_target_t; + +#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN 43 +#define MAVLINK_MSG_ID_139_LEN 43 + +#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC 168 +#define MAVLINK_MSG_ID_139_CRC 168 + +#define MAVLINK_MSG_SET_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS_LEN 8 + +#define MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET { \ + "SET_ACTUATOR_CONTROL_TARGET", \ + 5, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_set_actuator_control_target_t, time_usec) }, \ + { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_set_actuator_control_target_t, controls) }, \ + { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_set_actuator_control_target_t, group_mlx) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_set_actuator_control_target_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_set_actuator_control_target_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a set_actuator_control_target message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param target_system System ID + * @param target_component Component ID + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_uint8_t(buf, 41, target_system); + _mav_put_uint8_t(buf, 42, target_component); + _mav_put_float_array(buf, 8, controls, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#else + mavlink_set_actuator_control_target_t packet; + packet.time_usec = time_usec; + packet.group_mlx = group_mlx; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.controls, controls, sizeof(float)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif +} + +/** + * @brief Pack a set_actuator_control_target message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param target_system System ID + * @param target_component Component ID + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t group_mlx,uint8_t target_system,uint8_t target_component,const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_uint8_t(buf, 41, target_system); + _mav_put_uint8_t(buf, 42, target_component); + _mav_put_float_array(buf, 8, controls, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#else + mavlink_set_actuator_control_target_t packet; + packet.time_usec = time_usec; + packet.group_mlx = group_mlx; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.controls, controls, sizeof(float)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif +} + +/** + * @brief Encode a set_actuator_control_target struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_actuator_control_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_actuator_control_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_actuator_control_target_t* set_actuator_control_target) +{ + return mavlink_msg_set_actuator_control_target_pack(system_id, component_id, msg, set_actuator_control_target->time_usec, set_actuator_control_target->group_mlx, set_actuator_control_target->target_system, set_actuator_control_target->target_component, set_actuator_control_target->controls); +} + +/** + * @brief Encode a set_actuator_control_target struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param set_actuator_control_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_actuator_control_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_actuator_control_target_t* set_actuator_control_target) +{ + return mavlink_msg_set_actuator_control_target_pack_chan(system_id, component_id, chan, msg, set_actuator_control_target->time_usec, set_actuator_control_target->group_mlx, set_actuator_control_target->target_system, set_actuator_control_target->target_component, set_actuator_control_target->controls); +} + +/** + * @brief Send a set_actuator_control_target message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param target_system System ID + * @param target_component Component ID + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_actuator_control_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_uint8_t(buf, 41, target_system); + _mav_put_uint8_t(buf, 42, target_component); + _mav_put_float_array(buf, 8, controls, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#else + mavlink_set_actuator_control_target_t packet; + packet.time_usec = time_usec; + packet.group_mlx = group_mlx; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.controls, controls, sizeof(float)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_set_actuator_control_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_uint8_t(buf, 41, target_system); + _mav_put_uint8_t(buf, 42, target_component); + _mav_put_float_array(buf, 8, controls, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#else + mavlink_set_actuator_control_target_t *packet = (mavlink_set_actuator_control_target_t *)msgbuf; + packet->time_usec = time_usec; + packet->group_mlx = group_mlx; + packet->target_system = target_system; + packet->target_component = target_component; + mav_array_memcpy(packet->controls, controls, sizeof(float)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SET_ACTUATOR_CONTROL_TARGET UNPACKING + + +/** + * @brief Get field time_usec from set_actuator_control_target message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_set_actuator_control_target_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field group_mlx from set_actuator_control_target message + * + * @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + */ +static inline uint8_t mavlink_msg_set_actuator_control_target_get_group_mlx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 40); +} + +/** + * @brief Get field target_system from set_actuator_control_target message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 41); +} + +/** + * @brief Get field target_component from set_actuator_control_target message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 42); +} + +/** + * @brief Get field controls from set_actuator_control_target message + * + * @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + */ +static inline uint16_t mavlink_msg_set_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls) +{ + return _MAV_RETURN_float_array(msg, controls, 8, 8); +} + +/** + * @brief Decode a set_actuator_control_target message into a struct + * + * @param msg The message to decode + * @param set_actuator_control_target C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_actuator_control_target_decode(const mavlink_message_t* msg, mavlink_set_actuator_control_target_t* set_actuator_control_target) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_actuator_control_target->time_usec = mavlink_msg_set_actuator_control_target_get_time_usec(msg); + mavlink_msg_set_actuator_control_target_get_controls(msg, set_actuator_control_target->controls); + set_actuator_control_target->group_mlx = mavlink_msg_set_actuator_control_target_get_group_mlx(msg); + set_actuator_control_target->target_system = mavlink_msg_set_actuator_control_target_get_target_system(msg); + set_actuator_control_target->target_component = mavlink_msg_set_actuator_control_target_get_target_component(msg); +#else + memcpy(set_actuator_control_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_attitude_target.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_attitude_target.h new file mode 100644 index 0000000..cca0d72 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_attitude_target.h @@ -0,0 +1,393 @@ +// MESSAGE SET_ATTITUDE_TARGET PACKING + +#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET 82 + +typedef struct __mavlink_set_attitude_target_t +{ + uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ + float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ + float body_roll_rate; /*< Body roll rate in radians per second*/ + float body_pitch_rate; /*< Body roll rate in radians per second*/ + float body_yaw_rate; /*< Body roll rate in radians per second*/ + float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t type_mask; /*< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude*/ +} mavlink_set_attitude_target_t; + +#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN 39 +#define MAVLINK_MSG_ID_82_LEN 39 + +#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC 49 +#define MAVLINK_MSG_ID_82_CRC 49 + +#define MAVLINK_MSG_SET_ATTITUDE_TARGET_FIELD_Q_LEN 4 + +#define MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET { \ + "SET_ATTITUDE_TARGET", \ + 9, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_attitude_target_t, time_boot_ms) }, \ + { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_set_attitude_target_t, q) }, \ + { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_attitude_target_t, body_roll_rate) }, \ + { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_attitude_target_t, body_pitch_rate) }, \ + { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_attitude_target_t, body_yaw_rate) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_attitude_target_t, thrust) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_set_attitude_target_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_set_attitude_target_t, target_component) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_set_attitude_target_t, type_mask) }, \ + } \ +} + + +/** + * @brief Pack a set_attitude_target message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate Body roll rate in radians per second + * @param body_pitch_rate Body roll rate in radians per second + * @param body_yaw_rate Body roll rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, target_system); + _mav_put_uint8_t(buf, 37, target_component); + _mav_put_uint8_t(buf, 38, type_mask); + _mav_put_float_array(buf, 4, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#else + mavlink_set_attitude_target_t packet; + packet.time_boot_ms = time_boot_ms; + packet.body_roll_rate = body_roll_rate; + packet.body_pitch_rate = body_pitch_rate; + packet.body_yaw_rate = body_yaw_rate; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type_mask = type_mask; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ATTITUDE_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif +} + +/** + * @brief Pack a set_attitude_target message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate Body roll rate in radians per second + * @param body_pitch_rate Body roll rate in radians per second + * @param body_yaw_rate Body roll rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t type_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, target_system); + _mav_put_uint8_t(buf, 37, target_component); + _mav_put_uint8_t(buf, 38, type_mask); + _mav_put_float_array(buf, 4, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#else + mavlink_set_attitude_target_t packet; + packet.time_boot_ms = time_boot_ms; + packet.body_roll_rate = body_roll_rate; + packet.body_pitch_rate = body_pitch_rate; + packet.body_yaw_rate = body_yaw_rate; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type_mask = type_mask; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ATTITUDE_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif +} + +/** + * @brief Encode a set_attitude_target struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_attitude_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_attitude_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_attitude_target_t* set_attitude_target) +{ + return mavlink_msg_set_attitude_target_pack(system_id, component_id, msg, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust); +} + +/** + * @brief Encode a set_attitude_target struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param set_attitude_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_attitude_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_attitude_target_t* set_attitude_target) +{ + return mavlink_msg_set_attitude_target_pack_chan(system_id, component_id, chan, msg, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust); +} + +/** + * @brief Send a set_attitude_target message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate Body roll rate in radians per second + * @param body_pitch_rate Body roll rate in radians per second + * @param body_yaw_rate Body roll rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_attitude_target_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, target_system); + _mav_put_uint8_t(buf, 37, target_component); + _mav_put_uint8_t(buf, 38, type_mask); + _mav_put_float_array(buf, 4, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif +#else + mavlink_set_attitude_target_t packet; + packet.time_boot_ms = time_boot_ms; + packet.body_roll_rate = body_roll_rate; + packet.body_pitch_rate = body_pitch_rate; + packet.body_yaw_rate = body_yaw_rate; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type_mask = type_mask; + mav_array_memcpy(packet.q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_set_attitude_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, target_system); + _mav_put_uint8_t(buf, 37, target_component); + _mav_put_uint8_t(buf, 38, type_mask); + _mav_put_float_array(buf, 4, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif +#else + mavlink_set_attitude_target_t *packet = (mavlink_set_attitude_target_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->body_roll_rate = body_roll_rate; + packet->body_pitch_rate = body_pitch_rate; + packet->body_yaw_rate = body_yaw_rate; + packet->thrust = thrust; + packet->target_system = target_system; + packet->target_component = target_component; + packet->type_mask = type_mask; + mav_array_memcpy(packet->q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SET_ATTITUDE_TARGET UNPACKING + + +/** + * @brief Get field time_boot_ms from set_attitude_target message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_set_attitude_target_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field target_system from set_attitude_target message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_attitude_target_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Get field target_component from set_attitude_target message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_attitude_target_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 37); +} + +/** + * @brief Get field type_mask from set_attitude_target message + * + * @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + */ +static inline uint8_t mavlink_msg_set_attitude_target_get_type_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 38); +} + +/** + * @brief Get field q from set_attitude_target message + * + * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + */ +static inline uint16_t mavlink_msg_set_attitude_target_get_q(const mavlink_message_t* msg, float *q) +{ + return _MAV_RETURN_float_array(msg, q, 4, 4); +} + +/** + * @brief Get field body_roll_rate from set_attitude_target message + * + * @return Body roll rate in radians per second + */ +static inline float mavlink_msg_set_attitude_target_get_body_roll_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field body_pitch_rate from set_attitude_target message + * + * @return Body roll rate in radians per second + */ +static inline float mavlink_msg_set_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field body_yaw_rate from set_attitude_target message + * + * @return Body roll rate in radians per second + */ +static inline float mavlink_msg_set_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field thrust from set_attitude_target message + * + * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + */ +static inline float mavlink_msg_set_attitude_target_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Decode a set_attitude_target message into a struct + * + * @param msg The message to decode + * @param set_attitude_target C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_attitude_target_decode(const mavlink_message_t* msg, mavlink_set_attitude_target_t* set_attitude_target) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_attitude_target->time_boot_ms = mavlink_msg_set_attitude_target_get_time_boot_ms(msg); + mavlink_msg_set_attitude_target_get_q(msg, set_attitude_target->q); + set_attitude_target->body_roll_rate = mavlink_msg_set_attitude_target_get_body_roll_rate(msg); + set_attitude_target->body_pitch_rate = mavlink_msg_set_attitude_target_get_body_pitch_rate(msg); + set_attitude_target->body_yaw_rate = mavlink_msg_set_attitude_target_get_body_yaw_rate(msg); + set_attitude_target->thrust = mavlink_msg_set_attitude_target_get_thrust(msg); + set_attitude_target->target_system = mavlink_msg_set_attitude_target_get_target_system(msg); + set_attitude_target->target_component = mavlink_msg_set_attitude_target_get_target_component(msg); + set_attitude_target->type_mask = mavlink_msg_set_attitude_target_get_type_mask(msg); +#else + memcpy(set_attitude_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h new file mode 100644 index 0000000..6644a61 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h @@ -0,0 +1,281 @@ +// MESSAGE SET_GPS_GLOBAL_ORIGIN PACKING + +#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN 48 + +typedef struct __mavlink_set_gps_global_origin_t +{ + int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/ + int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ + uint8_t target_system; /*< System ID*/ +} mavlink_set_gps_global_origin_t; + +#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN 13 +#define MAVLINK_MSG_ID_48_LEN 13 + +#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC 41 +#define MAVLINK_MSG_ID_48_CRC 41 + + + +#define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \ + "SET_GPS_GLOBAL_ORIGIN", \ + 4, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \ + } \ +} + + +/** + * @brief Pack a set_gps_global_origin message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#else + mavlink_set_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.target_system = target_system; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif +} + +/** + * @brief Pack a set_gps_global_origin message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,int32_t latitude,int32_t longitude,int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#else + mavlink_set_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.target_system = target_system; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif +} + +/** + * @brief Encode a set_gps_global_origin struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_gps_global_origin C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin) +{ + return mavlink_msg_set_gps_global_origin_pack(system_id, component_id, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude); +} + +/** + * @brief Encode a set_gps_global_origin struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param set_gps_global_origin C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_gps_global_origin_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin) +{ + return mavlink_msg_set_gps_global_origin_pack_chan(system_id, component_id, chan, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude); +} + +/** + * @brief Send a set_gps_global_origin message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_gps_global_origin_send(mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif +#else + mavlink_set_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.target_system = target_system; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_set_gps_global_origin_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif +#else + mavlink_set_gps_global_origin_t *packet = (mavlink_set_gps_global_origin_t *)msgbuf; + packet->latitude = latitude; + packet->longitude = longitude; + packet->altitude = altitude; + packet->target_system = target_system; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SET_GPS_GLOBAL_ORIGIN UNPACKING + + +/** + * @brief Get field target_system from set_gps_global_origin message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_gps_global_origin_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field latitude from set_gps_global_origin message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_set_gps_global_origin_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from set_gps_global_origin message + * + * @return Longitude (WGS84, in degrees * 1E7 + */ +static inline int32_t mavlink_msg_set_gps_global_origin_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from set_gps_global_origin message + * + * @return Altitude (AMSL), in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_set_gps_global_origin_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Decode a set_gps_global_origin message into a struct + * + * @param msg The message to decode + * @param set_gps_global_origin C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_set_gps_global_origin_t* set_gps_global_origin) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_gps_global_origin->latitude = mavlink_msg_set_gps_global_origin_get_latitude(msg); + set_gps_global_origin->longitude = mavlink_msg_set_gps_global_origin_get_longitude(msg); + set_gps_global_origin->altitude = mavlink_msg_set_gps_global_origin_get_altitude(msg); + set_gps_global_origin->target_system = mavlink_msg_set_gps_global_origin_get_target_system(msg); +#else + memcpy(set_gps_global_origin, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_home_position.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_home_position.h new file mode 100644 index 0000000..91ed1c7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_home_position.h @@ -0,0 +1,441 @@ +// MESSAGE SET_HOME_POSITION PACKING + +#define MAVLINK_MSG_ID_SET_HOME_POSITION 243 + +typedef struct __mavlink_set_home_position_t +{ + int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/ + int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ + float x; /*< Local X position of this position in the local coordinate frame*/ + float y; /*< Local Y position of this position in the local coordinate frame*/ + float z; /*< Local Z position of this position in the local coordinate frame*/ + float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/ + float approach_x; /*< Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ + float approach_y; /*< Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ + float approach_z; /*< Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ + uint8_t target_system; /*< System ID.*/ +} mavlink_set_home_position_t; + +#define MAVLINK_MSG_ID_SET_HOME_POSITION_LEN 53 +#define MAVLINK_MSG_ID_243_LEN 53 + +#define MAVLINK_MSG_ID_SET_HOME_POSITION_CRC 85 +#define MAVLINK_MSG_ID_243_CRC 85 + +#define MAVLINK_MSG_SET_HOME_POSITION_FIELD_Q_LEN 4 + +#define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION { \ + "SET_HOME_POSITION", \ + 11, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_home_position_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_home_position_t, altitude) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_home_position_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_home_position_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_home_position_t, z) }, \ + { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_set_home_position_t, q) }, \ + { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_home_position_t, approach_x) }, \ + { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_home_position_t, approach_y) }, \ + { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_set_home_position_t, approach_z) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \ + } \ +} + + +/** + * @brief Pack a set_home_position message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID. + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param x Local X position of this position in the local coordinate frame + * @param y Local Y position of this position in the local coordinate frame + * @param z Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_uint8_t(buf, 52, target_system); + _mav_put_float_array(buf, 24, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#else + mavlink_set_home_position_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.x = x; + packet.y = y; + packet.z = z; + packet.approach_x = approach_x; + packet.approach_y = approach_y; + packet.approach_z = approach_z; + packet.target_system = target_system; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_HOME_POSITION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif +} + +/** + * @brief Pack a set_home_position message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID. + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param x Local X position of this position in the local coordinate frame + * @param y Local Y position of this position in the local coordinate frame + * @param z Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,int32_t latitude,int32_t longitude,int32_t altitude,float x,float y,float z,const float *q,float approach_x,float approach_y,float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_uint8_t(buf, 52, target_system); + _mav_put_float_array(buf, 24, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#else + mavlink_set_home_position_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.x = x; + packet.y = y; + packet.z = z; + packet.approach_x = approach_x; + packet.approach_y = approach_y; + packet.approach_z = approach_z; + packet.target_system = target_system; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_HOME_POSITION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif +} + +/** + * @brief Encode a set_home_position struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_home_position C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_home_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_home_position_t* set_home_position) +{ + return mavlink_msg_set_home_position_pack(system_id, component_id, msg, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z); +} + +/** + * @brief Encode a set_home_position struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param set_home_position C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_home_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_home_position_t* set_home_position) +{ + return mavlink_msg_set_home_position_pack_chan(system_id, component_id, chan, msg, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z); +} + +/** + * @brief Send a set_home_position message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID. + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param x Local X position of this position in the local coordinate frame + * @param y Local Y position of this position in the local coordinate frame + * @param z Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_home_position_send(mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_uint8_t(buf, 52, target_system); + _mav_put_float_array(buf, 24, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif +#else + mavlink_set_home_position_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.x = x; + packet.y = y; + packet.z = z; + packet.approach_x = approach_x; + packet.approach_y = approach_y; + packet.approach_z = approach_z; + packet.target_system = target_system; + mav_array_memcpy(packet.q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SET_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_set_home_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_uint8_t(buf, 52, target_system); + _mav_put_float_array(buf, 24, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif +#else + mavlink_set_home_position_t *packet = (mavlink_set_home_position_t *)msgbuf; + packet->latitude = latitude; + packet->longitude = longitude; + packet->altitude = altitude; + packet->x = x; + packet->y = y; + packet->z = z; + packet->approach_x = approach_x; + packet->approach_y = approach_y; + packet->approach_z = approach_z; + packet->target_system = target_system; + mav_array_memcpy(packet->q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SET_HOME_POSITION UNPACKING + + +/** + * @brief Get field target_system from set_home_position message + * + * @return System ID. + */ +static inline uint8_t mavlink_msg_set_home_position_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 52); +} + +/** + * @brief Get field latitude from set_home_position message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_set_home_position_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from set_home_position message + * + * @return Longitude (WGS84, in degrees * 1E7 + */ +static inline int32_t mavlink_msg_set_home_position_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from set_home_position message + * + * @return Altitude (AMSL), in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_set_home_position_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field x from set_home_position message + * + * @return Local X position of this position in the local coordinate frame + */ +static inline float mavlink_msg_set_home_position_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field y from set_home_position message + * + * @return Local Y position of this position in the local coordinate frame + */ +static inline float mavlink_msg_set_home_position_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field z from set_home_position message + * + * @return Local Z position of this position in the local coordinate frame + */ +static inline float mavlink_msg_set_home_position_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field q from set_home_position message + * + * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + */ +static inline uint16_t mavlink_msg_set_home_position_get_q(const mavlink_message_t* msg, float *q) +{ + return _MAV_RETURN_float_array(msg, q, 4, 24); +} + +/** + * @brief Get field approach_x from set_home_position message + * + * @return Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +static inline float mavlink_msg_set_home_position_get_approach_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field approach_y from set_home_position message + * + * @return Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +static inline float mavlink_msg_set_home_position_get_approach_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field approach_z from set_home_position message + * + * @return Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +static inline float mavlink_msg_set_home_position_get_approach_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 48); +} + +/** + * @brief Decode a set_home_position message into a struct + * + * @param msg The message to decode + * @param set_home_position C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_home_position_decode(const mavlink_message_t* msg, mavlink_set_home_position_t* set_home_position) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_home_position->latitude = mavlink_msg_set_home_position_get_latitude(msg); + set_home_position->longitude = mavlink_msg_set_home_position_get_longitude(msg); + set_home_position->altitude = mavlink_msg_set_home_position_get_altitude(msg); + set_home_position->x = mavlink_msg_set_home_position_get_x(msg); + set_home_position->y = mavlink_msg_set_home_position_get_y(msg); + set_home_position->z = mavlink_msg_set_home_position_get_z(msg); + mavlink_msg_set_home_position_get_q(msg, set_home_position->q); + set_home_position->approach_x = mavlink_msg_set_home_position_get_approach_x(msg); + set_home_position->approach_y = mavlink_msg_set_home_position_get_approach_y(msg); + set_home_position->approach_z = mavlink_msg_set_home_position_get_approach_z(msg); + set_home_position->target_system = mavlink_msg_set_home_position_get_target_system(msg); +#else + memcpy(set_home_position, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_mode.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_mode.h new file mode 100644 index 0000000..849c1a4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_mode.h @@ -0,0 +1,257 @@ +// MESSAGE SET_MODE PACKING + +#define MAVLINK_MSG_ID_SET_MODE 11 + +typedef struct __mavlink_set_mode_t +{ + uint32_t custom_mode; /*< The new autopilot-specific mode. This field can be ignored by an autopilot.*/ + uint8_t target_system; /*< The system setting the mode*/ + uint8_t base_mode; /*< The new base mode*/ +} mavlink_set_mode_t; + +#define MAVLINK_MSG_ID_SET_MODE_LEN 6 +#define MAVLINK_MSG_ID_11_LEN 6 + +#define MAVLINK_MSG_ID_SET_MODE_CRC 89 +#define MAVLINK_MSG_ID_11_CRC 89 + + + +#define MAVLINK_MESSAGE_INFO_SET_MODE { \ + "SET_MODE", \ + 3, \ + { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ + { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \ + } \ +} + + +/** + * @brief Pack a set_mode message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system The system setting the mode + * @param base_mode The new base mode + * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_MODE_LEN]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, base_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MODE_LEN); +#else + mavlink_set_mode_t packet; + packet.custom_mode = custom_mode; + packet.target_system = target_system; + packet.base_mode = base_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_MODE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif +} + +/** + * @brief Pack a set_mode message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system The system setting the mode + * @param base_mode The new base mode + * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t base_mode,uint32_t custom_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_MODE_LEN]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, base_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MODE_LEN); +#else + mavlink_set_mode_t packet; + packet.custom_mode = custom_mode; + packet.target_system = target_system; + packet.base_mode = base_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_MODE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif +} + +/** + * @brief Encode a set_mode struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_mode C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) +{ + return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); +} + +/** + * @brief Encode a set_mode struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param set_mode C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_mode_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) +{ + return mavlink_msg_set_mode_pack_chan(system_id, component_id, chan, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); +} + +/** + * @brief Send a set_mode message + * @param chan MAVLink channel to send the message + * + * @param target_system The system setting the mode + * @param base_mode The new base mode + * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_MODE_LEN]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, base_mode); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif +#else + mavlink_set_mode_t packet; + packet.custom_mode = custom_mode; + packet.target_system = target_system; + packet.base_mode = base_mode; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SET_MODE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_set_mode_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, base_mode); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif +#else + mavlink_set_mode_t *packet = (mavlink_set_mode_t *)msgbuf; + packet->custom_mode = custom_mode; + packet->target_system = target_system; + packet->base_mode = base_mode; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)packet, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)packet, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SET_MODE UNPACKING + + +/** + * @brief Get field target_system from set_mode message + * + * @return The system setting the mode + */ +static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field base_mode from set_mode message + * + * @return The new base mode + */ +static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field custom_mode from set_mode message + * + * @return The new autopilot-specific mode. This field can be ignored by an autopilot. + */ +static inline uint32_t mavlink_msg_set_mode_get_custom_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Decode a set_mode message into a struct + * + * @param msg The message to decode + * @param set_mode C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_mode->custom_mode = mavlink_msg_set_mode_get_custom_mode(msg); + set_mode->target_system = mavlink_msg_set_mode_get_target_system(msg); + set_mode->base_mode = mavlink_msg_set_mode_get_base_mode(msg); +#else + memcpy(set_mode, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_MODE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_position_target_global_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_position_target_global_int.h new file mode 100644 index 0000000..b63b636 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_position_target_global_int.h @@ -0,0 +1,569 @@ +// MESSAGE SET_POSITION_TARGET_GLOBAL_INT PACKING + +#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT 86 + +typedef struct __mavlink_set_position_target_global_int_t +{ + uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/ + int32_t lat_int; /*< X Position in WGS84 frame in 1e7 * meters*/ + int32_t lon_int; /*< Y Position in WGS84 frame in 1e7 * meters*/ + float alt; /*< Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT*/ + float vx; /*< X velocity in NED frame in meter / s*/ + float vy; /*< Y velocity in NED frame in meter / s*/ + float vz; /*< Z velocity in NED frame in meter / s*/ + float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float yaw; /*< yaw setpoint in rad*/ + float yaw_rate; /*< yaw rate setpoint in rad/s*/ + uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/ +} mavlink_set_position_target_global_int_t; + +#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN 53 +#define MAVLINK_MSG_ID_86_LEN 53 + +#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC 5 +#define MAVLINK_MSG_ID_86_CRC 5 + + + +#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \ + "SET_POSITION_TARGET_GLOBAL_INT", \ + 16, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \ + { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \ + { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_global_int_t, alt) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_global_int_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_global_int_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_global_int_t, vz) }, \ + { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_global_int_t, afx) }, \ + { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_global_int_t, afy) }, \ + { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \ + { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a set_position_target_global_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param lat_int X Position in WGS84 frame in 1e7 * meters + * @param lon_int Y Position in WGS84 frame in 1e7 * meters + * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#else + mavlink_set_position_target_global_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat_int = lat_int; + packet.lon_int = lon_int; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +} + +/** + * @brief Pack a set_position_target_global_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param lat_int X Position in WGS84 frame in 1e7 * meters + * @param lon_int Y Position in WGS84 frame in 1e7 * meters + * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#else + mavlink_set_position_target_global_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat_int = lat_int; + packet.lon_int = lon_int; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +} + +/** + * @brief Encode a set_position_target_global_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_position_target_global_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int) +{ + return mavlink_msg_set_position_target_global_int_pack(system_id, component_id, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate); +} + +/** + * @brief Encode a set_position_target_global_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param set_position_target_global_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int) +{ + return mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, chan, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate); +} + +/** + * @brief Send a set_position_target_global_int message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param lat_int X Position in WGS84 frame in 1e7 * meters + * @param lon_int Y Position in WGS84 frame in 1e7 * meters + * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#else + mavlink_set_position_target_global_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat_int = lat_int; + packet.lon_int = lon_int; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_set_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#else + mavlink_set_position_target_global_int_t *packet = (mavlink_set_position_target_global_int_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->lat_int = lat_int; + packet->lon_int = lon_int; + packet->alt = alt; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->afx = afx; + packet->afy = afy; + packet->afz = afz; + packet->yaw = yaw; + packet->yaw_rate = yaw_rate; + packet->type_mask = type_mask; + packet->target_system = target_system; + packet->target_component = target_component; + packet->coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SET_POSITION_TARGET_GLOBAL_INT UNPACKING + + +/** + * @brief Get field time_boot_ms from set_position_target_global_int message + * + * @return Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + */ +static inline uint32_t mavlink_msg_set_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field target_system from set_position_target_global_int message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 50); +} + +/** + * @brief Get field target_component from set_position_target_global_int message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 51); +} + +/** + * @brief Get field coordinate_frame from set_position_target_global_int message + * + * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + */ +static inline uint8_t mavlink_msg_set_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 52); +} + +/** + * @brief Get field type_mask from set_position_target_global_int message + * + * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + */ +static inline uint16_t mavlink_msg_set_position_target_global_int_get_type_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 48); +} + +/** + * @brief Get field lat_int from set_position_target_global_int message + * + * @return X Position in WGS84 frame in 1e7 * meters + */ +static inline int32_t mavlink_msg_set_position_target_global_int_get_lat_int(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field lon_int from set_position_target_global_int message + * + * @return Y Position in WGS84 frame in 1e7 * meters + */ +static inline int32_t mavlink_msg_set_position_target_global_int_get_lon_int(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field alt from set_position_target_global_int message + * + * @return Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + */ +static inline float mavlink_msg_set_position_target_global_int_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vx from set_position_target_global_int message + * + * @return X velocity in NED frame in meter / s + */ +static inline float mavlink_msg_set_position_target_global_int_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vy from set_position_target_global_int message + * + * @return Y velocity in NED frame in meter / s + */ +static inline float mavlink_msg_set_position_target_global_int_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vz from set_position_target_global_int message + * + * @return Z velocity in NED frame in meter / s + */ +static inline float mavlink_msg_set_position_target_global_int_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field afx from set_position_target_global_int message + * + * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_set_position_target_global_int_get_afx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field afy from set_position_target_global_int message + * + * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_set_position_target_global_int_get_afy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field afz from set_position_target_global_int message + * + * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_set_position_target_global_int_get_afz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field yaw from set_position_target_global_int message + * + * @return yaw setpoint in rad + */ +static inline float mavlink_msg_set_position_target_global_int_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field yaw_rate from set_position_target_global_int message + * + * @return yaw rate setpoint in rad/s + */ +static inline float mavlink_msg_set_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Decode a set_position_target_global_int message into a struct + * + * @param msg The message to decode + * @param set_position_target_global_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_position_target_global_int_decode(const mavlink_message_t* msg, mavlink_set_position_target_global_int_t* set_position_target_global_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_position_target_global_int->time_boot_ms = mavlink_msg_set_position_target_global_int_get_time_boot_ms(msg); + set_position_target_global_int->lat_int = mavlink_msg_set_position_target_global_int_get_lat_int(msg); + set_position_target_global_int->lon_int = mavlink_msg_set_position_target_global_int_get_lon_int(msg); + set_position_target_global_int->alt = mavlink_msg_set_position_target_global_int_get_alt(msg); + set_position_target_global_int->vx = mavlink_msg_set_position_target_global_int_get_vx(msg); + set_position_target_global_int->vy = mavlink_msg_set_position_target_global_int_get_vy(msg); + set_position_target_global_int->vz = mavlink_msg_set_position_target_global_int_get_vz(msg); + set_position_target_global_int->afx = mavlink_msg_set_position_target_global_int_get_afx(msg); + set_position_target_global_int->afy = mavlink_msg_set_position_target_global_int_get_afy(msg); + set_position_target_global_int->afz = mavlink_msg_set_position_target_global_int_get_afz(msg); + set_position_target_global_int->yaw = mavlink_msg_set_position_target_global_int_get_yaw(msg); + set_position_target_global_int->yaw_rate = mavlink_msg_set_position_target_global_int_get_yaw_rate(msg); + set_position_target_global_int->type_mask = mavlink_msg_set_position_target_global_int_get_type_mask(msg); + set_position_target_global_int->target_system = mavlink_msg_set_position_target_global_int_get_target_system(msg); + set_position_target_global_int->target_component = mavlink_msg_set_position_target_global_int_get_target_component(msg); + set_position_target_global_int->coordinate_frame = mavlink_msg_set_position_target_global_int_get_coordinate_frame(msg); +#else + memcpy(set_position_target_global_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_position_target_local_ned.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_position_target_local_ned.h new file mode 100644 index 0000000..3a8b635 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_set_position_target_local_ned.h @@ -0,0 +1,569 @@ +// MESSAGE SET_POSITION_TARGET_LOCAL_NED PACKING + +#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED 84 + +typedef struct __mavlink_set_position_target_local_ned_t +{ + uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ + float x; /*< X Position in NED frame in meters*/ + float y; /*< Y Position in NED frame in meters*/ + float z; /*< Z Position in NED frame in meters (note, altitude is negative in NED)*/ + float vx; /*< X velocity in NED frame in meter / s*/ + float vy; /*< Y velocity in NED frame in meter / s*/ + float vz; /*< Z velocity in NED frame in meter / s*/ + float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float yaw; /*< yaw setpoint in rad*/ + float yaw_rate; /*< yaw rate setpoint in rad/s*/ + uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/ +} mavlink_set_position_target_local_ned_t; + +#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN 53 +#define MAVLINK_MSG_ID_84_LEN 53 + +#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC 143 +#define MAVLINK_MSG_ID_84_CRC 143 + + + +#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED { \ + "SET_POSITION_TARGET_LOCAL_NED", \ + 16, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_local_ned_t, time_boot_ms) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_target_local_ned_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_target_local_ned_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_local_ned_t, z) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_local_ned_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_local_ned_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_local_ned_t, vz) }, \ + { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_local_ned_t, afx) }, \ + { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_local_ned_t, afy) }, \ + { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_local_ned_t, afz) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, yaw) }, \ + { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, yaw_rate) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a set_position_target_local_ned message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param x X Position in NED frame in meters + * @param y Y Position in NED frame in meters + * @param z Z Position in NED frame in meters (note, altitude is negative in NED) + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#else + mavlink_set_position_target_local_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif +} + +/** + * @brief Pack a set_position_target_local_ned message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param x X Position in NED frame in meters + * @param y Y Position in NED frame in meters + * @param z Z Position in NED frame in meters (note, altitude is negative in NED) + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#else + mavlink_set_position_target_local_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif +} + +/** + * @brief Encode a set_position_target_local_ned struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_position_target_local_ned C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned) +{ + return mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate); +} + +/** + * @brief Encode a set_position_target_local_ned struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param set_position_target_local_ned C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned) +{ + return mavlink_msg_set_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate); +} + +/** + * @brief Send a set_position_target_local_ned message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param x X Position in NED frame in meters + * @param y Y Position in NED frame in meters + * @param z Z Position in NED frame in meters (note, altitude is negative in NED) + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#else + mavlink_set_position_target_local_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_set_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#else + mavlink_set_position_target_local_ned_t *packet = (mavlink_set_position_target_local_ned_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->x = x; + packet->y = y; + packet->z = z; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->afx = afx; + packet->afy = afy; + packet->afz = afz; + packet->yaw = yaw; + packet->yaw_rate = yaw_rate; + packet->type_mask = type_mask; + packet->target_system = target_system; + packet->target_component = target_component; + packet->coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SET_POSITION_TARGET_LOCAL_NED UNPACKING + + +/** + * @brief Get field time_boot_ms from set_position_target_local_ned message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_set_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field target_system from set_position_target_local_ned message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 50); +} + +/** + * @brief Get field target_component from set_position_target_local_ned message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 51); +} + +/** + * @brief Get field coordinate_frame from set_position_target_local_ned message + * + * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + */ +static inline uint8_t mavlink_msg_set_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 52); +} + +/** + * @brief Get field type_mask from set_position_target_local_ned message + * + * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + */ +static inline uint16_t mavlink_msg_set_position_target_local_ned_get_type_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 48); +} + +/** + * @brief Get field x from set_position_target_local_ned message + * + * @return X Position in NED frame in meters + */ +static inline float mavlink_msg_set_position_target_local_ned_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field y from set_position_target_local_ned message + * + * @return Y Position in NED frame in meters + */ +static inline float mavlink_msg_set_position_target_local_ned_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field z from set_position_target_local_ned message + * + * @return Z Position in NED frame in meters (note, altitude is negative in NED) + */ +static inline float mavlink_msg_set_position_target_local_ned_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vx from set_position_target_local_ned message + * + * @return X velocity in NED frame in meter / s + */ +static inline float mavlink_msg_set_position_target_local_ned_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vy from set_position_target_local_ned message + * + * @return Y velocity in NED frame in meter / s + */ +static inline float mavlink_msg_set_position_target_local_ned_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vz from set_position_target_local_ned message + * + * @return Z velocity in NED frame in meter / s + */ +static inline float mavlink_msg_set_position_target_local_ned_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field afx from set_position_target_local_ned message + * + * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_set_position_target_local_ned_get_afx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field afy from set_position_target_local_ned message + * + * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_set_position_target_local_ned_get_afy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field afz from set_position_target_local_ned message + * + * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_set_position_target_local_ned_get_afz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field yaw from set_position_target_local_ned message + * + * @return yaw setpoint in rad + */ +static inline float mavlink_msg_set_position_target_local_ned_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field yaw_rate from set_position_target_local_ned message + * + * @return yaw rate setpoint in rad/s + */ +static inline float mavlink_msg_set_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Decode a set_position_target_local_ned message into a struct + * + * @param msg The message to decode + * @param set_position_target_local_ned C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_set_position_target_local_ned_t* set_position_target_local_ned) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_position_target_local_ned->time_boot_ms = mavlink_msg_set_position_target_local_ned_get_time_boot_ms(msg); + set_position_target_local_ned->x = mavlink_msg_set_position_target_local_ned_get_x(msg); + set_position_target_local_ned->y = mavlink_msg_set_position_target_local_ned_get_y(msg); + set_position_target_local_ned->z = mavlink_msg_set_position_target_local_ned_get_z(msg); + set_position_target_local_ned->vx = mavlink_msg_set_position_target_local_ned_get_vx(msg); + set_position_target_local_ned->vy = mavlink_msg_set_position_target_local_ned_get_vy(msg); + set_position_target_local_ned->vz = mavlink_msg_set_position_target_local_ned_get_vz(msg); + set_position_target_local_ned->afx = mavlink_msg_set_position_target_local_ned_get_afx(msg); + set_position_target_local_ned->afy = mavlink_msg_set_position_target_local_ned_get_afy(msg); + set_position_target_local_ned->afz = mavlink_msg_set_position_target_local_ned_get_afz(msg); + set_position_target_local_ned->yaw = mavlink_msg_set_position_target_local_ned_get_yaw(msg); + set_position_target_local_ned->yaw_rate = mavlink_msg_set_position_target_local_ned_get_yaw_rate(msg); + set_position_target_local_ned->type_mask = mavlink_msg_set_position_target_local_ned_get_type_mask(msg); + set_position_target_local_ned->target_system = mavlink_msg_set_position_target_local_ned_get_target_system(msg); + set_position_target_local_ned->target_component = mavlink_msg_set_position_target_local_ned_get_target_component(msg); + set_position_target_local_ned->coordinate_frame = mavlink_msg_set_position_target_local_ned_get_coordinate_frame(msg); +#else + memcpy(set_position_target_local_ned, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_sim_state.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_sim_state.h new file mode 100644 index 0000000..ad6934d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_sim_state.h @@ -0,0 +1,689 @@ +// MESSAGE SIM_STATE PACKING + +#define MAVLINK_MSG_ID_SIM_STATE 108 + +typedef struct __mavlink_sim_state_t +{ + float q1; /*< True attitude quaternion component 1, w (1 in null-rotation)*/ + float q2; /*< True attitude quaternion component 2, x (0 in null-rotation)*/ + float q3; /*< True attitude quaternion component 3, y (0 in null-rotation)*/ + float q4; /*< True attitude quaternion component 4, z (0 in null-rotation)*/ + float roll; /*< Attitude roll expressed as Euler angles, not recommended except for human-readable outputs*/ + float pitch; /*< Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs*/ + float yaw; /*< Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs*/ + float xacc; /*< X acceleration m/s/s*/ + float yacc; /*< Y acceleration m/s/s*/ + float zacc; /*< Z acceleration m/s/s*/ + float xgyro; /*< Angular speed around X axis rad/s*/ + float ygyro; /*< Angular speed around Y axis rad/s*/ + float zgyro; /*< Angular speed around Z axis rad/s*/ + float lat; /*< Latitude in degrees*/ + float lon; /*< Longitude in degrees*/ + float alt; /*< Altitude in meters*/ + float std_dev_horz; /*< Horizontal position standard deviation*/ + float std_dev_vert; /*< Vertical position standard deviation*/ + float vn; /*< True velocity in m/s in NORTH direction in earth-fixed NED frame*/ + float ve; /*< True velocity in m/s in EAST direction in earth-fixed NED frame*/ + float vd; /*< True velocity in m/s in DOWN direction in earth-fixed NED frame*/ +} mavlink_sim_state_t; + +#define MAVLINK_MSG_ID_SIM_STATE_LEN 84 +#define MAVLINK_MSG_ID_108_LEN 84 + +#define MAVLINK_MSG_ID_SIM_STATE_CRC 32 +#define MAVLINK_MSG_ID_108_CRC 32 + + + +#define MAVLINK_MESSAGE_INFO_SIM_STATE { \ + "SIM_STATE", \ + 21, \ + { { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sim_state_t, q1) }, \ + { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sim_state_t, q2) }, \ + { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sim_state_t, q3) }, \ + { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sim_state_t, q4) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sim_state_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sim_state_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sim_state_t, yaw) }, \ + { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sim_state_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sim_state_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sim_state_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sim_state_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sim_state_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sim_state_t, zgyro) }, \ + { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sim_state_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sim_state_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sim_state_t, alt) }, \ + { "std_dev_horz", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sim_state_t, std_dev_horz) }, \ + { "std_dev_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sim_state_t, std_dev_vert) }, \ + { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sim_state_t, vn) }, \ + { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sim_state_t, ve) }, \ + { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sim_state_t, vd) }, \ + } \ +} + + +/** + * @brief Pack a sim_state message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param q1 True attitude quaternion component 1, w (1 in null-rotation) + * @param q2 True attitude quaternion component 2, x (0 in null-rotation) + * @param q3 True attitude quaternion component 3, y (0 in null-rotation) + * @param q4 True attitude quaternion component 4, z (0 in null-rotation) + * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + * @param xacc X acceleration m/s/s + * @param yacc Y acceleration m/s/s + * @param zacc Z acceleration m/s/s + * @param xgyro Angular speed around X axis rad/s + * @param ygyro Angular speed around Y axis rad/s + * @param zgyro Angular speed around Z axis rad/s + * @param lat Latitude in degrees + * @param lon Longitude in degrees + * @param alt Altitude in meters + * @param std_dev_horz Horizontal position standard deviation + * @param std_dev_vert Vertical position standard deviation + * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame + * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame + * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sim_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; + _mav_put_float(buf, 0, q1); + _mav_put_float(buf, 4, q2); + _mav_put_float(buf, 8, q3); + _mav_put_float(buf, 12, q4); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + _mav_put_float(buf, 28, xacc); + _mav_put_float(buf, 32, yacc); + _mav_put_float(buf, 36, zacc); + _mav_put_float(buf, 40, xgyro); + _mav_put_float(buf, 44, ygyro); + _mav_put_float(buf, 48, zgyro); + _mav_put_float(buf, 52, lat); + _mav_put_float(buf, 56, lon); + _mav_put_float(buf, 60, alt); + _mav_put_float(buf, 64, std_dev_horz); + _mav_put_float(buf, 68, std_dev_vert); + _mav_put_float(buf, 72, vn); + _mav_put_float(buf, 76, ve); + _mav_put_float(buf, 80, vd); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN); +#else + mavlink_sim_state_t packet; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.std_dev_horz = std_dev_horz; + packet.std_dev_vert = std_dev_vert; + packet.vn = vn; + packet.ve = ve; + packet.vd = vd; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SIM_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +} + +/** + * @brief Pack a sim_state message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param q1 True attitude quaternion component 1, w (1 in null-rotation) + * @param q2 True attitude quaternion component 2, x (0 in null-rotation) + * @param q3 True attitude quaternion component 3, y (0 in null-rotation) + * @param q4 True attitude quaternion component 4, z (0 in null-rotation) + * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + * @param xacc X acceleration m/s/s + * @param yacc Y acceleration m/s/s + * @param zacc Z acceleration m/s/s + * @param xgyro Angular speed around X axis rad/s + * @param ygyro Angular speed around Y axis rad/s + * @param zgyro Angular speed around Z axis rad/s + * @param lat Latitude in degrees + * @param lon Longitude in degrees + * @param alt Altitude in meters + * @param std_dev_horz Horizontal position standard deviation + * @param std_dev_vert Vertical position standard deviation + * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame + * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame + * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sim_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float q1,float q2,float q3,float q4,float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lon,float alt,float std_dev_horz,float std_dev_vert,float vn,float ve,float vd) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; + _mav_put_float(buf, 0, q1); + _mav_put_float(buf, 4, q2); + _mav_put_float(buf, 8, q3); + _mav_put_float(buf, 12, q4); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + _mav_put_float(buf, 28, xacc); + _mav_put_float(buf, 32, yacc); + _mav_put_float(buf, 36, zacc); + _mav_put_float(buf, 40, xgyro); + _mav_put_float(buf, 44, ygyro); + _mav_put_float(buf, 48, zgyro); + _mav_put_float(buf, 52, lat); + _mav_put_float(buf, 56, lon); + _mav_put_float(buf, 60, alt); + _mav_put_float(buf, 64, std_dev_horz); + _mav_put_float(buf, 68, std_dev_vert); + _mav_put_float(buf, 72, vn); + _mav_put_float(buf, 76, ve); + _mav_put_float(buf, 80, vd); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN); +#else + mavlink_sim_state_t packet; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.std_dev_horz = std_dev_horz; + packet.std_dev_vert = std_dev_vert; + packet.vn = vn; + packet.ve = ve; + packet.vd = vd; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SIM_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +} + +/** + * @brief Encode a sim_state struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param sim_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sim_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state) +{ + return mavlink_msg_sim_state_pack(system_id, component_id, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd); +} + +/** + * @brief Encode a sim_state struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param sim_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sim_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state) +{ + return mavlink_msg_sim_state_pack_chan(system_id, component_id, chan, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd); +} + +/** + * @brief Send a sim_state message + * @param chan MAVLink channel to send the message + * + * @param q1 True attitude quaternion component 1, w (1 in null-rotation) + * @param q2 True attitude quaternion component 2, x (0 in null-rotation) + * @param q3 True attitude quaternion component 3, y (0 in null-rotation) + * @param q4 True attitude quaternion component 4, z (0 in null-rotation) + * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + * @param xacc X acceleration m/s/s + * @param yacc Y acceleration m/s/s + * @param zacc Z acceleration m/s/s + * @param xgyro Angular speed around X axis rad/s + * @param ygyro Angular speed around Y axis rad/s + * @param zgyro Angular speed around Z axis rad/s + * @param lat Latitude in degrees + * @param lon Longitude in degrees + * @param alt Altitude in meters + * @param std_dev_horz Horizontal position standard deviation + * @param std_dev_vert Vertical position standard deviation + * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame + * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame + * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_sim_state_send(mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; + _mav_put_float(buf, 0, q1); + _mav_put_float(buf, 4, q2); + _mav_put_float(buf, 8, q3); + _mav_put_float(buf, 12, q4); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + _mav_put_float(buf, 28, xacc); + _mav_put_float(buf, 32, yacc); + _mav_put_float(buf, 36, zacc); + _mav_put_float(buf, 40, xgyro); + _mav_put_float(buf, 44, ygyro); + _mav_put_float(buf, 48, zgyro); + _mav_put_float(buf, 52, lat); + _mav_put_float(buf, 56, lon); + _mav_put_float(buf, 60, alt); + _mav_put_float(buf, 64, std_dev_horz); + _mav_put_float(buf, 68, std_dev_vert); + _mav_put_float(buf, 72, vn); + _mav_put_float(buf, 76, ve); + _mav_put_float(buf, 80, vd); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +#else + mavlink_sim_state_t packet; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.std_dev_horz = std_dev_horz; + packet.std_dev_vert = std_dev_vert; + packet.vn = vn; + packet.ve = ve; + packet.vd = vd; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SIM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_sim_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, q1); + _mav_put_float(buf, 4, q2); + _mav_put_float(buf, 8, q3); + _mav_put_float(buf, 12, q4); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + _mav_put_float(buf, 28, xacc); + _mav_put_float(buf, 32, yacc); + _mav_put_float(buf, 36, zacc); + _mav_put_float(buf, 40, xgyro); + _mav_put_float(buf, 44, ygyro); + _mav_put_float(buf, 48, zgyro); + _mav_put_float(buf, 52, lat); + _mav_put_float(buf, 56, lon); + _mav_put_float(buf, 60, alt); + _mav_put_float(buf, 64, std_dev_horz); + _mav_put_float(buf, 68, std_dev_vert); + _mav_put_float(buf, 72, vn); + _mav_put_float(buf, 76, ve); + _mav_put_float(buf, 80, vd); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +#else + mavlink_sim_state_t *packet = (mavlink_sim_state_t *)msgbuf; + packet->q1 = q1; + packet->q2 = q2; + packet->q3 = q3; + packet->q4 = q4; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->std_dev_horz = std_dev_horz; + packet->std_dev_vert = std_dev_vert; + packet->vn = vn; + packet->ve = ve; + packet->vd = vd; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SIM_STATE UNPACKING + + +/** + * @brief Get field q1 from sim_state message + * + * @return True attitude quaternion component 1, w (1 in null-rotation) + */ +static inline float mavlink_msg_sim_state_get_q1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field q2 from sim_state message + * + * @return True attitude quaternion component 2, x (0 in null-rotation) + */ +static inline float mavlink_msg_sim_state_get_q2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field q3 from sim_state message + * + * @return True attitude quaternion component 3, y (0 in null-rotation) + */ +static inline float mavlink_msg_sim_state_get_q3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field q4 from sim_state message + * + * @return True attitude quaternion component 4, z (0 in null-rotation) + */ +static inline float mavlink_msg_sim_state_get_q4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field roll from sim_state message + * + * @return Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + */ +static inline float mavlink_msg_sim_state_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field pitch from sim_state message + * + * @return Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + */ +static inline float mavlink_msg_sim_state_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field yaw from sim_state message + * + * @return Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + */ +static inline float mavlink_msg_sim_state_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field xacc from sim_state message + * + * @return X acceleration m/s/s + */ +static inline float mavlink_msg_sim_state_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field yacc from sim_state message + * + * @return Y acceleration m/s/s + */ +static inline float mavlink_msg_sim_state_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field zacc from sim_state message + * + * @return Z acceleration m/s/s + */ +static inline float mavlink_msg_sim_state_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field xgyro from sim_state message + * + * @return Angular speed around X axis rad/s + */ +static inline float mavlink_msg_sim_state_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field ygyro from sim_state message + * + * @return Angular speed around Y axis rad/s + */ +static inline float mavlink_msg_sim_state_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field zgyro from sim_state message + * + * @return Angular speed around Z axis rad/s + */ +static inline float mavlink_msg_sim_state_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 48); +} + +/** + * @brief Get field lat from sim_state message + * + * @return Latitude in degrees + */ +static inline float mavlink_msg_sim_state_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 52); +} + +/** + * @brief Get field lon from sim_state message + * + * @return Longitude in degrees + */ +static inline float mavlink_msg_sim_state_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 56); +} + +/** + * @brief Get field alt from sim_state message + * + * @return Altitude in meters + */ +static inline float mavlink_msg_sim_state_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 60); +} + +/** + * @brief Get field std_dev_horz from sim_state message + * + * @return Horizontal position standard deviation + */ +static inline float mavlink_msg_sim_state_get_std_dev_horz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 64); +} + +/** + * @brief Get field std_dev_vert from sim_state message + * + * @return Vertical position standard deviation + */ +static inline float mavlink_msg_sim_state_get_std_dev_vert(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 68); +} + +/** + * @brief Get field vn from sim_state message + * + * @return True velocity in m/s in NORTH direction in earth-fixed NED frame + */ +static inline float mavlink_msg_sim_state_get_vn(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 72); +} + +/** + * @brief Get field ve from sim_state message + * + * @return True velocity in m/s in EAST direction in earth-fixed NED frame + */ +static inline float mavlink_msg_sim_state_get_ve(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 76); +} + +/** + * @brief Get field vd from sim_state message + * + * @return True velocity in m/s in DOWN direction in earth-fixed NED frame + */ +static inline float mavlink_msg_sim_state_get_vd(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 80); +} + +/** + * @brief Decode a sim_state message into a struct + * + * @param msg The message to decode + * @param sim_state C-struct to decode the message contents into + */ +static inline void mavlink_msg_sim_state_decode(const mavlink_message_t* msg, mavlink_sim_state_t* sim_state) +{ +#if MAVLINK_NEED_BYTE_SWAP + sim_state->q1 = mavlink_msg_sim_state_get_q1(msg); + sim_state->q2 = mavlink_msg_sim_state_get_q2(msg); + sim_state->q3 = mavlink_msg_sim_state_get_q3(msg); + sim_state->q4 = mavlink_msg_sim_state_get_q4(msg); + sim_state->roll = mavlink_msg_sim_state_get_roll(msg); + sim_state->pitch = mavlink_msg_sim_state_get_pitch(msg); + sim_state->yaw = mavlink_msg_sim_state_get_yaw(msg); + sim_state->xacc = mavlink_msg_sim_state_get_xacc(msg); + sim_state->yacc = mavlink_msg_sim_state_get_yacc(msg); + sim_state->zacc = mavlink_msg_sim_state_get_zacc(msg); + sim_state->xgyro = mavlink_msg_sim_state_get_xgyro(msg); + sim_state->ygyro = mavlink_msg_sim_state_get_ygyro(msg); + sim_state->zgyro = mavlink_msg_sim_state_get_zgyro(msg); + sim_state->lat = mavlink_msg_sim_state_get_lat(msg); + sim_state->lon = mavlink_msg_sim_state_get_lon(msg); + sim_state->alt = mavlink_msg_sim_state_get_alt(msg); + sim_state->std_dev_horz = mavlink_msg_sim_state_get_std_dev_horz(msg); + sim_state->std_dev_vert = mavlink_msg_sim_state_get_std_dev_vert(msg); + sim_state->vn = mavlink_msg_sim_state_get_vn(msg); + sim_state->ve = mavlink_msg_sim_state_get_ve(msg); + sim_state->vd = mavlink_msg_sim_state_get_vd(msg); +#else + memcpy(sim_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_statustext.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_statustext.h new file mode 100644 index 0000000..9dcbff8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_statustext.h @@ -0,0 +1,225 @@ +// MESSAGE STATUSTEXT PACKING + +#define MAVLINK_MSG_ID_STATUSTEXT 253 + +typedef struct __mavlink_statustext_t +{ + uint8_t severity; /*< Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.*/ + char text[50]; /*< Status text message, without null termination character*/ +} mavlink_statustext_t; + +#define MAVLINK_MSG_ID_STATUSTEXT_LEN 51 +#define MAVLINK_MSG_ID_253_LEN 51 + +#define MAVLINK_MSG_ID_STATUSTEXT_CRC 83 +#define MAVLINK_MSG_ID_253_CRC 83 + +#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50 + +#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \ + "STATUSTEXT", \ + 2, \ + { { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \ + { "text", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_statustext_t, text) }, \ + } \ +} + + +/** + * @brief Pack a statustext message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + * @param text Status text message, without null termination character + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t severity, const char *text) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN]; + _mav_put_uint8_t(buf, 0, severity); + _mav_put_char_array(buf, 1, text, 50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#else + mavlink_statustext_t packet; + packet.severity = severity; + mav_array_memcpy(packet.text, text, sizeof(char)*50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif +} + +/** + * @brief Pack a statustext message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + * @param text Status text message, without null termination character + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t severity,const char *text) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN]; + _mav_put_uint8_t(buf, 0, severity); + _mav_put_char_array(buf, 1, text, 50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#else + mavlink_statustext_t packet; + packet.severity = severity; + mav_array_memcpy(packet.text, text, sizeof(char)*50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif +} + +/** + * @brief Encode a statustext struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param statustext C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_statustext_t* statustext) +{ + return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text); +} + +/** + * @brief Encode a statustext struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param statustext C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_statustext_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_statustext_t* statustext) +{ + return mavlink_msg_statustext_pack_chan(system_id, component_id, chan, msg, statustext->severity, statustext->text); +} + +/** + * @brief Send a statustext message + * @param chan MAVLink channel to send the message + * + * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + * @param text Status text message, without null termination character + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const char *text) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN]; + _mav_put_uint8_t(buf, 0, severity); + _mav_put_char_array(buf, 1, text, 50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif +#else + mavlink_statustext_t packet; + packet.severity = severity; + mav_array_memcpy(packet.text, text, sizeof(char)*50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_STATUSTEXT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_statustext_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t severity, const char *text) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, severity); + _mav_put_char_array(buf, 1, text, 50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif +#else + mavlink_statustext_t *packet = (mavlink_statustext_t *)msgbuf; + packet->severity = severity; + mav_array_memcpy(packet->text, text, sizeof(char)*50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)packet, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE STATUSTEXT UNPACKING + + +/** + * @brief Get field severity from statustext message + * + * @return Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + */ +static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field text from statustext message + * + * @return Status text message, without null termination character + */ +static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, char *text) +{ + return _MAV_RETURN_char_array(msg, text, 50, 1); +} + +/** + * @brief Decode a statustext message into a struct + * + * @param msg The message to decode + * @param statustext C-struct to decode the message contents into + */ +static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext) +{ +#if MAVLINK_NEED_BYTE_SWAP + statustext->severity = mavlink_msg_statustext_get_severity(msg); + mavlink_msg_statustext_get_text(msg, statustext->text); +#else + memcpy(statustext, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_sys_status.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_sys_status.h new file mode 100644 index 0000000..e4e4099 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_sys_status.h @@ -0,0 +1,497 @@ +// MESSAGE SYS_STATUS PACKING + +#define MAVLINK_MSG_ID_SYS_STATUS 1 + +typedef struct __mavlink_sys_status_t +{ + uint32_t onboard_control_sensors_present; /*< Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/ + uint32_t onboard_control_sensors_enabled; /*< Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/ + uint32_t onboard_control_sensors_health; /*< Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/ + uint16_t load; /*< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000*/ + uint16_t voltage_battery; /*< Battery voltage, in millivolts (1 = 1 millivolt)*/ + int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current*/ + uint16_t drop_rate_comm; /*< Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/ + uint16_t errors_comm; /*< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/ + uint16_t errors_count1; /*< Autopilot-specific errors*/ + uint16_t errors_count2; /*< Autopilot-specific errors*/ + uint16_t errors_count3; /*< Autopilot-specific errors*/ + uint16_t errors_count4; /*< Autopilot-specific errors*/ + int8_t battery_remaining; /*< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery*/ +} mavlink_sys_status_t; + +#define MAVLINK_MSG_ID_SYS_STATUS_LEN 31 +#define MAVLINK_MSG_ID_1_LEN 31 + +#define MAVLINK_MSG_ID_SYS_STATUS_CRC 124 +#define MAVLINK_MSG_ID_1_CRC 124 + + + +#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \ + "SYS_STATUS", \ + 13, \ + { { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \ + { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \ + { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \ + { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \ + { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \ + { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \ + { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \ + { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \ + { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \ + { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \ + { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \ + { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \ + { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \ + } \ +} + + +/** + * @brief Pack a sys_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_count1 Autopilot-specific errors + * @param errors_count2 Autopilot-specific errors + * @param errors_count3 Autopilot-specific errors + * @param errors_count4 Autopilot-specific errors + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN]; + _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); + _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); + _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); + _mav_put_uint16_t(buf, 12, load); + _mav_put_uint16_t(buf, 14, voltage_battery); + _mav_put_int16_t(buf, 16, current_battery); + _mav_put_uint16_t(buf, 18, drop_rate_comm); + _mav_put_uint16_t(buf, 20, errors_comm); + _mav_put_uint16_t(buf, 22, errors_count1); + _mav_put_uint16_t(buf, 24, errors_count2); + _mav_put_uint16_t(buf, 26, errors_count3); + _mav_put_uint16_t(buf, 28, errors_count4); + _mav_put_int8_t(buf, 30, battery_remaining); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#else + mavlink_sys_status_t packet; + packet.onboard_control_sensors_present = onboard_control_sensors_present; + packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; + packet.onboard_control_sensors_health = onboard_control_sensors_health; + packet.load = load; + packet.voltage_battery = voltage_battery; + packet.current_battery = current_battery; + packet.drop_rate_comm = drop_rate_comm; + packet.errors_comm = errors_comm; + packet.errors_count1 = errors_count1; + packet.errors_count2 = errors_count2; + packet.errors_count3 = errors_count3; + packet.errors_count4 = errors_count4; + packet.battery_remaining = battery_remaining; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif +} + +/** + * @brief Pack a sys_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_count1 Autopilot-specific errors + * @param errors_count2 Autopilot-specific errors + * @param errors_count3 Autopilot-specific errors + * @param errors_count4 Autopilot-specific errors + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t onboard_control_sensors_present,uint32_t onboard_control_sensors_enabled,uint32_t onboard_control_sensors_health,uint16_t load,uint16_t voltage_battery,int16_t current_battery,int8_t battery_remaining,uint16_t drop_rate_comm,uint16_t errors_comm,uint16_t errors_count1,uint16_t errors_count2,uint16_t errors_count3,uint16_t errors_count4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN]; + _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); + _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); + _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); + _mav_put_uint16_t(buf, 12, load); + _mav_put_uint16_t(buf, 14, voltage_battery); + _mav_put_int16_t(buf, 16, current_battery); + _mav_put_uint16_t(buf, 18, drop_rate_comm); + _mav_put_uint16_t(buf, 20, errors_comm); + _mav_put_uint16_t(buf, 22, errors_count1); + _mav_put_uint16_t(buf, 24, errors_count2); + _mav_put_uint16_t(buf, 26, errors_count3); + _mav_put_uint16_t(buf, 28, errors_count4); + _mav_put_int8_t(buf, 30, battery_remaining); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#else + mavlink_sys_status_t packet; + packet.onboard_control_sensors_present = onboard_control_sensors_present; + packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; + packet.onboard_control_sensors_health = onboard_control_sensors_health; + packet.load = load; + packet.voltage_battery = voltage_battery; + packet.current_battery = current_battery; + packet.drop_rate_comm = drop_rate_comm; + packet.errors_comm = errors_comm; + packet.errors_count1 = errors_count1; + packet.errors_count2 = errors_count2; + packet.errors_count3 = errors_count3; + packet.errors_count4 = errors_count4; + packet.battery_remaining = battery_remaining; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif +} + +/** + * @brief Encode a sys_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param sys_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) +{ + return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4); +} + +/** + * @brief Encode a sys_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param sys_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sys_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) +{ + return mavlink_msg_sys_status_pack_chan(system_id, component_id, chan, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4); +} + +/** + * @brief Send a sys_status message + * @param chan MAVLink channel to send the message + * + * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_count1 Autopilot-specific errors + * @param errors_count2 Autopilot-specific errors + * @param errors_count3 Autopilot-specific errors + * @param errors_count4 Autopilot-specific errors + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN]; + _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); + _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); + _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); + _mav_put_uint16_t(buf, 12, load); + _mav_put_uint16_t(buf, 14, voltage_battery); + _mav_put_int16_t(buf, 16, current_battery); + _mav_put_uint16_t(buf, 18, drop_rate_comm); + _mav_put_uint16_t(buf, 20, errors_comm); + _mav_put_uint16_t(buf, 22, errors_count1); + _mav_put_uint16_t(buf, 24, errors_count2); + _mav_put_uint16_t(buf, 26, errors_count3); + _mav_put_uint16_t(buf, 28, errors_count4); + _mav_put_int8_t(buf, 30, battery_remaining); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif +#else + mavlink_sys_status_t packet; + packet.onboard_control_sensors_present = onboard_control_sensors_present; + packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; + packet.onboard_control_sensors_health = onboard_control_sensors_health; + packet.load = load; + packet.voltage_battery = voltage_battery; + packet.current_battery = current_battery; + packet.drop_rate_comm = drop_rate_comm; + packet.errors_comm = errors_comm; + packet.errors_count1 = errors_count1; + packet.errors_count2 = errors_count2; + packet.errors_count3 = errors_count3; + packet.errors_count4 = errors_count4; + packet.battery_remaining = battery_remaining; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SYS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_sys_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); + _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); + _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); + _mav_put_uint16_t(buf, 12, load); + _mav_put_uint16_t(buf, 14, voltage_battery); + _mav_put_int16_t(buf, 16, current_battery); + _mav_put_uint16_t(buf, 18, drop_rate_comm); + _mav_put_uint16_t(buf, 20, errors_comm); + _mav_put_uint16_t(buf, 22, errors_count1); + _mav_put_uint16_t(buf, 24, errors_count2); + _mav_put_uint16_t(buf, 26, errors_count3); + _mav_put_uint16_t(buf, 28, errors_count4); + _mav_put_int8_t(buf, 30, battery_remaining); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif +#else + mavlink_sys_status_t *packet = (mavlink_sys_status_t *)msgbuf; + packet->onboard_control_sensors_present = onboard_control_sensors_present; + packet->onboard_control_sensors_enabled = onboard_control_sensors_enabled; + packet->onboard_control_sensors_health = onboard_control_sensors_health; + packet->load = load; + packet->voltage_battery = voltage_battery; + packet->current_battery = current_battery; + packet->drop_rate_comm = drop_rate_comm; + packet->errors_comm = errors_comm; + packet->errors_count1 = errors_count1; + packet->errors_count2 = errors_count2; + packet->errors_count3 = errors_count3; + packet->errors_count4 = errors_count4; + packet->battery_remaining = battery_remaining; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)packet, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SYS_STATUS UNPACKING + + +/** + * @brief Get field onboard_control_sensors_present from sys_status message + * + * @return Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + */ +static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field onboard_control_sensors_enabled from sys_status message + * + * @return Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + */ +static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Get field onboard_control_sensors_health from sys_status message + * + * @return Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + */ +static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field load from sys_status message + * + * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + */ +static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field voltage_battery from sys_status message + * + * @return Battery voltage, in millivolts (1 = 1 millivolt) + */ +static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field current_battery from sys_status message + * + * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + */ +static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field battery_remaining from sys_status message + * + * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + */ +static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 30); +} + +/** + * @brief Get field drop_rate_comm from sys_status message + * + * @return Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + */ +static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field errors_comm from sys_status message + * + * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field errors_count1 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field errors_count2 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field errors_count3 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field errors_count4 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Decode a sys_status message into a struct + * + * @param msg The message to decode + * @param sys_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + sys_status->onboard_control_sensors_present = mavlink_msg_sys_status_get_onboard_control_sensors_present(msg); + sys_status->onboard_control_sensors_enabled = mavlink_msg_sys_status_get_onboard_control_sensors_enabled(msg); + sys_status->onboard_control_sensors_health = mavlink_msg_sys_status_get_onboard_control_sensors_health(msg); + sys_status->load = mavlink_msg_sys_status_get_load(msg); + sys_status->voltage_battery = mavlink_msg_sys_status_get_voltage_battery(msg); + sys_status->current_battery = mavlink_msg_sys_status_get_current_battery(msg); + sys_status->drop_rate_comm = mavlink_msg_sys_status_get_drop_rate_comm(msg); + sys_status->errors_comm = mavlink_msg_sys_status_get_errors_comm(msg); + sys_status->errors_count1 = mavlink_msg_sys_status_get_errors_count1(msg); + sys_status->errors_count2 = mavlink_msg_sys_status_get_errors_count2(msg); + sys_status->errors_count3 = mavlink_msg_sys_status_get_errors_count3(msg); + sys_status->errors_count4 = mavlink_msg_sys_status_get_errors_count4(msg); + sys_status->battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg); +#else + memcpy(sys_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_system_time.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_system_time.h new file mode 100644 index 0000000..e2aab67 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_system_time.h @@ -0,0 +1,233 @@ +// MESSAGE SYSTEM_TIME PACKING + +#define MAVLINK_MSG_ID_SYSTEM_TIME 2 + +typedef struct __mavlink_system_time_t +{ + uint64_t time_unix_usec; /*< Timestamp of the master clock in microseconds since UNIX epoch.*/ + uint32_t time_boot_ms; /*< Timestamp of the component clock since boot time in milliseconds.*/ +} mavlink_system_time_t; + +#define MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12 +#define MAVLINK_MSG_ID_2_LEN 12 + +#define MAVLINK_MSG_ID_SYSTEM_TIME_CRC 137 +#define MAVLINK_MSG_ID_2_CRC 137 + + + +#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \ + "SYSTEM_TIME", \ + 2, \ + { { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \ + { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \ + } \ +} + + +/** + * @brief Pack a system_time message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. + * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_unix_usec, uint32_t time_boot_ms) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN]; + _mav_put_uint64_t(buf, 0, time_unix_usec); + _mav_put_uint32_t(buf, 8, time_boot_ms); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#else + mavlink_system_time_t packet; + packet.time_unix_usec = time_unix_usec; + packet.time_boot_ms = time_boot_ms; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif +} + +/** + * @brief Pack a system_time message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. + * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_unix_usec,uint32_t time_boot_ms) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN]; + _mav_put_uint64_t(buf, 0, time_unix_usec); + _mav_put_uint32_t(buf, 8, time_boot_ms); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#else + mavlink_system_time_t packet; + packet.time_unix_usec = time_unix_usec; + packet.time_boot_ms = time_boot_ms; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif +} + +/** + * @brief Encode a system_time struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param system_time C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_t* system_time) +{ + return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_unix_usec, system_time->time_boot_ms); +} + +/** + * @brief Encode a system_time struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param system_time C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_system_time_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_system_time_t* system_time) +{ + return mavlink_msg_system_time_pack_chan(system_id, component_id, chan, msg, system_time->time_unix_usec, system_time->time_boot_ms); +} + +/** + * @brief Send a system_time message + * @param chan MAVLink channel to send the message + * + * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. + * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN]; + _mav_put_uint64_t(buf, 0, time_unix_usec); + _mav_put_uint32_t(buf, 8, time_boot_ms); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif +#else + mavlink_system_time_t packet; + packet.time_unix_usec = time_unix_usec; + packet.time_boot_ms = time_boot_ms; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)&packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)&packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SYSTEM_TIME_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_system_time_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_unix_usec); + _mav_put_uint32_t(buf, 8, time_boot_ms); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif +#else + mavlink_system_time_t *packet = (mavlink_system_time_t *)msgbuf; + packet->time_unix_usec = time_unix_usec; + packet->time_boot_ms = time_boot_ms; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SYSTEM_TIME UNPACKING + + +/** + * @brief Get field time_unix_usec from system_time message + * + * @return Timestamp of the master clock in microseconds since UNIX epoch. + */ +static inline uint64_t mavlink_msg_system_time_get_time_unix_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field time_boot_ms from system_time message + * + * @return Timestamp of the component clock since boot time in milliseconds. + */ +static inline uint32_t mavlink_msg_system_time_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Decode a system_time message into a struct + * + * @param msg The message to decode + * @param system_time C-struct to decode the message contents into + */ +static inline void mavlink_msg_system_time_decode(const mavlink_message_t* msg, mavlink_system_time_t* system_time) +{ +#if MAVLINK_NEED_BYTE_SWAP + system_time->time_unix_usec = mavlink_msg_system_time_get_time_unix_usec(msg); + system_time->time_boot_ms = mavlink_msg_system_time_get_time_boot_ms(msg); +#else + memcpy(system_time, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_terrain_check.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_terrain_check.h new file mode 100644 index 0000000..d4ecaf3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_terrain_check.h @@ -0,0 +1,233 @@ +// MESSAGE TERRAIN_CHECK PACKING + +#define MAVLINK_MSG_ID_TERRAIN_CHECK 135 + +typedef struct __mavlink_terrain_check_t +{ + int32_t lat; /*< Latitude (degrees *10^7)*/ + int32_t lon; /*< Longitude (degrees *10^7)*/ +} mavlink_terrain_check_t; + +#define MAVLINK_MSG_ID_TERRAIN_CHECK_LEN 8 +#define MAVLINK_MSG_ID_135_LEN 8 + +#define MAVLINK_MSG_ID_TERRAIN_CHECK_CRC 203 +#define MAVLINK_MSG_ID_135_CRC 203 + + + +#define MAVLINK_MESSAGE_INFO_TERRAIN_CHECK { \ + "TERRAIN_CHECK", \ + 2, \ + { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_check_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_check_t, lon) }, \ + } \ +} + + +/** + * @brief Pack a terrain_check message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param lat Latitude (degrees *10^7) + * @param lon Longitude (degrees *10^7) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_check_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int32_t lat, int32_t lon) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#else + mavlink_terrain_check_t packet; + packet.lat = lat; + packet.lon = lon; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_CHECK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif +} + +/** + * @brief Pack a terrain_check message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param lat Latitude (degrees *10^7) + * @param lon Longitude (degrees *10^7) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_check_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int32_t lat,int32_t lon) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#else + mavlink_terrain_check_t packet; + packet.lat = lat; + packet.lon = lon; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_CHECK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif +} + +/** + * @brief Encode a terrain_check struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param terrain_check C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_check_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_check_t* terrain_check) +{ + return mavlink_msg_terrain_check_pack(system_id, component_id, msg, terrain_check->lat, terrain_check->lon); +} + +/** + * @brief Encode a terrain_check struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param terrain_check C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_check_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_check_t* terrain_check) +{ + return mavlink_msg_terrain_check_pack_chan(system_id, component_id, chan, msg, terrain_check->lat, terrain_check->lon); +} + +/** + * @brief Send a terrain_check message + * @param chan MAVLink channel to send the message + * + * @param lat Latitude (degrees *10^7) + * @param lon Longitude (degrees *10^7) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_terrain_check_send(mavlink_channel_t chan, int32_t lat, int32_t lon) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif +#else + mavlink_terrain_check_t packet; + packet.lat = lat; + packet.lon = lon; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_TERRAIN_CHECK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_terrain_check_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif +#else + mavlink_terrain_check_t *packet = (mavlink_terrain_check_t *)msgbuf; + packet->lat = lat; + packet->lon = lon; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE TERRAIN_CHECK UNPACKING + + +/** + * @brief Get field lat from terrain_check message + * + * @return Latitude (degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_check_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field lon from terrain_check message + * + * @return Longitude (degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_check_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Decode a terrain_check message into a struct + * + * @param msg The message to decode + * @param terrain_check C-struct to decode the message contents into + */ +static inline void mavlink_msg_terrain_check_decode(const mavlink_message_t* msg, mavlink_terrain_check_t* terrain_check) +{ +#if MAVLINK_NEED_BYTE_SWAP + terrain_check->lat = mavlink_msg_terrain_check_get_lat(msg); + terrain_check->lon = mavlink_msg_terrain_check_get_lon(msg); +#else + memcpy(terrain_check, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_terrain_data.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_terrain_data.h new file mode 100644 index 0000000..2e2f05a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_terrain_data.h @@ -0,0 +1,297 @@ +// MESSAGE TERRAIN_DATA PACKING + +#define MAVLINK_MSG_ID_TERRAIN_DATA 134 + +typedef struct __mavlink_terrain_data_t +{ + int32_t lat; /*< Latitude of SW corner of first grid (degrees *10^7)*/ + int32_t lon; /*< Longitude of SW corner of first grid (in degrees *10^7)*/ + uint16_t grid_spacing; /*< Grid spacing in meters*/ + int16_t data[16]; /*< Terrain data in meters AMSL*/ + uint8_t gridbit; /*< bit within the terrain request mask*/ +} mavlink_terrain_data_t; + +#define MAVLINK_MSG_ID_TERRAIN_DATA_LEN 43 +#define MAVLINK_MSG_ID_134_LEN 43 + +#define MAVLINK_MSG_ID_TERRAIN_DATA_CRC 229 +#define MAVLINK_MSG_ID_134_CRC 229 + +#define MAVLINK_MSG_TERRAIN_DATA_FIELD_DATA_LEN 16 + +#define MAVLINK_MESSAGE_INFO_TERRAIN_DATA { \ + "TERRAIN_DATA", \ + 5, \ + { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \ + { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \ + { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \ + { "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \ + } \ +} + + +/** + * @brief Pack a terrain_data message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param lat Latitude of SW corner of first grid (degrees *10^7) + * @param lon Longitude of SW corner of first grid (in degrees *10^7) + * @param grid_spacing Grid spacing in meters + * @param gridbit bit within the terrain request mask + * @param data Terrain data in meters AMSL + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_uint16_t(buf, 8, grid_spacing); + _mav_put_uint8_t(buf, 42, gridbit); + _mav_put_int16_t_array(buf, 10, data, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#else + mavlink_terrain_data_t packet; + packet.lat = lat; + packet.lon = lon; + packet.grid_spacing = grid_spacing; + packet.gridbit = gridbit; + mav_array_memcpy(packet.data, data, sizeof(int16_t)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif +} + +/** + * @brief Pack a terrain_data message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param lat Latitude of SW corner of first grid (degrees *10^7) + * @param lon Longitude of SW corner of first grid (in degrees *10^7) + * @param grid_spacing Grid spacing in meters + * @param gridbit bit within the terrain request mask + * @param data Terrain data in meters AMSL + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int32_t lat,int32_t lon,uint16_t grid_spacing,uint8_t gridbit,const int16_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_uint16_t(buf, 8, grid_spacing); + _mav_put_uint8_t(buf, 42, gridbit); + _mav_put_int16_t_array(buf, 10, data, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#else + mavlink_terrain_data_t packet; + packet.lat = lat; + packet.lon = lon; + packet.grid_spacing = grid_spacing; + packet.gridbit = gridbit; + mav_array_memcpy(packet.data, data, sizeof(int16_t)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif +} + +/** + * @brief Encode a terrain_data struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param terrain_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_data_t* terrain_data) +{ + return mavlink_msg_terrain_data_pack(system_id, component_id, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data); +} + +/** + * @brief Encode a terrain_data struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param terrain_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_data_t* terrain_data) +{ + return mavlink_msg_terrain_data_pack_chan(system_id, component_id, chan, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data); +} + +/** + * @brief Send a terrain_data message + * @param chan MAVLink channel to send the message + * + * @param lat Latitude of SW corner of first grid (degrees *10^7) + * @param lon Longitude of SW corner of first grid (in degrees *10^7) + * @param grid_spacing Grid spacing in meters + * @param gridbit bit within the terrain request mask + * @param data Terrain data in meters AMSL + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_terrain_data_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_uint16_t(buf, 8, grid_spacing); + _mav_put_uint8_t(buf, 42, gridbit); + _mav_put_int16_t_array(buf, 10, data, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif +#else + mavlink_terrain_data_t packet; + packet.lat = lat; + packet.lon = lon; + packet.grid_spacing = grid_spacing; + packet.gridbit = gridbit; + mav_array_memcpy(packet.data, data, sizeof(int16_t)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_TERRAIN_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_terrain_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_uint16_t(buf, 8, grid_spacing); + _mav_put_uint8_t(buf, 42, gridbit); + _mav_put_int16_t_array(buf, 10, data, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif +#else + mavlink_terrain_data_t *packet = (mavlink_terrain_data_t *)msgbuf; + packet->lat = lat; + packet->lon = lon; + packet->grid_spacing = grid_spacing; + packet->gridbit = gridbit; + mav_array_memcpy(packet->data, data, sizeof(int16_t)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE TERRAIN_DATA UNPACKING + + +/** + * @brief Get field lat from terrain_data message + * + * @return Latitude of SW corner of first grid (degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_data_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field lon from terrain_data message + * + * @return Longitude of SW corner of first grid (in degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_data_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field grid_spacing from terrain_data message + * + * @return Grid spacing in meters + */ +static inline uint16_t mavlink_msg_terrain_data_get_grid_spacing(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field gridbit from terrain_data message + * + * @return bit within the terrain request mask + */ +static inline uint8_t mavlink_msg_terrain_data_get_gridbit(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 42); +} + +/** + * @brief Get field data from terrain_data message + * + * @return Terrain data in meters AMSL + */ +static inline uint16_t mavlink_msg_terrain_data_get_data(const mavlink_message_t* msg, int16_t *data) +{ + return _MAV_RETURN_int16_t_array(msg, data, 16, 10); +} + +/** + * @brief Decode a terrain_data message into a struct + * + * @param msg The message to decode + * @param terrain_data C-struct to decode the message contents into + */ +static inline void mavlink_msg_terrain_data_decode(const mavlink_message_t* msg, mavlink_terrain_data_t* terrain_data) +{ +#if MAVLINK_NEED_BYTE_SWAP + terrain_data->lat = mavlink_msg_terrain_data_get_lat(msg); + terrain_data->lon = mavlink_msg_terrain_data_get_lon(msg); + terrain_data->grid_spacing = mavlink_msg_terrain_data_get_grid_spacing(msg); + mavlink_msg_terrain_data_get_data(msg, terrain_data->data); + terrain_data->gridbit = mavlink_msg_terrain_data_get_gridbit(msg); +#else + memcpy(terrain_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_terrain_report.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_terrain_report.h new file mode 100644 index 0000000..2ed7db6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_terrain_report.h @@ -0,0 +1,353 @@ +// MESSAGE TERRAIN_REPORT PACKING + +#define MAVLINK_MSG_ID_TERRAIN_REPORT 136 + +typedef struct __mavlink_terrain_report_t +{ + int32_t lat; /*< Latitude (degrees *10^7)*/ + int32_t lon; /*< Longitude (degrees *10^7)*/ + float terrain_height; /*< Terrain height in meters AMSL*/ + float current_height; /*< Current vehicle height above lat/lon terrain height (meters)*/ + uint16_t spacing; /*< grid spacing (zero if terrain at this location unavailable)*/ + uint16_t pending; /*< Number of 4x4 terrain blocks waiting to be received or read from disk*/ + uint16_t loaded; /*< Number of 4x4 terrain blocks in memory*/ +} mavlink_terrain_report_t; + +#define MAVLINK_MSG_ID_TERRAIN_REPORT_LEN 22 +#define MAVLINK_MSG_ID_136_LEN 22 + +#define MAVLINK_MSG_ID_TERRAIN_REPORT_CRC 1 +#define MAVLINK_MSG_ID_136_CRC 1 + + + +#define MAVLINK_MESSAGE_INFO_TERRAIN_REPORT { \ + "TERRAIN_REPORT", \ + 7, \ + { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_report_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_report_t, lon) }, \ + { "terrain_height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_terrain_report_t, terrain_height) }, \ + { "current_height", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_terrain_report_t, current_height) }, \ + { "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \ + { "pending", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_terrain_report_t, pending) }, \ + { "loaded", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_terrain_report_t, loaded) }, \ + } \ +} + + +/** + * @brief Pack a terrain_report message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param lat Latitude (degrees *10^7) + * @param lon Longitude (degrees *10^7) + * @param spacing grid spacing (zero if terrain at this location unavailable) + * @param terrain_height Terrain height in meters AMSL + * @param current_height Current vehicle height above lat/lon terrain height (meters) + * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk + * @param loaded Number of 4x4 terrain blocks in memory + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_float(buf, 8, terrain_height); + _mav_put_float(buf, 12, current_height); + _mav_put_uint16_t(buf, 16, spacing); + _mav_put_uint16_t(buf, 18, pending); + _mav_put_uint16_t(buf, 20, loaded); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#else + mavlink_terrain_report_t packet; + packet.lat = lat; + packet.lon = lon; + packet.terrain_height = terrain_height; + packet.current_height = current_height; + packet.spacing = spacing; + packet.pending = pending; + packet.loaded = loaded; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif +} + +/** + * @brief Pack a terrain_report message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param lat Latitude (degrees *10^7) + * @param lon Longitude (degrees *10^7) + * @param spacing grid spacing (zero if terrain at this location unavailable) + * @param terrain_height Terrain height in meters AMSL + * @param current_height Current vehicle height above lat/lon terrain height (meters) + * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk + * @param loaded Number of 4x4 terrain blocks in memory + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int32_t lat,int32_t lon,uint16_t spacing,float terrain_height,float current_height,uint16_t pending,uint16_t loaded) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_float(buf, 8, terrain_height); + _mav_put_float(buf, 12, current_height); + _mav_put_uint16_t(buf, 16, spacing); + _mav_put_uint16_t(buf, 18, pending); + _mav_put_uint16_t(buf, 20, loaded); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#else + mavlink_terrain_report_t packet; + packet.lat = lat; + packet.lon = lon; + packet.terrain_height = terrain_height; + packet.current_height = current_height; + packet.spacing = spacing; + packet.pending = pending; + packet.loaded = loaded; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif +} + +/** + * @brief Encode a terrain_report struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param terrain_report C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_report_t* terrain_report) +{ + return mavlink_msg_terrain_report_pack(system_id, component_id, msg, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded); +} + +/** + * @brief Encode a terrain_report struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param terrain_report C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_report_t* terrain_report) +{ + return mavlink_msg_terrain_report_pack_chan(system_id, component_id, chan, msg, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded); +} + +/** + * @brief Send a terrain_report message + * @param chan MAVLink channel to send the message + * + * @param lat Latitude (degrees *10^7) + * @param lon Longitude (degrees *10^7) + * @param spacing grid spacing (zero if terrain at this location unavailable) + * @param terrain_height Terrain height in meters AMSL + * @param current_height Current vehicle height above lat/lon terrain height (meters) + * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk + * @param loaded Number of 4x4 terrain blocks in memory + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_terrain_report_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_float(buf, 8, terrain_height); + _mav_put_float(buf, 12, current_height); + _mav_put_uint16_t(buf, 16, spacing); + _mav_put_uint16_t(buf, 18, pending); + _mav_put_uint16_t(buf, 20, loaded); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif +#else + mavlink_terrain_report_t packet; + packet.lat = lat; + packet.lon = lon; + packet.terrain_height = terrain_height; + packet.current_height = current_height; + packet.spacing = spacing; + packet.pending = pending; + packet.loaded = loaded; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_TERRAIN_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_terrain_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_float(buf, 8, terrain_height); + _mav_put_float(buf, 12, current_height); + _mav_put_uint16_t(buf, 16, spacing); + _mav_put_uint16_t(buf, 18, pending); + _mav_put_uint16_t(buf, 20, loaded); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif +#else + mavlink_terrain_report_t *packet = (mavlink_terrain_report_t *)msgbuf; + packet->lat = lat; + packet->lon = lon; + packet->terrain_height = terrain_height; + packet->current_height = current_height; + packet->spacing = spacing; + packet->pending = pending; + packet->loaded = loaded; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE TERRAIN_REPORT UNPACKING + + +/** + * @brief Get field lat from terrain_report message + * + * @return Latitude (degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_report_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field lon from terrain_report message + * + * @return Longitude (degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_report_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field spacing from terrain_report message + * + * @return grid spacing (zero if terrain at this location unavailable) + */ +static inline uint16_t mavlink_msg_terrain_report_get_spacing(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field terrain_height from terrain_report message + * + * @return Terrain height in meters AMSL + */ +static inline float mavlink_msg_terrain_report_get_terrain_height(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field current_height from terrain_report message + * + * @return Current vehicle height above lat/lon terrain height (meters) + */ +static inline float mavlink_msg_terrain_report_get_current_height(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field pending from terrain_report message + * + * @return Number of 4x4 terrain blocks waiting to be received or read from disk + */ +static inline uint16_t mavlink_msg_terrain_report_get_pending(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field loaded from terrain_report message + * + * @return Number of 4x4 terrain blocks in memory + */ +static inline uint16_t mavlink_msg_terrain_report_get_loaded(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Decode a terrain_report message into a struct + * + * @param msg The message to decode + * @param terrain_report C-struct to decode the message contents into + */ +static inline void mavlink_msg_terrain_report_decode(const mavlink_message_t* msg, mavlink_terrain_report_t* terrain_report) +{ +#if MAVLINK_NEED_BYTE_SWAP + terrain_report->lat = mavlink_msg_terrain_report_get_lat(msg); + terrain_report->lon = mavlink_msg_terrain_report_get_lon(msg); + terrain_report->terrain_height = mavlink_msg_terrain_report_get_terrain_height(msg); + terrain_report->current_height = mavlink_msg_terrain_report_get_current_height(msg); + terrain_report->spacing = mavlink_msg_terrain_report_get_spacing(msg); + terrain_report->pending = mavlink_msg_terrain_report_get_pending(msg); + terrain_report->loaded = mavlink_msg_terrain_report_get_loaded(msg); +#else + memcpy(terrain_report, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_terrain_request.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_terrain_request.h new file mode 100644 index 0000000..fdab6de --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_terrain_request.h @@ -0,0 +1,281 @@ +// MESSAGE TERRAIN_REQUEST PACKING + +#define MAVLINK_MSG_ID_TERRAIN_REQUEST 133 + +typedef struct __mavlink_terrain_request_t +{ + uint64_t mask; /*< Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)*/ + int32_t lat; /*< Latitude of SW corner of first grid (degrees *10^7)*/ + int32_t lon; /*< Longitude of SW corner of first grid (in degrees *10^7)*/ + uint16_t grid_spacing; /*< Grid spacing in meters*/ +} mavlink_terrain_request_t; + +#define MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN 18 +#define MAVLINK_MSG_ID_133_LEN 18 + +#define MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC 6 +#define MAVLINK_MSG_ID_133_CRC 6 + + + +#define MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST { \ + "TERRAIN_REQUEST", \ + 4, \ + { { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_terrain_request_t, lon) }, \ + { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_request_t, grid_spacing) }, \ + } \ +} + + +/** + * @brief Pack a terrain_request message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param lat Latitude of SW corner of first grid (degrees *10^7) + * @param lon Longitude of SW corner of first grid (in degrees *10^7) + * @param grid_spacing Grid spacing in meters + * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN]; + _mav_put_uint64_t(buf, 0, mask); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_uint16_t(buf, 16, grid_spacing); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#else + mavlink_terrain_request_t packet; + packet.mask = mask; + packet.lat = lat; + packet.lon = lon; + packet.grid_spacing = grid_spacing; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_REQUEST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif +} + +/** + * @brief Pack a terrain_request message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param lat Latitude of SW corner of first grid (degrees *10^7) + * @param lon Longitude of SW corner of first grid (in degrees *10^7) + * @param grid_spacing Grid spacing in meters + * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int32_t lat,int32_t lon,uint16_t grid_spacing,uint64_t mask) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN]; + _mav_put_uint64_t(buf, 0, mask); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_uint16_t(buf, 16, grid_spacing); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#else + mavlink_terrain_request_t packet; + packet.mask = mask; + packet.lat = lat; + packet.lon = lon; + packet.grid_spacing = grid_spacing; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_REQUEST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif +} + +/** + * @brief Encode a terrain_request struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param terrain_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_request_t* terrain_request) +{ + return mavlink_msg_terrain_request_pack(system_id, component_id, msg, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask); +} + +/** + * @brief Encode a terrain_request struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param terrain_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_request_t* terrain_request) +{ + return mavlink_msg_terrain_request_pack_chan(system_id, component_id, chan, msg, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask); +} + +/** + * @brief Send a terrain_request message + * @param chan MAVLink channel to send the message + * + * @param lat Latitude of SW corner of first grid (degrees *10^7) + * @param lon Longitude of SW corner of first grid (in degrees *10^7) + * @param grid_spacing Grid spacing in meters + * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_terrain_request_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN]; + _mav_put_uint64_t(buf, 0, mask); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_uint16_t(buf, 16, grid_spacing); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif +#else + mavlink_terrain_request_t packet; + packet.mask = mask; + packet.lat = lat; + packet.lon = lon; + packet.grid_spacing = grid_spacing; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_terrain_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, mask); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_uint16_t(buf, 16, grid_spacing); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif +#else + mavlink_terrain_request_t *packet = (mavlink_terrain_request_t *)msgbuf; + packet->mask = mask; + packet->lat = lat; + packet->lon = lon; + packet->grid_spacing = grid_spacing; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE TERRAIN_REQUEST UNPACKING + + +/** + * @brief Get field lat from terrain_request message + * + * @return Latitude of SW corner of first grid (degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_request_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field lon from terrain_request message + * + * @return Longitude of SW corner of first grid (in degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_request_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field grid_spacing from terrain_request message + * + * @return Grid spacing in meters + */ +static inline uint16_t mavlink_msg_terrain_request_get_grid_spacing(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field mask from terrain_request message + * + * @return Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + */ +static inline uint64_t mavlink_msg_terrain_request_get_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Decode a terrain_request message into a struct + * + * @param msg The message to decode + * @param terrain_request C-struct to decode the message contents into + */ +static inline void mavlink_msg_terrain_request_decode(const mavlink_message_t* msg, mavlink_terrain_request_t* terrain_request) +{ +#if MAVLINK_NEED_BYTE_SWAP + terrain_request->mask = mavlink_msg_terrain_request_get_mask(msg); + terrain_request->lat = mavlink_msg_terrain_request_get_lat(msg); + terrain_request->lon = mavlink_msg_terrain_request_get_lon(msg); + terrain_request->grid_spacing = mavlink_msg_terrain_request_get_grid_spacing(msg); +#else + memcpy(terrain_request, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_timesync.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_timesync.h new file mode 100644 index 0000000..be28442 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_timesync.h @@ -0,0 +1,233 @@ +// MESSAGE TIMESYNC PACKING + +#define MAVLINK_MSG_ID_TIMESYNC 111 + +typedef struct __mavlink_timesync_t +{ + int64_t tc1; /*< Time sync timestamp 1*/ + int64_t ts1; /*< Time sync timestamp 2*/ +} mavlink_timesync_t; + +#define MAVLINK_MSG_ID_TIMESYNC_LEN 16 +#define MAVLINK_MSG_ID_111_LEN 16 + +#define MAVLINK_MSG_ID_TIMESYNC_CRC 34 +#define MAVLINK_MSG_ID_111_CRC 34 + + + +#define MAVLINK_MESSAGE_INFO_TIMESYNC { \ + "TIMESYNC", \ + 2, \ + { { "tc1", NULL, MAVLINK_TYPE_INT64_T, 0, 0, offsetof(mavlink_timesync_t, tc1) }, \ + { "ts1", NULL, MAVLINK_TYPE_INT64_T, 0, 8, offsetof(mavlink_timesync_t, ts1) }, \ + } \ +} + + +/** + * @brief Pack a timesync message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param tc1 Time sync timestamp 1 + * @param ts1 Time sync timestamp 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_timesync_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int64_t tc1, int64_t ts1) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TIMESYNC_LEN]; + _mav_put_int64_t(buf, 0, tc1); + _mav_put_int64_t(buf, 8, ts1); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TIMESYNC_LEN); +#else + mavlink_timesync_t packet; + packet.tc1 = tc1; + packet.ts1 = ts1; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TIMESYNC; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif +} + +/** + * @brief Pack a timesync message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param tc1 Time sync timestamp 1 + * @param ts1 Time sync timestamp 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_timesync_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int64_t tc1,int64_t ts1) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TIMESYNC_LEN]; + _mav_put_int64_t(buf, 0, tc1); + _mav_put_int64_t(buf, 8, ts1); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TIMESYNC_LEN); +#else + mavlink_timesync_t packet; + packet.tc1 = tc1; + packet.ts1 = ts1; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TIMESYNC; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif +} + +/** + * @brief Encode a timesync struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param timesync C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_timesync_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_timesync_t* timesync) +{ + return mavlink_msg_timesync_pack(system_id, component_id, msg, timesync->tc1, timesync->ts1); +} + +/** + * @brief Encode a timesync struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param timesync C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_timesync_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_timesync_t* timesync) +{ + return mavlink_msg_timesync_pack_chan(system_id, component_id, chan, msg, timesync->tc1, timesync->ts1); +} + +/** + * @brief Send a timesync message + * @param chan MAVLink channel to send the message + * + * @param tc1 Time sync timestamp 1 + * @param ts1 Time sync timestamp 2 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_timesync_send(mavlink_channel_t chan, int64_t tc1, int64_t ts1) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TIMESYNC_LEN]; + _mav_put_int64_t(buf, 0, tc1); + _mav_put_int64_t(buf, 8, ts1); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif +#else + mavlink_timesync_t packet; + packet.tc1 = tc1; + packet.ts1 = ts1; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)&packet, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)&packet, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_TIMESYNC_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_timesync_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int64_t tc1, int64_t ts1) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int64_t(buf, 0, tc1); + _mav_put_int64_t(buf, 8, ts1); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif +#else + mavlink_timesync_t *packet = (mavlink_timesync_t *)msgbuf; + packet->tc1 = tc1; + packet->ts1 = ts1; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)packet, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)packet, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE TIMESYNC UNPACKING + + +/** + * @brief Get field tc1 from timesync message + * + * @return Time sync timestamp 1 + */ +static inline int64_t mavlink_msg_timesync_get_tc1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int64_t(msg, 0); +} + +/** + * @brief Get field ts1 from timesync message + * + * @return Time sync timestamp 2 + */ +static inline int64_t mavlink_msg_timesync_get_ts1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int64_t(msg, 8); +} + +/** + * @brief Decode a timesync message into a struct + * + * @param msg The message to decode + * @param timesync C-struct to decode the message contents into + */ +static inline void mavlink_msg_timesync_decode(const mavlink_message_t* msg, mavlink_timesync_t* timesync) +{ +#if MAVLINK_NEED_BYTE_SWAP + timesync->tc1 = mavlink_msg_timesync_get_tc1(msg); + timesync->ts1 = mavlink_msg_timesync_get_ts1(msg); +#else + memcpy(timesync, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_v2_extension.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_v2_extension.h new file mode 100644 index 0000000..26f18ad --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_v2_extension.h @@ -0,0 +1,297 @@ +// MESSAGE V2_EXTENSION PACKING + +#define MAVLINK_MSG_ID_V2_EXTENSION 248 + +typedef struct __mavlink_v2_extension_t +{ + uint16_t message_type; /*< A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.*/ + uint8_t target_network; /*< Network ID (0 for broadcast)*/ + uint8_t target_system; /*< System ID (0 for broadcast)*/ + uint8_t target_component; /*< Component ID (0 for broadcast)*/ + uint8_t payload[249]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.*/ +} mavlink_v2_extension_t; + +#define MAVLINK_MSG_ID_V2_EXTENSION_LEN 254 +#define MAVLINK_MSG_ID_248_LEN 254 + +#define MAVLINK_MSG_ID_V2_EXTENSION_CRC 8 +#define MAVLINK_MSG_ID_248_CRC 8 + +#define MAVLINK_MSG_V2_EXTENSION_FIELD_PAYLOAD_LEN 249 + +#define MAVLINK_MESSAGE_INFO_V2_EXTENSION { \ + "V2_EXTENSION", \ + 5, \ + { { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \ + { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_v2_extension_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_v2_extension_t, target_component) }, \ + { "payload", NULL, MAVLINK_TYPE_UINT8_T, 249, 5, offsetof(mavlink_v2_extension_t, payload) }, \ + } \ +} + + +/** + * @brief Pack a v2_extension message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_v2_extension_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN]; + _mav_put_uint16_t(buf, 0, message_type); + _mav_put_uint8_t(buf, 2, target_network); + _mav_put_uint8_t(buf, 3, target_system); + _mav_put_uint8_t(buf, 4, target_component); + _mav_put_uint8_t_array(buf, 5, payload, 249); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#else + mavlink_v2_extension_t packet; + packet.message_type = message_type; + packet.target_network = target_network; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif +} + +/** + * @brief Pack a v2_extension message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_v2_extension_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_network,uint8_t target_system,uint8_t target_component,uint16_t message_type,const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN]; + _mav_put_uint16_t(buf, 0, message_type); + _mav_put_uint8_t(buf, 2, target_network); + _mav_put_uint8_t(buf, 3, target_system); + _mav_put_uint8_t(buf, 4, target_component); + _mav_put_uint8_t_array(buf, 5, payload, 249); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#else + mavlink_v2_extension_t packet; + packet.message_type = message_type; + packet.target_network = target_network; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif +} + +/** + * @brief Encode a v2_extension struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param v2_extension C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_v2_extension_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension) +{ + return mavlink_msg_v2_extension_pack(system_id, component_id, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload); +} + +/** + * @brief Encode a v2_extension struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param v2_extension C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_v2_extension_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension) +{ + return mavlink_msg_v2_extension_pack_chan(system_id, component_id, chan, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload); +} + +/** + * @brief Send a v2_extension message + * @param chan MAVLink channel to send the message + * + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_v2_extension_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN]; + _mav_put_uint16_t(buf, 0, message_type); + _mav_put_uint8_t(buf, 2, target_network); + _mav_put_uint8_t(buf, 3, target_system); + _mav_put_uint8_t(buf, 4, target_component); + _mav_put_uint8_t_array(buf, 5, payload, 249); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif +#else + mavlink_v2_extension_t packet; + packet.message_type = message_type; + packet.target_network = target_network; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)&packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)&packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_V2_EXTENSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_v2_extension_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, message_type); + _mav_put_uint8_t(buf, 2, target_network); + _mav_put_uint8_t(buf, 3, target_system); + _mav_put_uint8_t(buf, 4, target_component); + _mav_put_uint8_t_array(buf, 5, payload, 249); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif +#else + mavlink_v2_extension_t *packet = (mavlink_v2_extension_t *)msgbuf; + packet->message_type = message_type; + packet->target_network = target_network; + packet->target_system = target_system; + packet->target_component = target_component; + mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*249); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE V2_EXTENSION UNPACKING + + +/** + * @brief Get field target_network from v2_extension message + * + * @return Network ID (0 for broadcast) + */ +static inline uint8_t mavlink_msg_v2_extension_get_target_network(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_system from v2_extension message + * + * @return System ID (0 for broadcast) + */ +static inline uint8_t mavlink_msg_v2_extension_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field target_component from v2_extension message + * + * @return Component ID (0 for broadcast) + */ +static inline uint8_t mavlink_msg_v2_extension_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field message_type from v2_extension message + * + * @return A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + */ +static inline uint16_t mavlink_msg_v2_extension_get_message_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field payload from v2_extension message + * + * @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + */ +static inline uint16_t mavlink_msg_v2_extension_get_payload(const mavlink_message_t* msg, uint8_t *payload) +{ + return _MAV_RETURN_uint8_t_array(msg, payload, 249, 5); +} + +/** + * @brief Decode a v2_extension message into a struct + * + * @param msg The message to decode + * @param v2_extension C-struct to decode the message contents into + */ +static inline void mavlink_msg_v2_extension_decode(const mavlink_message_t* msg, mavlink_v2_extension_t* v2_extension) +{ +#if MAVLINK_NEED_BYTE_SWAP + v2_extension->message_type = mavlink_msg_v2_extension_get_message_type(msg); + v2_extension->target_network = mavlink_msg_v2_extension_get_target_network(msg); + v2_extension->target_system = mavlink_msg_v2_extension_get_target_system(msg); + v2_extension->target_component = mavlink_msg_v2_extension_get_target_component(msg); + mavlink_msg_v2_extension_get_payload(msg, v2_extension->payload); +#else + memcpy(v2_extension, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_vfr_hud.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_vfr_hud.h new file mode 100644 index 0000000..0dc5b82 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_vfr_hud.h @@ -0,0 +1,329 @@ +// MESSAGE VFR_HUD PACKING + +#define MAVLINK_MSG_ID_VFR_HUD 74 + +typedef struct __mavlink_vfr_hud_t +{ + float airspeed; /*< Current airspeed in m/s*/ + float groundspeed; /*< Current ground speed in m/s*/ + float alt; /*< Current altitude (MSL), in meters*/ + float climb; /*< Current climb rate in meters/second*/ + int16_t heading; /*< Current heading in degrees, in compass units (0..360, 0=north)*/ + uint16_t throttle; /*< Current throttle setting in integer percent, 0 to 100*/ +} mavlink_vfr_hud_t; + +#define MAVLINK_MSG_ID_VFR_HUD_LEN 20 +#define MAVLINK_MSG_ID_74_LEN 20 + +#define MAVLINK_MSG_ID_VFR_HUD_CRC 20 +#define MAVLINK_MSG_ID_74_CRC 20 + + + +#define MAVLINK_MESSAGE_INFO_VFR_HUD { \ + "VFR_HUD", \ + 6, \ + { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \ + { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \ + { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \ + { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \ + { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \ + } \ +} + + +/** + * @brief Pack a vfr_hud message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param airspeed Current airspeed in m/s + * @param groundspeed Current ground speed in m/s + * @param heading Current heading in degrees, in compass units (0..360, 0=north) + * @param throttle Current throttle setting in integer percent, 0 to 100 + * @param alt Current altitude (MSL), in meters + * @param climb Current climb rate in meters/second + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VFR_HUD_LEN]; + _mav_put_float(buf, 0, airspeed); + _mav_put_float(buf, 4, groundspeed); + _mav_put_float(buf, 8, alt); + _mav_put_float(buf, 12, climb); + _mav_put_int16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, throttle); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN); +#else + mavlink_vfr_hud_t packet; + packet.airspeed = airspeed; + packet.groundspeed = groundspeed; + packet.alt = alt; + packet.climb = climb; + packet.heading = heading; + packet.throttle = throttle; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VFR_HUD; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif +} + +/** + * @brief Pack a vfr_hud message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param airspeed Current airspeed in m/s + * @param groundspeed Current ground speed in m/s + * @param heading Current heading in degrees, in compass units (0..360, 0=north) + * @param throttle Current throttle setting in integer percent, 0 to 100 + * @param alt Current altitude (MSL), in meters + * @param climb Current climb rate in meters/second + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float airspeed,float groundspeed,int16_t heading,uint16_t throttle,float alt,float climb) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VFR_HUD_LEN]; + _mav_put_float(buf, 0, airspeed); + _mav_put_float(buf, 4, groundspeed); + _mav_put_float(buf, 8, alt); + _mav_put_float(buf, 12, climb); + _mav_put_int16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, throttle); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN); +#else + mavlink_vfr_hud_t packet; + packet.airspeed = airspeed; + packet.groundspeed = groundspeed; + packet.alt = alt; + packet.climb = climb; + packet.heading = heading; + packet.throttle = throttle; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VFR_HUD; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif +} + +/** + * @brief Encode a vfr_hud struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vfr_hud C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud) +{ + return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); +} + +/** + * @brief Encode a vfr_hud struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param vfr_hud C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vfr_hud_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud) +{ + return mavlink_msg_vfr_hud_pack_chan(system_id, component_id, chan, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); +} + +/** + * @brief Send a vfr_hud message + * @param chan MAVLink channel to send the message + * + * @param airspeed Current airspeed in m/s + * @param groundspeed Current ground speed in m/s + * @param heading Current heading in degrees, in compass units (0..360, 0=north) + * @param throttle Current throttle setting in integer percent, 0 to 100 + * @param alt Current altitude (MSL), in meters + * @param climb Current climb rate in meters/second + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VFR_HUD_LEN]; + _mav_put_float(buf, 0, airspeed); + _mav_put_float(buf, 4, groundspeed); + _mav_put_float(buf, 8, alt); + _mav_put_float(buf, 12, climb); + _mav_put_int16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, throttle); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif +#else + mavlink_vfr_hud_t packet; + packet.airspeed = airspeed; + packet.groundspeed = groundspeed; + packet.alt = alt; + packet.climb = climb; + packet.heading = heading; + packet.throttle = throttle; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_VFR_HUD_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_vfr_hud_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, airspeed); + _mav_put_float(buf, 4, groundspeed); + _mav_put_float(buf, 8, alt); + _mav_put_float(buf, 12, climb); + _mav_put_int16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, throttle); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif +#else + mavlink_vfr_hud_t *packet = (mavlink_vfr_hud_t *)msgbuf; + packet->airspeed = airspeed; + packet->groundspeed = groundspeed; + packet->alt = alt; + packet->climb = climb; + packet->heading = heading; + packet->throttle = throttle; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)packet, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)packet, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE VFR_HUD UNPACKING + + +/** + * @brief Get field airspeed from vfr_hud message + * + * @return Current airspeed in m/s + */ +static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field groundspeed from vfr_hud message + * + * @return Current ground speed in m/s + */ +static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field heading from vfr_hud message + * + * @return Current heading in degrees, in compass units (0..360, 0=north) + */ +static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field throttle from vfr_hud message + * + * @return Current throttle setting in integer percent, 0 to 100 + */ +static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field alt from vfr_hud message + * + * @return Current altitude (MSL), in meters + */ +static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field climb from vfr_hud message + * + * @return Current climb rate in meters/second + */ +static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a vfr_hud message into a struct + * + * @param msg The message to decode + * @param vfr_hud C-struct to decode the message contents into + */ +static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavlink_vfr_hud_t* vfr_hud) +{ +#if MAVLINK_NEED_BYTE_SWAP + vfr_hud->airspeed = mavlink_msg_vfr_hud_get_airspeed(msg); + vfr_hud->groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg); + vfr_hud->alt = mavlink_msg_vfr_hud_get_alt(msg); + vfr_hud->climb = mavlink_msg_vfr_hud_get_climb(msg); + vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg); + vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg); +#else + memcpy(vfr_hud, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_vibration.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_vibration.h new file mode 100644 index 0000000..7b2d10c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_vibration.h @@ -0,0 +1,353 @@ +// MESSAGE VIBRATION PACKING + +#define MAVLINK_MSG_ID_VIBRATION 241 + +typedef struct __mavlink_vibration_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float vibration_x; /*< Vibration levels on X-axis*/ + float vibration_y; /*< Vibration levels on Y-axis*/ + float vibration_z; /*< Vibration levels on Z-axis*/ + uint32_t clipping_0; /*< first accelerometer clipping count*/ + uint32_t clipping_1; /*< second accelerometer clipping count*/ + uint32_t clipping_2; /*< third accelerometer clipping count*/ +} mavlink_vibration_t; + +#define MAVLINK_MSG_ID_VIBRATION_LEN 32 +#define MAVLINK_MSG_ID_241_LEN 32 + +#define MAVLINK_MSG_ID_VIBRATION_CRC 90 +#define MAVLINK_MSG_ID_241_CRC 90 + + + +#define MAVLINK_MESSAGE_INFO_VIBRATION { \ + "VIBRATION", \ + 7, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vibration_t, time_usec) }, \ + { "vibration_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vibration_t, vibration_x) }, \ + { "vibration_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vibration_t, vibration_y) }, \ + { "vibration_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vibration_t, vibration_z) }, \ + { "clipping_0", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_vibration_t, clipping_0) }, \ + { "clipping_1", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_vibration_t, clipping_1) }, \ + { "clipping_2", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_vibration_t, clipping_2) }, \ + } \ +} + + +/** + * @brief Pack a vibration message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param vibration_x Vibration levels on X-axis + * @param vibration_y Vibration levels on Y-axis + * @param vibration_z Vibration levels on Z-axis + * @param clipping_0 first accelerometer clipping count + * @param clipping_1 second accelerometer clipping count + * @param clipping_2 third accelerometer clipping count + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VIBRATION_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vibration_x); + _mav_put_float(buf, 12, vibration_y); + _mav_put_float(buf, 16, vibration_z); + _mav_put_uint32_t(buf, 20, clipping_0); + _mav_put_uint32_t(buf, 24, clipping_1); + _mav_put_uint32_t(buf, 28, clipping_2); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIBRATION_LEN); +#else + mavlink_vibration_t packet; + packet.time_usec = time_usec; + packet.vibration_x = vibration_x; + packet.vibration_y = vibration_y; + packet.vibration_z = vibration_z; + packet.clipping_0 = clipping_0; + packet.clipping_1 = clipping_1; + packet.clipping_2 = clipping_2; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VIBRATION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif +} + +/** + * @brief Pack a vibration message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param vibration_x Vibration levels on X-axis + * @param vibration_y Vibration levels on Y-axis + * @param vibration_z Vibration levels on Z-axis + * @param clipping_0 first accelerometer clipping count + * @param clipping_1 second accelerometer clipping count + * @param clipping_2 third accelerometer clipping count + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float vibration_x,float vibration_y,float vibration_z,uint32_t clipping_0,uint32_t clipping_1,uint32_t clipping_2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VIBRATION_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vibration_x); + _mav_put_float(buf, 12, vibration_y); + _mav_put_float(buf, 16, vibration_z); + _mav_put_uint32_t(buf, 20, clipping_0); + _mav_put_uint32_t(buf, 24, clipping_1); + _mav_put_uint32_t(buf, 28, clipping_2); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIBRATION_LEN); +#else + mavlink_vibration_t packet; + packet.time_usec = time_usec; + packet.vibration_x = vibration_x; + packet.vibration_y = vibration_y; + packet.vibration_z = vibration_z; + packet.clipping_0 = clipping_0; + packet.clipping_1 = clipping_1; + packet.clipping_2 = clipping_2; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VIBRATION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif +} + +/** + * @brief Encode a vibration struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vibration C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vibration_t* vibration) +{ + return mavlink_msg_vibration_pack(system_id, component_id, msg, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2); +} + +/** + * @brief Encode a vibration struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param vibration C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vibration_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vibration_t* vibration) +{ + return mavlink_msg_vibration_pack_chan(system_id, component_id, chan, msg, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2); +} + +/** + * @brief Send a vibration message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param vibration_x Vibration levels on X-axis + * @param vibration_y Vibration levels on Y-axis + * @param vibration_z Vibration levels on Z-axis + * @param clipping_0 first accelerometer clipping count + * @param clipping_1 second accelerometer clipping count + * @param clipping_2 third accelerometer clipping count + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vibration_send(mavlink_channel_t chan, uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VIBRATION_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vibration_x); + _mav_put_float(buf, 12, vibration_y); + _mav_put_float(buf, 16, vibration_z); + _mav_put_uint32_t(buf, 20, clipping_0); + _mav_put_uint32_t(buf, 24, clipping_1); + _mav_put_uint32_t(buf, 28, clipping_2); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif +#else + mavlink_vibration_t packet; + packet.time_usec = time_usec; + packet.vibration_x = vibration_x; + packet.vibration_y = vibration_y; + packet.vibration_z = vibration_z; + packet.clipping_0 = clipping_0; + packet.clipping_1 = clipping_1; + packet.clipping_2 = clipping_2; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)&packet, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)&packet, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_VIBRATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_vibration_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vibration_x); + _mav_put_float(buf, 12, vibration_y); + _mav_put_float(buf, 16, vibration_z); + _mav_put_uint32_t(buf, 20, clipping_0); + _mav_put_uint32_t(buf, 24, clipping_1); + _mav_put_uint32_t(buf, 28, clipping_2); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif +#else + mavlink_vibration_t *packet = (mavlink_vibration_t *)msgbuf; + packet->time_usec = time_usec; + packet->vibration_x = vibration_x; + packet->vibration_y = vibration_y; + packet->vibration_z = vibration_z; + packet->clipping_0 = clipping_0; + packet->clipping_1 = clipping_1; + packet->clipping_2 = clipping_2; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)packet, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)packet, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE VIBRATION UNPACKING + + +/** + * @brief Get field time_usec from vibration message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_vibration_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field vibration_x from vibration message + * + * @return Vibration levels on X-axis + */ +static inline float mavlink_msg_vibration_get_vibration_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field vibration_y from vibration message + * + * @return Vibration levels on Y-axis + */ +static inline float mavlink_msg_vibration_get_vibration_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vibration_z from vibration message + * + * @return Vibration levels on Z-axis + */ +static inline float mavlink_msg_vibration_get_vibration_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field clipping_0 from vibration message + * + * @return first accelerometer clipping count + */ +static inline uint32_t mavlink_msg_vibration_get_clipping_0(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 20); +} + +/** + * @brief Get field clipping_1 from vibration message + * + * @return second accelerometer clipping count + */ +static inline uint32_t mavlink_msg_vibration_get_clipping_1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 24); +} + +/** + * @brief Get field clipping_2 from vibration message + * + * @return third accelerometer clipping count + */ +static inline uint32_t mavlink_msg_vibration_get_clipping_2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 28); +} + +/** + * @brief Decode a vibration message into a struct + * + * @param msg The message to decode + * @param vibration C-struct to decode the message contents into + */ +static inline void mavlink_msg_vibration_decode(const mavlink_message_t* msg, mavlink_vibration_t* vibration) +{ +#if MAVLINK_NEED_BYTE_SWAP + vibration->time_usec = mavlink_msg_vibration_get_time_usec(msg); + vibration->vibration_x = mavlink_msg_vibration_get_vibration_x(msg); + vibration->vibration_y = mavlink_msg_vibration_get_vibration_y(msg); + vibration->vibration_z = mavlink_msg_vibration_get_vibration_z(msg); + vibration->clipping_0 = mavlink_msg_vibration_get_clipping_0(msg); + vibration->clipping_1 = mavlink_msg_vibration_get_clipping_1(msg); + vibration->clipping_2 = mavlink_msg_vibration_get_clipping_2(msg); +#else + memcpy(vibration, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VIBRATION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h new file mode 100644 index 0000000..9fb41e7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h @@ -0,0 +1,353 @@ +// MESSAGE VICON_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 104 + +typedef struct __mavlink_vicon_position_estimate_t +{ + uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + float x; /*< Global X position*/ + float y; /*< Global Y position*/ + float z; /*< Global Z position*/ + float roll; /*< Roll angle in rad*/ + float pitch; /*< Pitch angle in rad*/ + float yaw; /*< Yaw angle in rad*/ +} mavlink_vicon_position_estimate_t; + +#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32 +#define MAVLINK_MSG_ID_104_LEN 32 + +#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC 56 +#define MAVLINK_MSG_ID_104_CRC 56 + + + +#define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \ + "VICON_POSITION_ESTIMATE", \ + 7, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vicon_position_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vicon_position_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vicon_position_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vicon_position_estimate_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vicon_position_estimate_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vicon_position_estimate_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vicon_position_estimate_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a vicon_position_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#else + mavlink_vicon_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif +} + +/** + * @brief Pack a vicon_position_estimate message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#else + mavlink_vicon_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif +} + +/** + * @brief Encode a vicon_position_estimate struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vicon_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) +{ + return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); +} + +/** + * @brief Encode a vicon_position_estimate struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param vicon_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) +{ + return mavlink_msg_vicon_position_estimate_pack_chan(system_id, component_id, chan, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); +} + +/** + * @brief Send a vicon_position_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif +#else + mavlink_vicon_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_vicon_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif +#else + mavlink_vicon_position_estimate_t *packet = (mavlink_vicon_position_estimate_t *)msgbuf; + packet->usec = usec; + packet->x = x; + packet->y = y; + packet->z = z; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE VICON_POSITION_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from vicon_position_estimate message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from vicon_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_vicon_position_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from vicon_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_vicon_position_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from vicon_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_vicon_position_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field roll from vicon_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitch from vicon_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yaw from vicon_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a vicon_position_estimate message into a struct + * + * @param msg The message to decode + * @param vicon_position_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_message_t* msg, mavlink_vicon_position_estimate_t* vicon_position_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + vicon_position_estimate->usec = mavlink_msg_vicon_position_estimate_get_usec(msg); + vicon_position_estimate->x = mavlink_msg_vicon_position_estimate_get_x(msg); + vicon_position_estimate->y = mavlink_msg_vicon_position_estimate_get_y(msg); + vicon_position_estimate->z = mavlink_msg_vicon_position_estimate_get_z(msg); + vicon_position_estimate->roll = mavlink_msg_vicon_position_estimate_get_roll(msg); + vicon_position_estimate->pitch = mavlink_msg_vicon_position_estimate_get_pitch(msg); + vicon_position_estimate->yaw = mavlink_msg_vicon_position_estimate_get_yaw(msg); +#else + memcpy(vicon_position_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h new file mode 100644 index 0000000..f3d8e5d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h @@ -0,0 +1,353 @@ +// MESSAGE VISION_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 102 + +typedef struct __mavlink_vision_position_estimate_t +{ + uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + float x; /*< Global X position*/ + float y; /*< Global Y position*/ + float z; /*< Global Z position*/ + float roll; /*< Roll angle in rad*/ + float pitch; /*< Pitch angle in rad*/ + float yaw; /*< Yaw angle in rad*/ +} mavlink_vision_position_estimate_t; + +#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32 +#define MAVLINK_MSG_ID_102_LEN 32 + +#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC 158 +#define MAVLINK_MSG_ID_102_CRC 158 + + + +#define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \ + "VISION_POSITION_ESTIMATE", \ + 7, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_position_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_position_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_position_estimate_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a vision_position_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#else + mavlink_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif +} + +/** + * @brief Pack a vision_position_estimate message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#else + mavlink_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif +} + +/** + * @brief Encode a vision_position_estimate struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vision_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) +{ + return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); +} + +/** + * @brief Encode a vision_position_estimate struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param vision_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vision_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) +{ + return mavlink_msg_vision_position_estimate_pack_chan(system_id, component_id, chan, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); +} + +/** + * @brief Send a vision_position_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif +#else + mavlink_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif +#else + mavlink_vision_position_estimate_t *packet = (mavlink_vision_position_estimate_t *)msgbuf; + packet->usec = usec; + packet->x = x; + packet->y = y; + packet->z = z; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE VISION_POSITION_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from vision_position_estimate message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from vision_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from vision_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from vision_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field roll from vision_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitch from vision_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yaw from vision_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a vision_position_estimate message into a struct + * + * @param msg The message to decode + * @param vision_position_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg); + vision_position_estimate->x = mavlink_msg_vision_position_estimate_get_x(msg); + vision_position_estimate->y = mavlink_msg_vision_position_estimate_get_y(msg); + vision_position_estimate->z = mavlink_msg_vision_position_estimate_get_z(msg); + vision_position_estimate->roll = mavlink_msg_vision_position_estimate_get_roll(msg); + vision_position_estimate->pitch = mavlink_msg_vision_position_estimate_get_pitch(msg); + vision_position_estimate->yaw = mavlink_msg_vision_position_estimate_get_yaw(msg); +#else + memcpy(vision_position_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h new file mode 100644 index 0000000..0154ea4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h @@ -0,0 +1,281 @@ +// MESSAGE VISION_SPEED_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103 + +typedef struct __mavlink_vision_speed_estimate_t +{ + uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + float x; /*< Global X speed*/ + float y; /*< Global Y speed*/ + float z; /*< Global Z speed*/ +} mavlink_vision_speed_estimate_t; + +#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20 +#define MAVLINK_MSG_ID_103_LEN 20 + +#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC 208 +#define MAVLINK_MSG_ID_103_CRC 208 + + + +#define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \ + "VISION_SPEED_ESTIMATE", \ + 4, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \ + } \ +} + + +/** + * @brief Pack a vision_speed_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X speed + * @param y Global Y speed + * @param z Global Z speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#else + mavlink_vision_speed_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif +} + +/** + * @brief Pack a vision_speed_estimate message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X speed + * @param y Global Y speed + * @param z Global Z speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#else + mavlink_vision_speed_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif +} + +/** + * @brief Encode a vision_speed_estimate struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vision_speed_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) +{ + return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); +} + +/** + * @brief Encode a vision_speed_estimate struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param vision_speed_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vision_speed_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) +{ + return mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, chan, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); +} + +/** + * @brief Send a vision_speed_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X speed + * @param y Global Y speed + * @param z Global Z speed + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif +#else + mavlink_vision_speed_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_vision_speed_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif +#else + mavlink_vision_speed_estimate_t *packet = (mavlink_vision_speed_estimate_t *)msgbuf; + packet->usec = usec; + packet->x = x; + packet->y = y; + packet->z = z; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE VISION_SPEED_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from vision_speed_estimate message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from vision_speed_estimate message + * + * @return Global X speed + */ +static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from vision_speed_estimate message + * + * @return Global Y speed + */ +static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from vision_speed_estimate message + * + * @return Global Z speed + */ +static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a vision_speed_estimate message into a struct + * + * @param msg The message to decode + * @param vision_speed_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg); + vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg); + vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg); + vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg); +#else + memcpy(vision_speed_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_wind_cov.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_wind_cov.h new file mode 100644 index 0000000..9a6b1aa --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/mavlink_msg_wind_cov.h @@ -0,0 +1,401 @@ +// MESSAGE WIND_COV PACKING + +#define MAVLINK_MSG_ID_WIND_COV 231 + +typedef struct __mavlink_wind_cov_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float wind_x; /*< Wind in X (NED) direction in m/s*/ + float wind_y; /*< Wind in Y (NED) direction in m/s*/ + float wind_z; /*< Wind in Z (NED) direction in m/s*/ + float var_horiz; /*< Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate.*/ + float var_vert; /*< Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate.*/ + float wind_alt; /*< AMSL altitude (m) this measurement was taken at*/ + float horiz_accuracy; /*< Horizontal speed 1-STD accuracy*/ + float vert_accuracy; /*< Vertical speed 1-STD accuracy*/ +} mavlink_wind_cov_t; + +#define MAVLINK_MSG_ID_WIND_COV_LEN 40 +#define MAVLINK_MSG_ID_231_LEN 40 + +#define MAVLINK_MSG_ID_WIND_COV_CRC 105 +#define MAVLINK_MSG_ID_231_CRC 105 + + + +#define MAVLINK_MESSAGE_INFO_WIND_COV { \ + "WIND_COV", \ + 9, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_wind_cov_t, time_usec) }, \ + { "wind_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_cov_t, wind_x) }, \ + { "wind_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_wind_cov_t, wind_y) }, \ + { "wind_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_wind_cov_t, wind_z) }, \ + { "var_horiz", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_wind_cov_t, var_horiz) }, \ + { "var_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_wind_cov_t, var_vert) }, \ + { "wind_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_wind_cov_t, wind_alt) }, \ + { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_wind_cov_t, horiz_accuracy) }, \ + { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_wind_cov_t, vert_accuracy) }, \ + } \ +} + + +/** + * @brief Pack a wind_cov message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param wind_x Wind in X (NED) direction in m/s + * @param wind_y Wind in Y (NED) direction in m/s + * @param wind_z Wind in Z (NED) direction in m/s + * @param var_horiz Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. + * @param var_vert Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. + * @param wind_alt AMSL altitude (m) this measurement was taken at + * @param horiz_accuracy Horizontal speed 1-STD accuracy + * @param vert_accuracy Vertical speed 1-STD accuracy + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_wind_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_WIND_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, wind_x); + _mav_put_float(buf, 12, wind_y); + _mav_put_float(buf, 16, wind_z); + _mav_put_float(buf, 20, var_horiz); + _mav_put_float(buf, 24, var_vert); + _mav_put_float(buf, 28, wind_alt); + _mav_put_float(buf, 32, horiz_accuracy); + _mav_put_float(buf, 36, vert_accuracy); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_COV_LEN); +#else + mavlink_wind_cov_t packet; + packet.time_usec = time_usec; + packet.wind_x = wind_x; + packet.wind_y = wind_y; + packet.wind_z = wind_z; + packet.var_horiz = var_horiz; + packet.var_vert = var_vert; + packet.wind_alt = wind_alt; + packet.horiz_accuracy = horiz_accuracy; + packet.vert_accuracy = vert_accuracy; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_WIND_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif +} + +/** + * @brief Pack a wind_cov message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param wind_x Wind in X (NED) direction in m/s + * @param wind_y Wind in Y (NED) direction in m/s + * @param wind_z Wind in Z (NED) direction in m/s + * @param var_horiz Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. + * @param var_vert Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. + * @param wind_alt AMSL altitude (m) this measurement was taken at + * @param horiz_accuracy Horizontal speed 1-STD accuracy + * @param vert_accuracy Vertical speed 1-STD accuracy + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_wind_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float wind_x,float wind_y,float wind_z,float var_horiz,float var_vert,float wind_alt,float horiz_accuracy,float vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_WIND_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, wind_x); + _mav_put_float(buf, 12, wind_y); + _mav_put_float(buf, 16, wind_z); + _mav_put_float(buf, 20, var_horiz); + _mav_put_float(buf, 24, var_vert); + _mav_put_float(buf, 28, wind_alt); + _mav_put_float(buf, 32, horiz_accuracy); + _mav_put_float(buf, 36, vert_accuracy); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_COV_LEN); +#else + mavlink_wind_cov_t packet; + packet.time_usec = time_usec; + packet.wind_x = wind_x; + packet.wind_y = wind_y; + packet.wind_z = wind_z; + packet.var_horiz = var_horiz; + packet.var_vert = var_vert; + packet.wind_alt = wind_alt; + packet.horiz_accuracy = horiz_accuracy; + packet.vert_accuracy = vert_accuracy; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_WIND_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif +} + +/** + * @brief Encode a wind_cov struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param wind_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_wind_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wind_cov_t* wind_cov) +{ + return mavlink_msg_wind_cov_pack(system_id, component_id, msg, wind_cov->time_usec, wind_cov->wind_x, wind_cov->wind_y, wind_cov->wind_z, wind_cov->var_horiz, wind_cov->var_vert, wind_cov->wind_alt, wind_cov->horiz_accuracy, wind_cov->vert_accuracy); +} + +/** + * @brief Encode a wind_cov struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param wind_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_wind_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wind_cov_t* wind_cov) +{ + return mavlink_msg_wind_cov_pack_chan(system_id, component_id, chan, msg, wind_cov->time_usec, wind_cov->wind_x, wind_cov->wind_y, wind_cov->wind_z, wind_cov->var_horiz, wind_cov->var_vert, wind_cov->wind_alt, wind_cov->horiz_accuracy, wind_cov->vert_accuracy); +} + +/** + * @brief Send a wind_cov message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param wind_x Wind in X (NED) direction in m/s + * @param wind_y Wind in Y (NED) direction in m/s + * @param wind_z Wind in Z (NED) direction in m/s + * @param var_horiz Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. + * @param var_vert Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. + * @param wind_alt AMSL altitude (m) this measurement was taken at + * @param horiz_accuracy Horizontal speed 1-STD accuracy + * @param vert_accuracy Vertical speed 1-STD accuracy + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_wind_cov_send(mavlink_channel_t chan, uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_WIND_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, wind_x); + _mav_put_float(buf, 12, wind_y); + _mav_put_float(buf, 16, wind_z); + _mav_put_float(buf, 20, var_horiz); + _mav_put_float(buf, 24, var_vert); + _mav_put_float(buf, 28, wind_alt); + _mav_put_float(buf, 32, horiz_accuracy); + _mav_put_float(buf, 36, vert_accuracy); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, buf, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, buf, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif +#else + mavlink_wind_cov_t packet; + packet.time_usec = time_usec; + packet.wind_x = wind_x; + packet.wind_y = wind_y; + packet.wind_z = wind_z; + packet.var_horiz = var_horiz; + packet.var_vert = var_vert; + packet.wind_alt = wind_alt; + packet.horiz_accuracy = horiz_accuracy; + packet.vert_accuracy = vert_accuracy; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)&packet, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)&packet, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_WIND_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_wind_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, wind_x); + _mav_put_float(buf, 12, wind_y); + _mav_put_float(buf, 16, wind_z); + _mav_put_float(buf, 20, var_horiz); + _mav_put_float(buf, 24, var_vert); + _mav_put_float(buf, 28, wind_alt); + _mav_put_float(buf, 32, horiz_accuracy); + _mav_put_float(buf, 36, vert_accuracy); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, buf, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, buf, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif +#else + mavlink_wind_cov_t *packet = (mavlink_wind_cov_t *)msgbuf; + packet->time_usec = time_usec; + packet->wind_x = wind_x; + packet->wind_y = wind_y; + packet->wind_z = wind_z; + packet->var_horiz = var_horiz; + packet->var_vert = var_vert; + packet->wind_alt = wind_alt; + packet->horiz_accuracy = horiz_accuracy; + packet->vert_accuracy = vert_accuracy; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)packet, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)packet, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE WIND_COV UNPACKING + + +/** + * @brief Get field time_usec from wind_cov message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_wind_cov_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field wind_x from wind_cov message + * + * @return Wind in X (NED) direction in m/s + */ +static inline float mavlink_msg_wind_cov_get_wind_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field wind_y from wind_cov message + * + * @return Wind in Y (NED) direction in m/s + */ +static inline float mavlink_msg_wind_cov_get_wind_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field wind_z from wind_cov message + * + * @return Wind in Z (NED) direction in m/s + */ +static inline float mavlink_msg_wind_cov_get_wind_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field var_horiz from wind_cov message + * + * @return Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. + */ +static inline float mavlink_msg_wind_cov_get_var_horiz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field var_vert from wind_cov message + * + * @return Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. + */ +static inline float mavlink_msg_wind_cov_get_var_vert(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field wind_alt from wind_cov message + * + * @return AMSL altitude (m) this measurement was taken at + */ +static inline float mavlink_msg_wind_cov_get_wind_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field horiz_accuracy from wind_cov message + * + * @return Horizontal speed 1-STD accuracy + */ +static inline float mavlink_msg_wind_cov_get_horiz_accuracy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field vert_accuracy from wind_cov message + * + * @return Vertical speed 1-STD accuracy + */ +static inline float mavlink_msg_wind_cov_get_vert_accuracy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Decode a wind_cov message into a struct + * + * @param msg The message to decode + * @param wind_cov C-struct to decode the message contents into + */ +static inline void mavlink_msg_wind_cov_decode(const mavlink_message_t* msg, mavlink_wind_cov_t* wind_cov) +{ +#if MAVLINK_NEED_BYTE_SWAP + wind_cov->time_usec = mavlink_msg_wind_cov_get_time_usec(msg); + wind_cov->wind_x = mavlink_msg_wind_cov_get_wind_x(msg); + wind_cov->wind_y = mavlink_msg_wind_cov_get_wind_y(msg); + wind_cov->wind_z = mavlink_msg_wind_cov_get_wind_z(msg); + wind_cov->var_horiz = mavlink_msg_wind_cov_get_var_horiz(msg); + wind_cov->var_vert = mavlink_msg_wind_cov_get_var_vert(msg); + wind_cov->wind_alt = mavlink_msg_wind_cov_get_wind_alt(msg); + wind_cov->horiz_accuracy = mavlink_msg_wind_cov_get_horiz_accuracy(msg); + wind_cov->vert_accuracy = mavlink_msg_wind_cov_get_vert_accuracy(msg); +#else + memcpy(wind_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_WIND_COV_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/testsuite.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/testsuite.h new file mode 100644 index 0000000..ae50f9a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/common/testsuite.h @@ -0,0 +1,6620 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from common.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef COMMON_TESTSUITE_H +#define COMMON_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL + +static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + + mavlink_test_common(system_id, component_id, last_msg); +} +#endif + + + + +static void mavlink_test_heartbeat(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_heartbeat_t packet_in = { + 963497464,17,84,151,218,3 + }; + mavlink_heartbeat_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.custom_mode = packet_in.custom_mode; + packet1.type = packet_in.type; + packet1.autopilot = packet_in.autopilot; + packet1.base_mode = packet_in.base_mode; + packet1.system_status = packet_in.system_status; + packet1.mavlink_version = packet_in.mavlink_version; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_heartbeat_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_heartbeat_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_heartbeat_pack(system_id, component_id, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); + mavlink_msg_heartbeat_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); + mavlink_msg_heartbeat_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; i + +#ifndef M_PI_2 + #define M_PI_2 ((float)asin(1)) +#endif + +/** + * @file mavlink_conversions.h + * + * These conversion functions follow the NASA rotation standards definition file + * available online. + * + * Their intent is to lower the barrier for MAVLink adopters to use gimbal-lock free + * (both rotation matrices, sometimes called DCM, and quaternions are gimbal-lock free) + * rotation representations. Euler angles (roll, pitch, yaw) will be phased out of the + * protocol as widely as possible. + * + * @author James Goppert + * @author Thomas Gubler + */ + + +/** + * Converts a quaternion to a rotation matrix + * + * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) + * @param dcm a 3x3 rotation matrix + */ +MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3]) +{ + double a = quaternion[0]; + double b = quaternion[1]; + double c = quaternion[2]; + double d = quaternion[3]; + double aSq = a * a; + double bSq = b * b; + double cSq = c * c; + double dSq = d * d; + dcm[0][0] = aSq + bSq - cSq - dSq; + dcm[0][1] = 2 * (b * c - a * d); + dcm[0][2] = 2 * (a * c + b * d); + dcm[1][0] = 2 * (b * c + a * d); + dcm[1][1] = aSq - bSq + cSq - dSq; + dcm[1][2] = 2 * (c * d - a * b); + dcm[2][0] = 2 * (b * d - a * c); + dcm[2][1] = 2 * (a * b + c * d); + dcm[2][2] = aSq - bSq - cSq + dSq; +} + + +/** + * Converts a rotation matrix to euler angles + * + * @param dcm a 3x3 rotation matrix + * @param roll the roll angle in radians + * @param pitch the pitch angle in radians + * @param yaw the yaw angle in radians + */ +MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw) +{ + float phi, theta, psi; + theta = asin(-dcm[2][0]); + + if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) { + phi = 0.0f; + psi = (atan2f(dcm[1][2] - dcm[0][1], + dcm[0][2] + dcm[1][1]) + phi); + + } else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) { + phi = 0.0f; + psi = atan2f(dcm[1][2] - dcm[0][1], + dcm[0][2] + dcm[1][1] - phi); + + } else { + phi = atan2f(dcm[2][1], dcm[2][2]); + psi = atan2f(dcm[1][0], dcm[0][0]); + } + + *roll = phi; + *pitch = theta; + *yaw = psi; +} + + +/** + * Converts a quaternion to euler angles + * + * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) + * @param roll the roll angle in radians + * @param pitch the pitch angle in radians + * @param yaw the yaw angle in radians + */ +MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float* roll, float* pitch, float* yaw) +{ + float dcm[3][3]; + mavlink_quaternion_to_dcm(quaternion, dcm); + mavlink_dcm_to_euler((const float(*)[3])dcm, roll, pitch, yaw); +} + + +/** + * Converts euler angles to a quaternion + * + * @param roll the roll angle in radians + * @param pitch the pitch angle in radians + * @param yaw the yaw angle in radians + * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) + */ +MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4]) +{ + float cosPhi_2 = cosf(roll / 2); + float sinPhi_2 = sinf(roll / 2); + float cosTheta_2 = cosf(pitch / 2); + float sinTheta_2 = sinf(pitch / 2); + float cosPsi_2 = cosf(yaw / 2); + float sinPsi_2 = sinf(yaw / 2); + quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 + + sinPhi_2 * sinTheta_2 * sinPsi_2); + quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 - + cosPhi_2 * sinTheta_2 * sinPsi_2); + quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 + + sinPhi_2 * cosTheta_2 * sinPsi_2); + quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 - + sinPhi_2 * sinTheta_2 * cosPsi_2); +} + + +/** + * Converts a rotation matrix to a quaternion + * Reference: + * - Shoemake, Quaternions, + * http://www.cs.ucr.edu/~vbz/resources/quatut.pdf + * + * @param dcm a 3x3 rotation matrix + * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) + */ +MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4]) +{ + float tr = dcm[0][0] + dcm[1][1] + dcm[2][2]; + if (tr > 0.0f) { + float s = sqrtf(tr + 1.0f); + quaternion[0] = s * 0.5f; + s = 0.5f / s; + quaternion[1] = (dcm[2][1] - dcm[1][2]) * s; + quaternion[2] = (dcm[0][2] - dcm[2][0]) * s; + quaternion[3] = (dcm[1][0] - dcm[0][1]) * s; + } else { + /* Find maximum diagonal element in dcm + * store index in dcm_i */ + int dcm_i = 0; + int i; + for (i = 1; i < 3; i++) { + if (dcm[i][i] > dcm[dcm_i][dcm_i]) { + dcm_i = i; + } + } + + int dcm_j = (dcm_i + 1) % 3; + int dcm_k = (dcm_i + 2) % 3; + + float s = sqrtf((dcm[dcm_i][dcm_i] - dcm[dcm_j][dcm_j] - + dcm[dcm_k][dcm_k]) + 1.0f); + quaternion[dcm_i + 1] = s * 0.5f; + s = 0.5f / s; + quaternion[dcm_j + 1] = (dcm[dcm_i][dcm_j] + dcm[dcm_j][dcm_i]) * s; + quaternion[dcm_k + 1] = (dcm[dcm_k][dcm_i] + dcm[dcm_i][dcm_k]) * s; + quaternion[0] = (dcm[dcm_k][dcm_j] - dcm[dcm_j][dcm_k]) * s; + } +} + + +/** + * Converts euler angles to a rotation matrix + * + * @param roll the roll angle in radians + * @param pitch the pitch angle in radians + * @param yaw the yaw angle in radians + * @param dcm a 3x3 rotation matrix + */ +MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3]) +{ + float cosPhi = cosf(roll); + float sinPhi = sinf(roll); + float cosThe = cosf(pitch); + float sinThe = sinf(pitch); + float cosPsi = cosf(yaw); + float sinPsi = sinf(yaw); + + dcm[0][0] = cosThe * cosPsi; + dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi; + dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi; + + dcm[1][0] = cosThe * sinPsi; + dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi; + dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi; + + dcm[2][0] = -sinThe; + dcm[2][1] = sinPhi * cosThe; + dcm[2][2] = cosPhi * cosThe; +} + +#endif diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/mavlink_helpers.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/mavlink_helpers.h new file mode 100644 index 0000000..0fa87fc --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/mavlink_helpers.h @@ -0,0 +1,676 @@ +#ifndef _MAVLINK_HELPERS_H_ +#define _MAVLINK_HELPERS_H_ + +#include "string.h" +#include "checksum.h" +#include "mavlink_types.h" +#include "mavlink_conversions.h" + +#ifndef MAVLINK_HELPER +#define MAVLINK_HELPER +#endif + +/* + * Internal function to give access to the channel status for each channel + */ +#ifndef MAVLINK_GET_CHANNEL_STATUS +MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan) +{ +#ifdef MAVLINK_EXTERNAL_RX_STATUS + // No m_mavlink_status array defined in function, + // has to be defined externally +#else + static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; +#endif + return &m_mavlink_status[chan]; +} +#endif + +/* + * Internal function to give access to the channel buffer for each channel + */ +#ifndef MAVLINK_GET_CHANNEL_BUFFER +MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) +{ + +#ifdef MAVLINK_EXTERNAL_RX_BUFFER + // No m_mavlink_buffer array defined in function, + // has to be defined externally +#else + static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS]; +#endif + return &m_mavlink_buffer[chan]; +} +#endif + +/** + * @brief Reset the status of a channel. + */ +MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan) +{ + mavlink_status_t *status = mavlink_get_channel_status(chan); + status->parse_state = MAVLINK_PARSE_STATE_IDLE; +} + +/** + * @brief Finalize a MAVLink message with channel assignment + * + * This function calculates the checksum and sets length and aircraft id correctly. + * It assumes that the message id and the payload are already correctly set. This function + * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack + * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. + * + * @param msg Message to finalize + * @param system_id Id of the sending (this) system, 1-127 + * @param length Message length + */ +#if MAVLINK_CRC_EXTRA +MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length, uint8_t crc_extra) +#else +MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length) +#endif +{ + // This code part is the same for all messages; + msg->magic = MAVLINK_STX; + msg->len = length; + msg->sysid = system_id; + msg->compid = component_id; + // One sequence number per channel + msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; + mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1; + msg->checksum = crc_calculate(((const uint8_t*)(msg)) + 3, MAVLINK_CORE_HEADER_LEN); + crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len); +#if MAVLINK_CRC_EXTRA + crc_accumulate(crc_extra, &msg->checksum); +#endif + mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF); + mavlink_ck_b(msg) = (uint8_t)(msg->checksum >> 8); + + return length + MAVLINK_NUM_NON_PAYLOAD_BYTES; +} + + +/** + * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel + */ +#if MAVLINK_CRC_EXTRA +MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length, uint8_t crc_extra) +{ + return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra); +} +#else +MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length) +{ + return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length); +} +#endif + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS +MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); + +/** + * @brief Finalize a MAVLink message with channel assignment and send + */ +#if MAVLINK_CRC_EXTRA +MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, + uint8_t length, uint8_t crc_extra) +#else +MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length) +#endif +{ + uint16_t checksum; + uint8_t buf[MAVLINK_NUM_HEADER_BYTES]; + uint8_t ck[2]; + mavlink_status_t *status = mavlink_get_channel_status(chan); + buf[0] = MAVLINK_STX; + buf[1] = length; + buf[2] = status->current_tx_seq; + buf[3] = mavlink_system.sysid; + buf[4] = mavlink_system.compid; + buf[5] = msgid; + status->current_tx_seq++; + checksum = crc_calculate((const uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN); + crc_accumulate_buffer(&checksum, packet, length); +#if MAVLINK_CRC_EXTRA + crc_accumulate(crc_extra, &checksum); +#endif + ck[0] = (uint8_t)(checksum & 0xFF); + ck[1] = (uint8_t)(checksum >> 8); + + MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); + _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES); + _mavlink_send_uart(chan, packet, length); + _mavlink_send_uart(chan, (const char *)ck, 2); + MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); +} + +/** + * @brief re-send a message over a uart channel + * this is more stack efficient than re-marshalling the message + */ +MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg) +{ + uint8_t ck[2]; + + ck[0] = (uint8_t)(msg->checksum & 0xFF); + ck[1] = (uint8_t)(msg->checksum >> 8); + // XXX use the right sequence here + + MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len); + _mavlink_send_uart(chan, (const char *)&msg->magic, MAVLINK_NUM_HEADER_BYTES); + _mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len); + _mavlink_send_uart(chan, (const char *)ck, 2); + MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len); +} +#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS + +/** + * @brief Pack a message to send it over a serial byte stream + */ +MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg) +{ + memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len); + + uint8_t *ck = buffer + (MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len); + + ck[0] = (uint8_t)(msg->checksum & 0xFF); + ck[1] = (uint8_t)(msg->checksum >> 8); + + return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; +} + +union __mavlink_bitfield { + uint8_t uint8; + int8_t int8; + uint16_t uint16; + int16_t int16; + uint32_t uint32; + int32_t int32; +}; + + +MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg) +{ + crc_init(&msg->checksum); +} + +MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) +{ + crc_accumulate(c, &msg->checksum); +} + +/** + * This is a varient of mavlink_frame_char() but with caller supplied + * parsing buffers. It is useful when you want to create a MAVLink + * parser in a library that doesn't use any global variables + * + * @param rxmsg parsing message buffer + * @param status parsing starus buffer + * @param c The char to parse + * + * @param returnMsg NULL if no message could be decoded, the message data else + * @param returnStats if a message was decoded, this is filled with the channel's stats + * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC + * + * A typical use scenario of this function call is: + * + * @code + * #include + * + * mavlink_message_t msg; + * int chan = 0; + * + * + * while(serial.bytesAvailable > 0) + * { + * uint8_t byte = serial.getNextByte(); + * if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE) + * { + * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); + * } + * } + * + * + * @endcode + */ +MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, + mavlink_status_t* status, + uint8_t c, + mavlink_message_t* r_message, + mavlink_status_t* r_mavlink_status) +{ + /* + default message crc function. You can override this per-system to + put this data in a different memory segment + */ +#if MAVLINK_CRC_EXTRA +#ifndef MAVLINK_MESSAGE_CRC + static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; +#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid] +#endif +#endif + + /* Enable this option to check the length of each message. + This allows invalid messages to be caught much sooner. Use if the transmission + medium is prone to missing (or extra) characters (e.g. a radio that fades in + and out). Only use if the channel will only contain messages types listed in + the headers. + */ +#ifdef MAVLINK_CHECK_MESSAGE_LENGTH +#ifndef MAVLINK_MESSAGE_LENGTH + static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS; +#define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid] +#endif +#endif + + int bufferIndex = 0; + + status->msg_received = MAVLINK_FRAMING_INCOMPLETE; + + switch (status->parse_state) + { + case MAVLINK_PARSE_STATE_UNINIT: + case MAVLINK_PARSE_STATE_IDLE: + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + rxmsg->len = 0; + rxmsg->magic = c; + mavlink_start_checksum(rxmsg); + } + break; + + case MAVLINK_PARSE_STATE_GOT_STX: + if (status->msg_received +/* Support shorter buffers than the + default maximum packet size */ +#if (MAVLINK_MAX_PAYLOAD_LEN < 255) + || c > MAVLINK_MAX_PAYLOAD_LEN +#endif + ) + { + status->buffer_overrun++; + status->parse_error++; + status->msg_received = 0; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + } + else + { + // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 + rxmsg->len = c; + status->packet_idx = 0; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; + } + break; + + case MAVLINK_PARSE_STATE_GOT_LENGTH: + rxmsg->seq = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; + break; + + case MAVLINK_PARSE_STATE_GOT_SEQ: + rxmsg->sysid = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; + break; + + case MAVLINK_PARSE_STATE_GOT_SYSID: + rxmsg->compid = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; + break; + + case MAVLINK_PARSE_STATE_GOT_COMPID: +#ifdef MAVLINK_CHECK_MESSAGE_LENGTH + if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c)) + { + status->parse_error++; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + break; + } +#endif + rxmsg->msgid = c; + mavlink_update_checksum(rxmsg, c); + if (rxmsg->len == 0) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; + } + else + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; + } + break; + + case MAVLINK_PARSE_STATE_GOT_MSGID: + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c; + mavlink_update_checksum(rxmsg, c); + if (status->packet_idx == rxmsg->len) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; + } + break; + + case MAVLINK_PARSE_STATE_GOT_PAYLOAD: +#if MAVLINK_CRC_EXTRA + mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid)); +#endif + if (c != (rxmsg->checksum & 0xFF)) { + status->parse_state = MAVLINK_PARSE_STATE_GOT_BAD_CRC1; + } else { + status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; + } + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c; + break; + + case MAVLINK_PARSE_STATE_GOT_CRC1: + case MAVLINK_PARSE_STATE_GOT_BAD_CRC1: + if (status->parse_state == MAVLINK_PARSE_STATE_GOT_BAD_CRC1 || c != (rxmsg->checksum >> 8)) { + // got a bad CRC message + status->msg_received = MAVLINK_FRAMING_BAD_CRC; + } else { + // Successfully got message + status->msg_received = MAVLINK_FRAMING_OK; + } + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c; + memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); + break; + } + + bufferIndex++; + // If a message has been sucessfully decoded, check index + if (status->msg_received == MAVLINK_FRAMING_OK) + { + //while(status->current_seq != rxmsg->seq) + //{ + // status->packet_rx_drop_count++; + // status->current_seq++; + //} + status->current_rx_seq = rxmsg->seq; + // Initial condition: If no packet has been received so far, drop count is undefined + if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; + // Count this packet as received + status->packet_rx_success_count++; + } + + r_message->len = rxmsg->len; // Provide visibility on how far we are into current msg + r_mavlink_status->parse_state = status->parse_state; + r_mavlink_status->packet_idx = status->packet_idx; + r_mavlink_status->current_rx_seq = status->current_rx_seq+1; + r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; + r_mavlink_status->packet_rx_drop_count = status->parse_error; + status->parse_error = 0; + + if (status->msg_received == MAVLINK_FRAMING_BAD_CRC) { + /* + the CRC came out wrong. We now need to overwrite the + msg CRC with the one on the wire so that if the + caller decides to forward the message anyway that + mavlink_msg_to_send_buffer() won't overwrite the + checksum + */ + r_message->checksum = _MAV_PAYLOAD(rxmsg)[status->packet_idx] | (_MAV_PAYLOAD(rxmsg)[status->packet_idx+1]<<8); + } + + return status->msg_received; +} + +/** + * This is a convenience function which handles the complete MAVLink parsing. + * the function will parse one byte at a time and return the complete packet once + * it could be successfully decoded. This function will return 0, 1 or + * 2 (MAVLINK_FRAMING_INCOMPLETE, MAVLINK_FRAMING_OK or MAVLINK_FRAMING_BAD_CRC) + * + * Messages are parsed into an internal buffer (one for each channel). When a complete + * message is received it is copies into *returnMsg and the channel's status is + * copied into *returnStats. + * + * @param chan ID of the current channel. This allows to parse different channels with this function. + * a channel is not a physical message channel like a serial port, but a logic partition of + * the communication streams in this case. COMM_NB is the limit for the number of channels + * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows + * @param c The char to parse + * + * @param returnMsg NULL if no message could be decoded, the message data else + * @param returnStats if a message was decoded, this is filled with the channel's stats + * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC + * + * A typical use scenario of this function call is: + * + * @code + * #include + * + * mavlink_message_t msg; + * int chan = 0; + * + * + * while(serial.bytesAvailable > 0) + * { + * uint8_t byte = serial.getNextByte(); + * if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE) + * { + * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); + * } + * } + * + * + * @endcode + */ +MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) +{ + return mavlink_frame_char_buffer(mavlink_get_channel_buffer(chan), + mavlink_get_channel_status(chan), + c, + r_message, + r_mavlink_status); +} + + +/** + * This is a convenience function which handles the complete MAVLink parsing. + * the function will parse one byte at a time and return the complete packet once + * it could be successfully decoded. This function will return 0 or 1. + * + * Messages are parsed into an internal buffer (one for each channel). When a complete + * message is received it is copies into *returnMsg and the channel's status is + * copied into *returnStats. + * + * @param chan ID of the current channel. This allows to parse different channels with this function. + * a channel is not a physical message channel like a serial port, but a logic partition of + * the communication streams in this case. COMM_NB is the limit for the number of channels + * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows + * @param c The char to parse + * + * @param returnMsg NULL if no message could be decoded, the message data else + * @param returnStats if a message was decoded, this is filled with the channel's stats + * @return 0 if no message could be decoded or bad CRC, 1 on good message and CRC + * + * A typical use scenario of this function call is: + * + * @code + * #include + * + * mavlink_message_t msg; + * int chan = 0; + * + * + * while(serial.bytesAvailable > 0) + * { + * uint8_t byte = serial.getNextByte(); + * if (mavlink_parse_char(chan, byte, &msg)) + * { + * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); + * } + * } + * + * + * @endcode + */ +MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) +{ + uint8_t msg_received = mavlink_frame_char(chan, c, r_message, r_mavlink_status); + if (msg_received == MAVLINK_FRAMING_BAD_CRC) { + // we got a bad CRC. Treat as a parse failure + mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); + mavlink_status_t* status = mavlink_get_channel_status(chan); + status->parse_error++; + status->msg_received = MAVLINK_FRAMING_INCOMPLETE; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + rxmsg->len = 0; + mavlink_start_checksum(rxmsg); + } + return 0; + } + return msg_received; +} + +/** + * @brief Put a bitfield of length 1-32 bit into the buffer + * + * @param b the value to add, will be encoded in the bitfield + * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. + * @param packet_index the position in the packet (the index of the first byte to use) + * @param bit_index the position in the byte (the index of the first bit to use) + * @param buffer packet buffer to write into + * @return new position of the last used byte in the buffer + */ +MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer) +{ + uint16_t bits_remain = bits; + // Transform number into network order + int32_t v; + uint8_t i_bit_index, i_byte_index, curr_bits_n; +#if MAVLINK_NEED_BYTE_SWAP + union { + int32_t i; + uint8_t b[4]; + } bin, bout; + bin.i = b; + bout.b[0] = bin.b[3]; + bout.b[1] = bin.b[2]; + bout.b[2] = bin.b[1]; + bout.b[3] = bin.b[0]; + v = bout.i; +#else + v = b; +#endif + + // buffer in + // 01100000 01000000 00000000 11110001 + // buffer out + // 11110001 00000000 01000000 01100000 + + // Existing partly filled byte (four free slots) + // 0111xxxx + + // Mask n free bits + // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1 + // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1 + + // Shift n bits into the right position + // out = in >> n; + + // Mask and shift bytes + i_bit_index = bit_index; + i_byte_index = packet_index; + if (bit_index > 0) + { + // If bits were available at start, they were available + // in the byte before the current index + i_byte_index--; + } + + // While bits have not been packed yet + while (bits_remain > 0) + { + // Bits still have to be packed + // there can be more than 8 bits, so + // we might have to pack them into more than one byte + + // First pack everything we can into the current 'open' byte + //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 + //FIXME + if (bits_remain <= (uint8_t)(8 - i_bit_index)) + { + // Enough space + curr_bits_n = (uint8_t)bits_remain; + } + else + { + curr_bits_n = (8 - i_bit_index); + } + + // Pack these n bits into the current byte + // Mask out whatever was at that position with ones (xxx11111) + buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n)); + // Put content to this position, by masking out the non-used part + buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v); + + // Increment the bit index + i_bit_index += curr_bits_n; + + // Now proceed to the next byte, if necessary + bits_remain -= curr_bits_n; + if (bits_remain > 0) + { + // Offer another 8 bits / one byte + i_byte_index++; + i_bit_index = 0; + } + } + + *r_bit_index = i_bit_index; + // If a partly filled byte is present, mark this as consumed + if (i_bit_index != 7) i_byte_index++; + return i_byte_index - packet_index; +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +// To make MAVLink work on your MCU, define comm_send_ch() if you wish +// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a +// whole packet at a time + +/* + +#include "mavlink_types.h" + +void comm_send_ch(mavlink_channel_t chan, uint8_t ch) +{ + if (chan == MAVLINK_COMM_0) + { + uart0_transmit(ch); + } + if (chan == MAVLINK_COMM_1) + { + uart1_transmit(ch); + } +} + */ + +MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len) +{ +#ifdef MAVLINK_SEND_UART_BYTES + /* this is the more efficient approach, if the platform + defines it */ + MAVLINK_SEND_UART_BYTES(chan, (const uint8_t *)buf, len); +#else + /* fallback to one byte at a time */ + uint16_t i; + for (i = 0; i < len; i++) { + comm_send_ch(chan, (uint8_t)buf[i]); + } +#endif +} +#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS + +#endif /* _MAVLINK_HELPERS_H_ */ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/mavlink_types.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/mavlink_types.h new file mode 100644 index 0000000..0a98ccc --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/mavlink_types.h @@ -0,0 +1,228 @@ +#ifndef MAVLINK_TYPES_H_ +#define MAVLINK_TYPES_H_ + +// Visual Studio versions before 2010 don't have stdint.h, so we just error out. +#if (defined _MSC_VER) && (_MSC_VER < 1600) +#error "The C-MAVLink implementation requires Visual Studio 2010 or greater" +#endif + +#include + +// Macro to define packed structures +#ifdef __GNUC__ + #define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed)) +#else + #define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) ) +#endif + +#ifndef MAVLINK_MAX_PAYLOAD_LEN +// it is possible to override this, but be careful! +#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length +#endif + +#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte) +#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum +#define MAVLINK_NUM_CHECKSUM_BYTES 2 +#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) + +#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length + +#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 +#define MAVLINK_EXTENDED_HEADER_LEN 14 + +#if (defined _MSC_VER) || ((defined __APPLE__) && (defined __MACH__)) || (defined __linux__) + /* full fledged 32bit++ OS */ + #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507 +#else + /* small microcontrollers */ + #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048 +#endif + +#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES) + + +/** + * Old-style 4 byte param union + * + * This struct is the data format to be used when sending + * parameters. The parameter should be copied to the native + * type (without type conversion) + * and re-instanted on the receiving side using the + * native type as well. + */ +MAVPACKED( +typedef struct param_union { + union { + float param_float; + int32_t param_int32; + uint32_t param_uint32; + int16_t param_int16; + uint16_t param_uint16; + int8_t param_int8; + uint8_t param_uint8; + uint8_t bytes[4]; + }; + uint8_t type; +}) mavlink_param_union_t; + + +/** + * New-style 8 byte param union + * mavlink_param_union_double_t will be 8 bytes long, and treated as needing 8 byte alignment for the purposes of MAVLink 1.0 field ordering. + * The mavlink_param_union_double_t will be treated as a little-endian structure. + * + * If is_double is 1 then the type is a double, and the remaining 63 bits are the double, with the lowest bit of the mantissa zero. + * The intention is that by replacing the is_double bit with 0 the type can be directly used as a double (as the is_double bit corresponds to the + * lowest mantissa bit of a double). If is_double is 0 then mavlink_type gives the type in the union. + * The mavlink_types.h header will also need to have shifts/masks to define the bit boundaries in the above, + * as bitfield ordering isn’t consistent between platforms. The above is intended to be for gcc on x86, + * which should be the same as gcc on little-endian arm. When using shifts/masks the value will be treated as a 64 bit unsigned number, + * and the bits pulled out using the shifts/masks. +*/ +MAVPACKED( +typedef struct param_union_extended { + union { + struct { + uint8_t is_double:1; + uint8_t mavlink_type:7; + union { + char c; + uint8_t uint8; + int8_t int8; + uint16_t uint16; + int16_t int16; + uint32_t uint32; + int32_t int32; + float f; + uint8_t align[7]; + }; + }; + uint8_t data[8]; + }; +}) mavlink_param_union_double_t; + +/** + * This structure is required to make the mavlink_send_xxx convenience functions + * work, as it tells the library what the current system and component ID are. + */ +MAVPACKED( +typedef struct __mavlink_system { + uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function + uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function +}) mavlink_system_t; + +MAVPACKED( +typedef struct __mavlink_message { + uint16_t checksum; ///< sent at end of packet + uint8_t magic; ///< protocol magic marker + uint8_t len; ///< Length of payload + uint8_t seq; ///< Sequence of packet + uint8_t sysid; ///< ID of message sender system/aircraft + uint8_t compid; ///< ID of the message sender component + uint8_t msgid; ///< ID of message in payload + uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; +}) mavlink_message_t; + +MAVPACKED( +typedef struct __mavlink_extended_message { + mavlink_message_t base_msg; + int32_t extended_payload_len; ///< Length of extended payload if any + uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN]; +}) mavlink_extended_message_t; + +typedef enum { + MAVLINK_TYPE_CHAR = 0, + MAVLINK_TYPE_UINT8_T = 1, + MAVLINK_TYPE_INT8_T = 2, + MAVLINK_TYPE_UINT16_T = 3, + MAVLINK_TYPE_INT16_T = 4, + MAVLINK_TYPE_UINT32_T = 5, + MAVLINK_TYPE_INT32_T = 6, + MAVLINK_TYPE_UINT64_T = 7, + MAVLINK_TYPE_INT64_T = 8, + MAVLINK_TYPE_FLOAT = 9, + MAVLINK_TYPE_DOUBLE = 10 +} mavlink_message_type_t; + +#define MAVLINK_MAX_FIELDS 64 + +typedef struct __mavlink_field_info { + const char *name; // name of this field + const char *print_format; // printing format hint, or NULL + mavlink_message_type_t type; // type of this field + unsigned int array_length; // if non-zero, field is an array + unsigned int wire_offset; // offset of each field in the payload + unsigned int structure_offset; // offset in a C structure +} mavlink_field_info_t; + +// note that in this structure the order of fields is the order +// in the XML file, not necessary the wire order +typedef struct __mavlink_message_info { + const char *name; // name of the message + unsigned num_fields; // how many fields in this message + mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information +} mavlink_message_info_t; + +#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0]))) +#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0]))) + +// checksum is immediately after the payload bytes +#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) +#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) + +typedef enum { + MAVLINK_COMM_0, + MAVLINK_COMM_1, + MAVLINK_COMM_2, + MAVLINK_COMM_3 +} mavlink_channel_t; + +/* + * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number + * of buffers they will use. If more are used, then the result will be + * a stack overrun + */ +#ifndef MAVLINK_COMM_NUM_BUFFERS +#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) +# define MAVLINK_COMM_NUM_BUFFERS 16 +#else +# define MAVLINK_COMM_NUM_BUFFERS 4 +#endif +#endif + +typedef enum { + MAVLINK_PARSE_STATE_UNINIT=0, + MAVLINK_PARSE_STATE_IDLE, + MAVLINK_PARSE_STATE_GOT_STX, + MAVLINK_PARSE_STATE_GOT_SEQ, + MAVLINK_PARSE_STATE_GOT_LENGTH, + MAVLINK_PARSE_STATE_GOT_SYSID, + MAVLINK_PARSE_STATE_GOT_COMPID, + MAVLINK_PARSE_STATE_GOT_MSGID, + MAVLINK_PARSE_STATE_GOT_PAYLOAD, + MAVLINK_PARSE_STATE_GOT_CRC1, + MAVLINK_PARSE_STATE_GOT_BAD_CRC1 +} mavlink_parse_state_t; ///< The state machine for the comm parser + +typedef enum { + MAVLINK_FRAMING_INCOMPLETE=0, + MAVLINK_FRAMING_OK=1, + MAVLINK_FRAMING_BAD_CRC=2 +} mavlink_framing_t; + +typedef struct __mavlink_status { + uint8_t msg_received; ///< Number of received messages + uint8_t buffer_overrun; ///< Number of buffer overruns + uint8_t parse_error; ///< Number of parse errors + mavlink_parse_state_t parse_state; ///< Parsing state machine + uint8_t packet_idx; ///< Index in current packet + uint8_t current_rx_seq; ///< Sequence number of last packet received + uint8_t current_tx_seq; ///< Sequence number of last packet sent + uint16_t packet_rx_success_count; ///< Received packets + uint16_t packet_rx_drop_count; ///< Number of packet drops +} mavlink_status_t; + +#define MAVLINK_BIG_ENDIAN 0 +#define MAVLINK_LITTLE_ENDIAN 1 + +#endif /* MAVLINK_TYPES_H_ */ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/ASLUAV.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/ASLUAV.xml new file mode 100644 index 0000000..0c3e394 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/ASLUAV.xml @@ -0,0 +1,176 @@ + + + + + common.xml + + + + + Mission command to reset Maximum Power Point Tracker (MPPT) + MPPT number + Empty + Empty + Empty + Empty + Empty + Empty + + + Mission command to perform a power cycle on payload + Complete power cycle + VISensor power cycle + Empty + Empty + Empty + Empty + Empty + + + + + + Voltage and current sensor data + Power board voltage sensor reading in volts + Power board current sensor reading in amps + Board current sensor 1 reading in amps + Board current sensor 2 reading in amps + + + Maximum Power Point Tracker (MPPT) sensor data for solar module power performance tracking + MPPT last timestamp + MPPT1 voltage + MPPT1 current + MPPT1 pwm + MPPT1 status + MPPT2 voltage + MPPT2 current + MPPT2 pwm + MPPT2 status + MPPT3 voltage + MPPT3 current + MPPT3 pwm + MPPT3 status + + + ASL-fixed-wing controller data + Timestamp + ASLCTRL control-mode (manual, stabilized, auto, etc...) + See sourcecode for a description of these values... + + + Pitch angle [deg] + Pitch angle reference[deg] + + + + + + + Airspeed reference [m/s] + + Yaw angle [deg] + Yaw angle reference[deg] + Roll angle [deg] + Roll angle reference[deg] + + + + + + + + + ASL-fixed-wing controller debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + + + Extended state information for ASLUAVs + Status of the position-indicator LEDs + Status of the IRIDIUM satellite communication system + Status vector for up to 8 servos + Motor RPM + + + + Extended EKF state estimates for ASLUAVs + Time since system start [us] + Magnitude of wind velocity (in lateral inertial plane) [m/s] + Wind heading angle from North [rad] + Z (Down) component of inertial wind velocity [m/s] + Magnitude of air velocity [m/s] + Sideslip angle [rad] + Angle of attack [rad] + + + Off-board controls/commands for ASLUAVs + Time since system start [us] + Elevator command [~] + Throttle command [~] + Throttle 2 command [~] + Left aileron command [~] + Right aileron command [~] + Rudder command [~] + Off-board computer status + + + Atmospheric sensors (temperature, humidity, ...) + Ambient temperature [degrees Celsius] + Relative humidity [%] + + + Battery pack monitoring data for Li-Ion batteries + Battery pack temperature in [deg C] + Battery pack voltage in [mV] + Battery pack current in [mA] + Battery pack state-of-charge + Battery monitor status report bits in Hex + Battery monitor serial number in Hex + Battery monitor sensor host FET control in Hex + Battery pack cell 1 voltage in [mV] + Battery pack cell 2 voltage in [mV] + Battery pack cell 3 voltage in [mV] + Battery pack cell 4 voltage in [mV] + Battery pack cell 5 voltage in [mV] + Battery pack cell 6 voltage in [mV] + + + Fixed-wing soaring (i.e. thermal seeking) data + Timestamp [ms] + Timestamp since last mode change[ms] + Updraft speed at current/local airplane position [m/s] + Thermal core updraft strength [m/s] + Thermal radius [m] + Thermal center latitude [deg] + Thermal center longitude [deg] + Variance W + Variance R + Variance Lat + Variance Lon + Suggested loiter radius [m] + Control Mode [-] + Data valid [-] + + + Monitoring of sensorpod status + Timestamp in linuxtime [ms] (since 1.1.1970) + Rate of ROS topic 1 + Rate of ROS topic 2 + Rate of ROS topic 3 + Rate of ROS topic 4 + Number of recording nodes + Temperature of sensorpod CPU in [deg C] + Free space available in recordings directory in [Gb] * 1e2 + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/ardupilotmega.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/ardupilotmega.xml new file mode 100644 index 0000000..e04c0b1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/ardupilotmega.xml @@ -0,0 +1,1564 @@ + + + common.xml + + + + + + Mission command to perform motor test + motor sequence number (a number from 1 to max number of motors on the vehicle) + throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum) + throttle + timeout (in seconds) + Empty + Empty + Empty + + + + Mission command to operate EPM gripper + gripper number (a number from 1 to max number of grippers on the vehicle) + gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum) + Empty + Empty + Empty + Empty + Empty + + + + Enable/disable autotune + enable (1: enable, 0:disable) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up. + altitude (m) + descent speed (m/s) + Wiggle Time (s) + Empty + Empty + Empty + Empty + + + + A system wide power-off event has been initiated. + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + + FLY button has been clicked. + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + FLY button has been held for 1.5 seconds. + Takeoff altitude + Empty + Empty + Empty + Empty + Empty + Empty + + + + PAUSE button has been clicked. + 1 if Solo is in a shot mode, 0 otherwise + Empty + Empty + Empty + Empty + Empty + Empty + + + + Initiate a magnetometer calibration + uint8_t bitmask of magnetometers (0 means all) + Automatically retry on failure (0=no retry, 1=retry). + Save without user input (0=require input, 1=autosave). + Delay (seconds) + Autoreboot (0=user reboot, 1=autoreboot) + Empty + Empty + + + + Initiate a magnetometer calibration + uint8_t bitmask of magnetometers (0 means all) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Cancel a running magnetometer calibration + uint8_t bitmask of magnetometers (0 means all) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Reply with the version banner + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + Causes the gimbal to reset and boot as if it was just powered on + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + Command autopilot to get into factory test/diagnostic mode + 0 means get out of test mode, 1 means get into test mode + Empty + Empty + Empty + Empty + Empty + Empty + + + + Reports progress and success or failure of gimbal axis calibration procedure + Gimbal axis we're reporting calibration progress for + Current calibration progress for this axis, 0x64=100% + Status of the calibration + Empty + Empty + Empty + Empty + + + + Starts commutation calibration on the gimbal + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + Erases gimbal application and parameters + Magic number + Magic number + Magic number + Magic number + Magic number + Magic number + Magic number + + + + + + + pre-initialization + + + + disabled + + + + checking limits + + + + a limit has been breached + + + + taking action eg. RTL + + + + we're no longer in breach of a limit + + + + + + + pre-initialization + + + + disabled + + + + checking limits + + + + + + Flags in RALLY_POINT message + + Flag set when requiring favorable winds for landing. + + + + Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land. + + + + + + + Disable parachute release + + + + Enable parachute release + + + + Release parachute + + + + + + + throttle as a percentage from 0 ~ 100 + + + + throttle as an absolute PWM value (normally in range of 1000~2000) + + + + throttle pass-through from pilot's transmitter + + + + + + Gripper actions. + + gripper release of cargo + + + + gripper grabs onto cargo + + + + + + + Camera heartbeat, announce camera component ID at 1hz + + + + Camera image triggered + + + + Camera connection lost + + + + Camera unknown error + + + + Camera battery low. Parameter p1 shows reported voltage + + + + Camera storage low. Parameter p1 shows reported shots remaining + + + + Camera storage low. Parameter p1 shows reported video minutes remaining + + + + + + + Shooting photos, not video + + + + Shooting video, not stills + + + + Unable to achieve requested exposure (e.g. shutter speed too low) + + + + Closed loop feedback from camera, we know for sure it has successfully taken a picture + + + + Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture + + + + + + + Gimbal is powered on but has not started initializing yet + + + + Gimbal is currently running calibration on the pitch axis + + + + Gimbal is currently running calibration on the roll axis + + + + Gimbal is currently running calibration on the yaw axis + + + + Gimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter + + + + Gimbal is actively stabilizing + + + + Gimbal is relaxed because it missed more than 10 expected rate command messages in a row. Gimbal will move back to active mode when it receives a new rate command + + + + + + Gimbal yaw axis + + + + Gimbal pitch axis + + + + Gimbal roll axis + + + + + + Axis calibration is in progress + + + + Axis calibration succeeded + + + + Axis calibration failed + + + + + + Whether or not this axis requires calibration is unknown at this time + + + + This axis requires calibration + + + + This axis does not require calibration + + + + + + + No GoPro connected + + + + The detected GoPro is not HeroBus compatible + + + + A HeroBus compatible GoPro is connected + + + + An unrecoverable error was encountered with the connected GoPro, it may require a power cycle + + + + + + + GoPro is currently recording + + + + + + The write message with ID indicated succeeded + + + + The write message with ID indicated failed + + + + + + (Get/Set) + + + + (Get/Set) + + + + (___/Set) + + + + (Get/___) + + + + (Get/___) + + + + (Get/Set) + + + + + (Get/Set) + + + + (Get/Set) + + + + (Get/Set) + + + + (Get/Set) + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) + + + + + (Get/Set) + + + + + + Video mode + + + + Photo mode + + + + Burst mode, hero 3+ only + + + + Time lapse mode, hero 3+ only + + + + Multi shot mode, hero 4 only + + + + Playback mode, hero 4 only, silver only except when LCD or HDMI is connected to black + + + + Playback mode, hero 4 only + + + + Mode not yet known + + + + + + 848 x 480 (480p) + + + + 1280 x 720 (720p) + + + + 1280 x 960 (960p) + + + + 1920 x 1080 (1080p) + + + + 1920 x 1440 (1440p) + + + + 2704 x 1440 (2.7k-17:9) + + + + 2704 x 1524 (2.7k-16:9) + + + + 2704 x 2028 (2.7k-4:3) + + + + 3840 x 2160 (4k-16:9) + + + + 4096 x 2160 (4k-17:9) + + + + 1280 x 720 (720p-SuperView) + + + + 1920 x 1080 (1080p-SuperView) + + + + 2704 x 1520 (2.7k-SuperView) + + + + 3840 x 2160 (4k-SuperView) + + + + + + 12 FPS + + + + 15 FPS + + + + 24 FPS + + + + 25 FPS + + + + 30 FPS + + + + 48 FPS + + + + 50 FPS + + + + 60 FPS + + + + 80 FPS + + + + 90 FPS + + + + 100 FPS + + + + 120 FPS + + + + 240 FPS + + + + 12.5 FPS + + + + + + 0x00: Wide + + + + 0x01: Medium + + + + 0x02: Narrow + + + + + + 0=NTSC, 1=PAL + + + + + + 5MP Medium + + + + 7MP Medium + + + + 7MP Wide + + + + 10MP Wide + + + + 12MP Wide + + + + + + Auto + + + + 3000K + + + + 5500K + + + + 6500K + + + + Camera Raw + + + + + + Auto + + + + Neutral + + + + + + ISO 400 + + + + ISO 800 (Only Hero 4) + + + + ISO 1600 + + + + ISO 3200 (Only Hero 4) + + + + ISO 6400 + + + + + + Low Sharpness + + + + Medium Sharpness + + + + High Sharpness + + + + + + -5.0 EV (Hero 3+ Only) + + + + -4.5 EV (Hero 3+ Only) + + + + -4.0 EV (Hero 3+ Only) + + + + -3.5 EV (Hero 3+ Only) + + + + -3.0 EV (Hero 3+ Only) + + + + -2.5 EV (Hero 3+ Only) + + + + -2.0 EV + + + + -1.5 EV + + + + -1.0 EV + + + + -0.5 EV + + + + 0.0 EV + + + + +0.5 EV + + + + +1.0 EV + + + + +1.5 EV + + + + +2.0 EV + + + + +2.5 EV (Hero 3+ Only) + + + + +3.0 EV (Hero 3+ Only) + + + + +3.5 EV (Hero 3+ Only) + + + + +4.0 EV (Hero 3+ Only) + + + + +4.5 EV (Hero 3+ Only) + + + + +5.0 EV (Hero 3+ Only) + + + + + + Charging disabled + + + + Charging enabled + + + + + + Unknown gopro model + + + + Hero 3+ Silver (HeroBus not supported by GoPro) + + + + Hero 3+ Black + + + + Hero 4 Silver + + + + Hero 4 Black + + + + + + 3 Shots / 1 Second + + + + 5 Shots / 1 Second + + + + 10 Shots / 1 Second + + + + 10 Shots / 2 Second + + + + 10 Shots / 3 Second (Hero 4 Only) + + + + 30 Shots / 1 Second + + + + 30 Shots / 2 Second + + + + 30 Shots / 3 Second + + + + 30 Shots / 6 Second + + + + + + + LED patterns off (return control to regular vehicle control) + + + + LEDs show pattern during firmware update + + + + Custom Pattern using custom bytes fields + + + + + + Flags in EKF_STATUS message + + set if EKF's attitude estimate is good + + + + set if EKF's horizontal velocity estimate is good + + + + set if EKF's vertical velocity estimate is good + + + + set if EKF's horizontal position (relative) estimate is good + + + + set if EKF's horizontal position (absolute) estimate is good + + + + set if EKF's vertical position (absolute) estimate is good + + + + set if EKF's vertical position (above ground) estimate is good + + + + EKF is in constant position mode and does not know it's absolute or relative position + + + + set if EKF's predicted horizontal position (relative) estimate is good + + + + set if EKF's predicted horizontal position (absolute) estimate is good + + + + + + + + + + + + + + + + + + + + + + Special ACK block numbers control activation of dataflash log streaming + + + + UAV to stop sending DataFlash blocks + + + + + UAV to start sending DataFlash blocks + + + + + + + Possible remote log data block statuses + + This block has NOT been received + + + + This block has been received + + + + + + + Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process. + magnetometer X offset + magnetometer Y offset + magnetometer Z offset + magnetic declination (radians) + raw pressure from barometer + raw temperature from barometer + gyro X calibration + gyro Y calibration + gyro Z calibration + accel X calibration + accel Y calibration + accel Z calibration + + + + Deprecated. Use MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS instead. Set the magnetometer offsets + System ID + Component ID + magnetometer X offset + magnetometer Y offset + magnetometer Z offset + + + + state of APM memory + heap top + free memory + + + + raw ADC output + ADC output 1 + ADC output 2 + ADC output 3 + ADC output 4 + ADC output 5 + ADC output 6 + + + + + Configure on-board Camera Control System. + System ID + Component ID + Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) + Divisor number //e.g. 1000 means 1/1000 (0 means ignore) + F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) + ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) + Exposure type enumeration from 1 to N (0 means ignore) + Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + Extra parameters enumeration (0 means ignore) + Correspondent value to given extra_param + + + + Control on-board Camera Control System to take shots. + System ID + Component ID + 0: stop, 1: start or keep it up //Session control e.g. show/hide lens + 1 to N //Zoom's absolute position (0 means ignore) + -100 to 100 //Zooming step value to offset zoom from the current position + 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus + 0: ignore, 1: shot or start filming + Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + Extra parameters enumeration (0 means ignore) + Correspondent value to given extra_param + + + + + Message to configure a camera mount, directional antenna, etc. + System ID + Component ID + mount operating mode (see MAV_MOUNT_MODE enum) + (1 = yes, 0 = no) + (1 = yes, 0 = no) + (1 = yes, 0 = no) + + + + Message to control a camera mount, directional antenna, etc. + System ID + Component ID + pitch(deg*100) or lat, depending on mount mode + roll(deg*100) or lon depending on mount mode + yaw(deg*100) or alt (in cm) depending on mount mode + if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) + + + + Message with some status from APM to GCS about camera or antenna mount + System ID + Component ID + pitch(deg*100) + roll(deg*100) + yaw(deg*100) + + + + + A fence point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS + System ID + Component ID + point index (first point is 1, 0 is for return point) + total number of points (for sanity checking) + Latitude of point + Longitude of point + + + + Request a current fence point from MAV + System ID + Component ID + point index (first point is 1, 0 is for return point) + + + + Status of geo-fencing. Sent in extended status stream when fencing enabled + 0 if currently inside fence, 1 if outside + number of fence breaches + last breach type (see FENCE_BREACH_* enum) + time of last breach in milliseconds since boot + + + + Status of DCM attitude estimator + X gyro drift estimate rad/s + Y gyro drift estimate rad/s + Z gyro drift estimate rad/s + average accel_weight + average renormalisation value + average error_roll_pitch value + average error_yaw value + + + + Status of simulation environment, if used + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + X acceleration m/s/s + Y acceleration m/s/s + Z acceleration m/s/s + Angular speed around X axis rad/s + Angular speed around Y axis rad/s + Angular speed around Z axis rad/s + Latitude in degrees * 1E7 + Longitude in degrees * 1E7 + + + + Status of key hardware + board voltage (mV) + I2C error count + + + + Status generated by radio + local signal strength + remote signal strength + how full the tx buffer is as a percentage + background noise level + remote background noise level + receive errors + count of error corrected packets + + + + + Status of AP_Limits. Sent in extended status stream when AP_Limits is enabled + state of AP_Limits, (see enum LimitState, LIMITS_STATE) + time of last breach in milliseconds since boot + time of last recovery action in milliseconds since boot + time of last successful recovery in milliseconds since boot + time of last all-clear in milliseconds since boot + number of fence breaches + AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE) + AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE) + AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE) + + + + Wind estimation + wind direction that wind is coming from (degrees) + wind speed in ground plane (m/s) + vertical wind speed (m/s) + + + + Data packet, size 16 + data type + data length + raw data + + + + Data packet, size 32 + data type + data length + raw data + + + + Data packet, size 64 + data type + data length + raw data + + + + Data packet, size 96 + data type + data length + raw data + + + + Rangefinder reporting + distance in meters + raw voltage if available, zero otherwise + + + + Airspeed auto-calibration + GPS velocity north m/s + GPS velocity east m/s + GPS velocity down m/s + Differential pressure pascals + Estimated to true airspeed ratio + Airspeed ratio + EKF state x + EKF state y + EKF state z + EKF Pax + EKF Pby + EKF Pcz + + + + + A rally point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS + System ID + Component ID + point index (first point is 0) + total number of points (for sanity checking) + Latitude of point in degrees * 1E7 + Longitude of point in degrees * 1E7 + Transit / loiter altitude in meters relative to home + + Break altitude in meters relative to home + Heading to aim for when landing. In centi-degrees. + See RALLY_FLAGS enum for definition of the bitmask. + + + + Request a current rally point from MAV. MAV should respond with a RALLY_POINT message. MAV should not respond if the request is invalid. + System ID + Component ID + point index (first point is 0) + + + + Status of compassmot calibration + throttle (percent*10) + current (amps) + interference (percent) + Motor Compensation X + Motor Compensation Y + Motor Compensation Z + + + + + Status of secondary AHRS filter if available + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Altitude (MSL) + Latitude in degrees * 1E7 + Longitude in degrees * 1E7 + + + + + Camera Event + Image timestamp (microseconds since UNIX epoch, according to camera clock) + System ID + + Camera ID + + Image index + + See CAMERA_STATUS_TYPES enum for definition of the bitmask + Parameter 1 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + Parameter 2 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + Parameter 3 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + Parameter 4 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + + + + + Camera Capture Feedback + Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB) + System ID + + Camera ID + + Image index + + Latitude in (deg * 1E7) + Longitude in (deg * 1E7) + Altitude Absolute (meters AMSL) + Altitude Relative (meters above HOME location) + Camera Roll angle (earth frame, degrees, +-180) + + Camera Pitch angle (earth frame, degrees, +-180) + + Camera Yaw (earth frame, degrees, 0-360, true) + + Focal Length (mm) + + See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask + + + + + 2nd Battery status + voltage in millivolts + Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + + + + Status of third AHRS filter if available. This is for ANU research group (Ali and Sean) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Altitude (MSL) + Latitude in degrees * 1E7 + Longitude in degrees * 1E7 + test variable1 + test variable2 + test variable3 + test variable4 + + + + Request the autopilot version from the system/component. + System ID + Component ID + + + + + Send a block of log data to remote location + System ID + Component ID + log data block sequence number + log data block + + + + Send Status of each log block that autopilot board might have sent + System ID + Component ID + log data block sequence number + log data block status + + + + Control vehicle LEDs + System ID + Component ID + Instance (LED instance to control or 255 for all LEDs) + Pattern (see LED_PATTERN_ENUM) + Custom Byte Length + Custom Bytes + + + + Reports progress of compass calibration. + Compass being calibrated + Bitmask of compasses being calibrated + Status (see MAG_CAL_STATUS enum) + Attempt number + Completion percentage + Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid) + Body frame direction vector for display + Body frame direction vector for display + Body frame direction vector for display + + + + Reports results of completed compass calibration. Sent until MAG_CAL_ACK received. + Compass being calibrated + Bitmask of compasses being calibrated + Status (see MAG_CAL_STATUS enum) + 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters + RMS milligauss residuals + X offset + Y offset + Z offset + X diagonal (matrix 11) + Y diagonal (matrix 22) + Z diagonal (matrix 33) + X off-diagonal (matrix 12 and 21) + Y off-diagonal (matrix 13 and 31) + Z off-diagonal (matrix 32 and 23) + + + + + EKF Status message including flags and variances + Flags + + Velocity variance + + Horizontal Position variance + Vertical Position variance + Compass variance + Terrain Altitude variance + + + + + PID tuning information + axis + desired rate (degrees/s) + achieved rate (degrees/s) + FF component + P component + I component + D component + + + + 3 axis gimbal mesuraments + System ID + Component ID + Time since last update (seconds) + Delta angle X (radians) + Delta angle Y (radians) + Delta angle X (radians) + Delta velocity X (m/s) + Delta velocity Y (m/s) + Delta velocity Z (m/s) + Joint ROLL (radians) + Joint EL (radians) + Joint AZ (radians) + + + + Control message for rate gimbal + System ID + Component ID + Demanded angular rate X (rad/s) + Demanded angular rate Y (rad/s) + Demanded angular rate Z (rad/s) + + + + 100 Hz gimbal torque command telemetry + System ID + Component ID + Roll Torque Command + Elevation Torque Command + Azimuth Torque Command + + + + + Heartbeat from a HeroBus attached GoPro + Status + Current capture mode + additional status bits + + + + + Request a GOPRO_COMMAND response from the GoPro + System ID + Component ID + Command ID + + + + Response from a GOPRO_COMMAND get request + Command ID + Status + Value + + + + Request to set a GOPRO_COMMAND with a desired + System ID + Component ID + Command ID + Value + + + + Response from a GOPRO_COMMAND set request + Command ID + Status + + + + + RPM sensor output + RPM Sensor1 + RPM Sensor2 + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/autoquad.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/autoquad.xml new file mode 100644 index 0000000..8c22478 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/autoquad.xml @@ -0,0 +1,169 @@ + + + common.xml + 3 + + + Track current version of these definitions (can be used by checking value of AUTOQUAD_MAVLINK_DEFS_VERSION_ENUM_END). Append a new entry for each published change. + + + + Available operating modes/statuses for AutoQuad flight controller. + Bitmask up to 32 bits. Low side bits for base modes, high side for + additional active features/modifiers/constraints. + + System is initializing + + + + System is *armed* and standing by, with no throttle input and no autonomous mode + + + Flying (throttle input detected), assumed under manual control unless other mode bits are set + + + Altitude hold engaged + + + Position hold engaged + + + Externally-guided (eg. GCS) navigation mode + + + Autonomous mission execution mode + + + + Ready but *not armed* + + + Calibration mode active + + + + No valid control input (eg. no radio link) + + + Battery is low (stage 1 warning) + + + Battery is depleted (stage 2 warning) + + + + Dynamic Velocity Hold is active (PH with proportional manual direction override) + + + ynamic Altitude Override is active (AH with proportional manual adjustment) + + + + Craft is at ceiling altitude + + + Ceiling altitude is set + + + Heading-Free dynamic mode active + + + Heading-Free locked mode active + + + Automatic Return to Home is active + + + System is in failsafe recovery mode + + + + + Orbit a waypoint. + Orbit radius in meters + Loiter time in decimal seconds + Maximum horizontal speed in m/s + Desired yaw angle at waypoint + Latitude + Longitude + Altitude + + + Start/stop AutoQuad telemetry values stream. + Start or stop (1 or 0) + Stream frequency in us + Dataset ID (refer to aq_mavlink.h::mavlinkCustomDataSets enum in AQ flight controller code) + Empty + Empty + Empty + Empty + + + + Request AutoQuad firmware version number. + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + + + Motor/ESC telemetry data. + + + + + + Sends up to 20 raw float values. + Index of message + value1 + value2 + value3 + value4 + value5 + value6 + value7 + value8 + value9 + value10 + value11 + value12 + value13 + value14 + value15 + value16 + value17 + value18 + value19 + value20 + + + Sends ESC32 telemetry data for up to 4 motors. Multiple messages may be sent in sequence when system has > 4 motors. Data is described as follows: + // unsigned int state : 3; + // unsigned int vin : 12; // x 100 + // unsigned int amps : 14; // x 100 + // unsigned int rpm : 15; + // unsigned int duty : 8; // x (255/100) + // - Data Version 2 - + // unsigned int errors : 9; // Bad detects error count + // - Data Version 3 - + // unsigned int temp : 9; // (Deg C + 32) * 4 + // unsigned int errCode : 3; + + Timestamp of the component clock since boot time in ms. + Sequence number of message (first set of 4 motors is #1, next 4 is #2, etc). + Total number of active ESCs/motors on the system. + Number of active ESCs in this sequence (1 through this many array members will be populated with data) + ESC/Motor ID + Age of each ESC telemetry reading in ms compared to boot time. A value of 0xFFFF means timeout/no data. + Version of data structure (determines contents). + Data bits 1-32 for each ESC. + Data bits 33-64 for each ESC. + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/common.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/common.xml new file mode 100644 index 0000000..7b043aa --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/common.xml @@ -0,0 +1,3440 @@ + + + 3 + + + Micro air vehicle / autopilot classes. This identifies the individual model. + + Generic autopilot, full support for everything + + + Reserved for future use. + + + SLUGS autopilot, http://slugsuav.soe.ucsc.edu + + + ArduPilotMega / ArduCopter, http://diydrones.com + + + OpenPilot, http://openpilot.org + + + Generic autopilot only supporting simple waypoints + + + Generic autopilot supporting waypoints and other simple navigation commands + + + Generic autopilot supporting the full mission command set + + + No valid autopilot, e.g. a GCS or other MAVLink component + + + PPZ UAV - http://nongnu.org/paparazzi + + + UAV Dev Board + + + FlexiPilot + + + PX4 Autopilot - http://pixhawk.ethz.ch/px4/ + + + SMACCMPilot - http://smaccmpilot.org + + + AutoQuad -- http://autoquad.org + + + Armazila -- http://armazila.com + + + Aerob -- http://aerob.ru + + + ASLUAV autopilot -- http://www.asl.ethz.ch + + + + + Generic micro air vehicle. + + + Fixed wing aircraft. + + + Quadrotor + + + Coaxial helicopter + + + Normal helicopter with tail rotor. + + + Ground installation + + + Operator control unit / ground control station + + + Airship, controlled + + + Free balloon, uncontrolled + + + Rocket + + + Ground rover + + + Surface vessel, boat, ship + + + Submarine + + + Hexarotor + + + Octorotor + + + Octorotor + + + Flapping wing + + + Flapping wing + + + Onboard companion controller + + + Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. + + + Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. + + + Tiltrotor VTOL + + + + VTOL reserved 2 + + + VTOL reserved 3 + + + VTOL reserved 4 + + + VTOL reserved 5 + + + Onboard gimbal + + + Onboard ADSB peripheral + + + + These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65. + + development release + + + alpha release + + + beta release + + + release candidate + + + official stable release + + + + + These flags encode the MAV mode. + + 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. + + + 0b01000000 remote control input is enabled. + + + 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. + + + 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. + + + 0b00001000 guided mode enabled, system flies MISSIONs / mission items. + + + 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. + + + 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. + + + 0b00000001 Reserved for future use. + + + + These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. + + First bit: 10000000 + + + Second bit: 01000000 + + + Third bit: 00100000 + + + Fourth bit: 00010000 + + + Fifth bit: 00001000 + + + Sixt bit: 00000100 + + + Seventh bit: 00000010 + + + Eighth bit: 00000001 + + + + Override command, pauses current mission execution and moves immediately to a position + + Hold at the current position. + + + Continue with the next item in mission execution. + + + Hold at the current position of the system + + + Hold at the position specified in the parameters of the DO_HOLD action + + + + These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it + simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. + + System is not ready to fly, booting, calibrating, etc. No flag is set. + + + System is allowed to be active, under assisted RC control. + + + System is allowed to be active, under assisted RC control. + + + System is allowed to be active, under manual (RC) control, no stabilization + + + System is allowed to be active, under manual (RC) control, no stabilization + + + System is allowed to be active, under autonomous control, manual setpoint + + + System is allowed to be active, under autonomous control, manual setpoint + + + System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) + + + System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) + + + UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. + + + UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. + + + + + Uninitialized system, state is unknown. + + + System is booting up. + + + System is calibrating and not flight-ready. + + + System is grounded and on standby. It can be launched any time. + + + System is active and might be already airborne. Motors are engaged. + + + System is in a non-normal flight mode. It can however still navigate. + + + System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. + + + System just initialized its power-down sequence, will shut down now. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + On Screen Display (OSD) devices for video links + + + Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol + + + + These encode the sensors whose status is sent as part of the SYS_STATUS message. + + 0x01 3D gyro + + + 0x02 3D accelerometer + + + 0x04 3D magnetometer + + + 0x08 absolute pressure + + + 0x10 differential pressure + + + 0x20 GPS + + + 0x40 optical flow + + + 0x80 computer vision position + + + 0x100 laser based position + + + 0x200 external ground truth (Vicon or Leica) + + + 0x400 3D angular rate control + + + 0x800 attitude stabilization + + + 0x1000 yaw position + + + 0x2000 z/altitude control + + + 0x4000 x/y position control + + + 0x8000 motor outputs / control + + + 0x10000 rc receiver + + + 0x20000 2nd 3D gyro + + + 0x40000 2nd 3D accelerometer + + + 0x80000 2nd 3D magnetometer + + + 0x100000 geofence + + + 0x200000 AHRS subsystem health + + + 0x400000 Terrain subsystem health + + + 0x800000 Motors are reversed + + + + + Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) + + + Local coordinate frame, Z-up (x: north, y: east, z: down). + + + NOT a coordinate frame, indicates a mission command. + + + Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. + + + Local coordinate frame, Z-down (x: east, y: north, z: up) + + + Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL) + + + Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. + + + Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. + + + Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. + + + Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. + + + Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. + + + Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. + + + + + + + + + + + + + + + + + + + + + + + + + + Disable fenced mode + + + Switched to guided mode to return point (fence point 0) + + + Report fence breach, but don't take action + + + Switched to guided mode to return point (fence point 0) with manual throttle control + + + + + + No last fence breach + + + Breached minimum altitude + + + Breached maximum altitude + + + Breached fence boundary + + + + + Enumeration of possible mount operation modes + Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization + Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. + Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization + Load neutral position and start RC Roll,Pitch,Yaw control with stabilization + Load neutral position and start to point to Lat,Lon,Alt + + + Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. + + Navigate to MISSION. + Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing) + Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached) + 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. + Desired yaw angle at MISSION (rotary wing) + Latitude + Longitude + Altitude + + + Loiter around this MISSION an unlimited amount of time + Empty + Empty + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this MISSION for X turns + Turns + Empty + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle + Latitude + Longitude + Altitude + + + Loiter around this MISSION for X seconds + Seconds (decimal) + Empty + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle + Latitude + Longitude + Altitude + + + Return to launch location + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Land at location + Abort Alt + Empty + Empty + Desired yaw angle + Latitude + Longitude + Altitude + + + Takeoff from ground / hand + Minimum pitch (if airspeed sensor present), desired pitch without sensor + Empty + Empty + Yaw angle (if magnetometer present), ignored without magnetometer + Latitude + Longitude + Altitude + + + Land at local position (local frame only) + Landing target number (if available) + Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land + Landing descend rate [ms^-1] + Desired yaw angle [rad] + Y-axis position [m] + X-axis position [m] + Z-axis / ground level position [m] + + + Takeoff from local position (local frame only) + Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad] + Empty + Takeoff ascend rate [ms^-1] + Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these + Y-axis position [m] + X-axis position [m] + Z-axis position [m] + + + Vehicle following, i.e. this waypoint represents the position of a moving vehicle + Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation + Ground speed of vehicle to be followed + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. + Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. + Empty + Empty + Empty + Empty + Empty + Desired altitude in meters + + + Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. + Heading Required (0 = False) + Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter. + Empty + Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location + Latitude + Longitude + Altitude + + + Being following a target + System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode + RESERVED + RESERVED + altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home + altitude + RESERVED + TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout + + + Reposition the MAV after a follow target command has been sent + Camera q1 (where 0 is on the ray from the camera to the tracking device) + Camera q2 + Camera q3 + Camera q4 + altitude offset from target (m) + X offset from target (m) + Y offset from target (m) + + + Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. + Region of intereset mode. (see MAV_ROI enum) + MISSION index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple ROI's) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + + Control autonomous path planning on the MAV. + 0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning + 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid + Empty + Yaw angle at goal, in compass degrees, [0..360] + Latitude/X of goal + Longitude/Y of goal + Altitude/Z of goal + + + Navigate to MISSION using a spline path. + Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing) + Empty + Empty + Empty + Latitude/X of goal + Longitude/Y of goal + Altitude/Z of goal + + + Takeoff from ground using VTOL mode + Empty + Empty + Empty + Yaw angle in degrees + Latitude + Longitude + Altitude + + + Land using VTOL mode + Empty + Empty + Empty + Yaw angle in degrees + Latitude + Longitude + Altitude + + + + + + hand control over to an external controller + On / Off (> 0.5f on) + Empty + Empty + Empty + Empty + Empty + Empty + + + Delay the next navigation command a number of seconds or until a specified time + Delay in seconds (decimal, -1 to enable time-of-day fields) + hour (24h format, UTC, -1 to ignore) + minute (24h format, UTC, -1 to ignore) + second (24h format, UTC) + Empty + Empty + Empty + + + NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Delay mission state machine. + Delay in seconds (decimal) + Empty + Empty + Empty + Empty + Empty + Empty + + + Ascend/descend at rate. Delay mission state machine until desired altitude reached. + Descent / Ascend rate (m/s) + Empty + Empty + Empty + Empty + Empty + Finish Altitude + + + Delay mission state machine until within desired distance of next NAV point. + Distance (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + Reach a certain target angle. + target angle: [0-360], 0 is north + speed during yaw change:[deg per second] + direction: negative: counter clockwise, positive: clockwise [-1,1] + relative offset or absolute angle: [ 1,0] + Empty + Empty + Empty + + + NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Set system mode. + Mode, as defined by ENUM MAV_MODE + Custom mode - this is system specific, please refer to the individual autopilot specifications for details. + Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details. + Empty + Empty + Empty + Empty + + + Jump to the desired command in the mission list. Repeat this action only the specified number of times + Sequence number + Repeat count + Empty + Empty + Empty + Empty + Empty + + + Change speed and/or throttle set points. + Speed type (0=Airspeed, 1=Ground Speed) + Speed (m/s, -1 indicates no change) + Throttle ( Percent, -1 indicates no change) + absolute or relative [0,1] + Empty + Empty + Empty + + + Changes the home location either to the current location or a specified location. + Use current (1=use current location, 0=use specified location) + Empty + Empty + Empty + Latitude + Longitude + Altitude + + + Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. + Parameter number + Parameter value + Empty + Empty + Empty + Empty + Empty + + + Set a relay to a condition. + Relay number + Setting (1=on, 0=off, others possible depending on system hardware) + Empty + Empty + Empty + Empty + Empty + + + Cycle a relay on and off for a desired number of cyles with a desired period. + Relay number + Cycle count + Cycle time (seconds, decimal) + Empty + Empty + Empty + Empty + + + Set a servo to a desired PWM value. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Empty + Empty + Empty + Empty + Empty + + + Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Cycle count + Cycle time (seconds) + Empty + Empty + Empty + + + Terminate flight immediately + Flight termination activated if > 0.5 + Empty + Empty + Empty + Empty + Empty + Empty + + + Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. + Empty + Empty + Empty + Empty + Latitude + Longitude + Empty + + + Mission command to perform a landing from a rally point. + Break altitude (meters) + Landing speed (m/s) + Empty + Empty + Empty + Empty + Empty + + + Mission command to safely abort an autonmous landing. + Altitude (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Reposition the vehicle to a specific WGS84 global position. + Ground speed, less than 0 (-1) for default + Bitmask of option flags, see the MAV_DO_REPOSITION_FLAGS enum. + Reserved + Yaw heading, NaN for unchanged. For planes indicates loiter direction (0: clockwise, 1: counter clockwise) + Latitude (deg * 1E7) + Longitude (deg * 1E7) + Altitude (meters) + + + If in a GPS controlled position mode, hold the current position or continue. + 0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + Control onboard camera system. + Camera ID (-1 for all) + Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw + Transmission mode: 0: video stream, >0: single images every n seconds (decimal) + Recording: 0: disabled, 1: enabled compressed, 2: enabled raw + Empty + Empty + Empty + + + Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. + Region of intereset mode. (see MAV_ROI enum) + MISSION index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple ROI's) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + + + + Mission command to configure an on-board camera controller system. + Modes: P, TV, AV, M, Etc + Shutter speed: Divisor number for one second + Aperture: F stop number + ISO number e.g. 80, 100, 200, Etc + Exposure type enumerator + Command Identity + Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + + + + Mission command to control an on-board camera controller system. + Session control e.g. show/hide lens + Zoom's absolute position + Zooming step value to offset zoom from the current position + Focus Locking, Unlocking or Re-locking + Shooting Command + Command Identity + Empty + + + + + Mission command to configure a camera or antenna mount + Mount operation mode (see MAV_MOUNT_MODE enum) + stabilize roll? (1 = yes, 0 = no) + stabilize pitch? (1 = yes, 0 = no) + stabilize yaw? (1 = yes, 0 = no) + Empty + Empty + Empty + + + + Mission command to control a camera or antenna mount + pitch or lat in degrees, depending on mount mode. + roll or lon in degrees depending on mount mode + yaw or alt (in meters) depending on mount mode + reserved + reserved + reserved + MAV_MOUNT_MODE enum value + + + + Mission command to set CAM_TRIGG_DIST for this flight + Camera trigger distance (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to enable the geofence + enable? (0=disable, 1=enable, 2=disable_floor_only) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to trigger a parachute + action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Change to/from inverted flight + inverted (0=normal, 1=inverted) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to control a camera or antenna mount, using a quaternion as reference. + q1 - quaternion param #1, w (1 in null-rotation) + q2 - quaternion param #2, x (0 in null-rotation) + q3 - quaternion param #3, y (0 in null-rotation) + q4 - quaternion param #4, z (0 in null-rotation) + Empty + Empty + Empty + + + + set id of master controller + System ID + Component ID + Empty + Empty + Empty + Empty + Empty + + + + set limits for external control + timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout + absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit + absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit + horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit + Empty + Empty + Empty + + + + NOP - This command is only used to mark the upper limit of the DO commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Trigger calibration. This command will be only accepted if in pre-flight mode. + Gyro calibration: 0: no, 1: yes + Magnetometer calibration: 0: no, 1: yes + Ground pressure: 0: no, 1: yes + Radio calibration: 0: no, 1: yes + Accelerometer calibration: 0: no, 1: yes + Compass/Motor interference calibration: 0: no, 1: yes + Empty + + + Set sensor offsets. This command will be only accepted if in pre-flight mode. + Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer + X axis offset (or generic dimension 1), in the sensor's raw units + Y axis offset (or generic dimension 2), in the sensor's raw units + Z axis offset (or generic dimension 3), in the sensor's raw units + Generic dimension 4, in the sensor's raw units + Generic dimension 5, in the sensor's raw units + Generic dimension 6, in the sensor's raw units + + + Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. + 1: Trigger actuator ID assignment and direction mapping. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. + Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults + Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults + Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging) + Reserved + Empty + Empty + Empty + + + Request the reboot or shutdown of system components. + 0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded. + 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded. + Reserved, send 0 + Reserved, send 0 + Reserved, send 0 + Reserved, send 0 + Reserved, send 0 + + + Hold / continue the current action + MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan + MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position + MAV_FRAME coordinate frame of hold point + Desired yaw angle in degrees + Latitude / X position + Longitude / Y position + Altitude / Z position + + + start running a mission + first_item: the first mission item to run + last_item: the last mission item to run (after this item is run, the mission ends) + + + Arms / Disarms a component + 1 to arm, 0 to disarm + + + Request the home position from the vehicle. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + Starts receiver pairing + 0:Spektrum + 0:Spektrum DSM2, 1:Spektrum DSMX + + + Request the interval between messages for a particular MAVLink message ID + The MAVLink message ID + + + Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM + The MAVLink message ID + The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate. + + + Request autopilot capabilities + 1: Request autopilot version + Reserved (all remaining params) + + + Start image capture sequence + Duration between two consecutive pictures (in seconds) + Number of images to capture total - 0 for unlimited capture + Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc) + + + + Stop image capture sequence + Reserved + Reserved + + + + Enable or disable on-board camera triggering system. + Trigger enable/disable (0 for disable, 1 for start) + Shutter integration time (in ms) + Reserved + + + + Starts video capture + Camera ID (0 for all cameras), 1 for first, 2 for second, etc. + Frames per second + Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc) + + + + Stop the current video capture + Reserved + Reserved + + + + Create a panorama at the current position + Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle) + Viewing angle vertical of panorama (in degrees) + Speed of the horizontal rotation (in degrees per second) + Speed of the vertical rotation (in degrees per second) + + + + Request VTOL transition + The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used. + + + + + + + Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. + Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list. + Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will. + Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will. + Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will. + Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT + Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT + Altitude, in meters AMSL + + + Control the payload deployment. + Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + + + THIS INTERFACE IS DEPRECATED AS OF JULY 2015. Please use MESSAGE_INTERVAL instead. A data stream is not a fixed set of messages, but rather a + recommendation to the autopilot software. Individual autopilots may or may not obey + the recommended messages. + + Enable all data streams + + + Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. + + + Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS + + + Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW + + + Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. + + + Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. + + + Dependent on the autopilot + + + Dependent on the autopilot + + + Dependent on the autopilot + + + + The ROI (region of interest) for the vehicle. This can be + be used by the vehicle for camera/vehicle attitude alignment (see + MAV_CMD_NAV_ROI). + + No region of interest. + + + Point toward next MISSION. + + + Point toward given MISSION. + + + Point toward fixed location. + + + Point toward of given id. + + + + ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. + + Command / mission item is ok. + + + Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. + + + The system is refusing to accept this command from this source / communication partner. + + + Command or mission item is not supported, other commands would be accepted. + + + The coordinate frame of this command / mission item is not supported. + + + The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. + + + The X or latitude value is out of range. + + + The Y or longitude value is out of range. + + + The Z or altitude value is out of range. + + + + Specifies the datatype of a MAVLink parameter. + + 8-bit unsigned integer + + + 8-bit signed integer + + + 16-bit unsigned integer + + + 16-bit signed integer + + + 32-bit unsigned integer + + + 32-bit signed integer + + + 64-bit unsigned integer + + + 64-bit signed integer + + + 32-bit floating-point + + + 64-bit floating-point + + + + result from a mavlink command + + Command ACCEPTED and EXECUTED + + + Command TEMPORARY REJECTED/DENIED + + + Command PERMANENTLY DENIED + + + Command UNKNOWN/UNSUPPORTED + + + Command executed, but failed + + + + result in a mavlink mission ack + + mission accepted OK + + + generic error / not accepting mission commands at all right now + + + coordinate frame is not supported + + + command is not supported + + + mission item exceeds storage space + + + one of the parameters has an invalid value + + + param1 has an invalid value + + + param2 has an invalid value + + + param3 has an invalid value + + + param4 has an invalid value + + + x/param5 has an invalid value + + + y/param6 has an invalid value + + + param7 has an invalid value + + + received waypoint out of sequence + + + not accepting any mission commands from this communication partner + + + + Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. + + System is unusable. This is a "panic" condition. + + + Action should be taken immediately. Indicates error in non-critical systems. + + + Action must be taken immediately. Indicates failure in a primary system. + + + Indicates an error in secondary/redundant systems. + + + Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. + + + An unusual event has occured, though not an error condition. This should be investigated for the root cause. + + + Normal operational messages. Useful for logging. No action is required for these messages. + + + Useful non-operational messages that can assist in debugging. These should not occur during normal operation. + + + + Power supply status flags (bitmask) + + main brick power supply valid + + + main servo power supply valid for FMU + + + USB power is connected + + + peripheral supply is in over-current state + + + hi-power peripheral supply is in over-current state + + + Power status has changed since boot + + + + SERIAL_CONTROL device types + + First telemetry port + + + Second telemetry port + + + First GPS port + + + Second GPS port + + + system shell + + + + SERIAL_CONTROL flags (bitmask) + + Set if this is a reply + + + Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message + + + Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set + + + Block on writes to the serial port + + + Send multiple replies until port is drained + + + + Enumeration of distance sensor types + + Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units + + + Ultrasound rangefinder, e.g. MaxBotix units + + + Infrared rangefinder, e.g. Sharp units + + + + Enumeration of sensor orientation, according to its rotations + + Roll: 0, Pitch: 0, Yaw: 0 + + + Roll: 0, Pitch: 0, Yaw: 45 + + + Roll: 0, Pitch: 0, Yaw: 90 + + + Roll: 0, Pitch: 0, Yaw: 135 + + + Roll: 0, Pitch: 0, Yaw: 180 + + + Roll: 0, Pitch: 0, Yaw: 225 + + + Roll: 0, Pitch: 0, Yaw: 270 + + + Roll: 0, Pitch: 0, Yaw: 315 + + + Roll: 180, Pitch: 0, Yaw: 0 + + + Roll: 180, Pitch: 0, Yaw: 45 + + + Roll: 180, Pitch: 0, Yaw: 90 + + + Roll: 180, Pitch: 0, Yaw: 135 + + + Roll: 0, Pitch: 180, Yaw: 0 + + + Roll: 180, Pitch: 0, Yaw: 225 + + + Roll: 180, Pitch: 0, Yaw: 270 + + + Roll: 180, Pitch: 0, Yaw: 315 + + + Roll: 90, Pitch: 0, Yaw: 0 + + + Roll: 90, Pitch: 0, Yaw: 45 + + + Roll: 90, Pitch: 0, Yaw: 90 + + + Roll: 90, Pitch: 0, Yaw: 135 + + + Roll: 270, Pitch: 0, Yaw: 0 + + + Roll: 270, Pitch: 0, Yaw: 45 + + + Roll: 270, Pitch: 0, Yaw: 90 + + + Roll: 270, Pitch: 0, Yaw: 135 + + + Roll: 0, Pitch: 90, Yaw: 0 + + + Roll: 0, Pitch: 270, Yaw: 0 + + + Roll: 0, Pitch: 180, Yaw: 90 + + + Roll: 0, Pitch: 180, Yaw: 270 + + + Roll: 90, Pitch: 90, Yaw: 0 + + + Roll: 180, Pitch: 90, Yaw: 0 + + + Roll: 270, Pitch: 90, Yaw: 0 + + + Roll: 90, Pitch: 180, Yaw: 0 + + + Roll: 270, Pitch: 180, Yaw: 0 + + + Roll: 90, Pitch: 270, Yaw: 0 + + + Roll: 180, Pitch: 270, Yaw: 0 + + + Roll: 270, Pitch: 270, Yaw: 0 + + + Roll: 90, Pitch: 180, Yaw: 90 + + + Roll: 90, Pitch: 0, Yaw: 270 + + + Roll: 315, Pitch: 315, Yaw: 315 + + + + Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability. + + Autopilot supports MISSION float message type. + + + Autopilot supports the new param float message type. + + + Autopilot supports MISSION_INT scaled integer message type. + + + Autopilot supports COMMAND_INT scaled integer message type. + + + Autopilot supports the new param union message type. + + + Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. + + + Autopilot supports commanding attitude offboard. + + + Autopilot supports commanding position and velocity targets in local NED frame. + + + Autopilot supports commanding position and velocity targets in global scaled integers. + + + Autopilot supports terrain protocol / data handling. + + + Autopilot supports direct actuator control. + + + Autopilot supports the flight termination command. + + + Autopilot supports onboard compass calibration. + + + + Enumeration of estimator types + + This is a naive estimator without any real covariance feedback. + + + Computer vision based estimate. Might be up to scale. + + + Visual-inertial estimate. + + + Plain GPS estimate. + + + Estimator integrating GPS and inertial sensing. + + + + Enumeration of battery types + + Not specified. + + + Lithium polymer battery + + + Lithium-iron-phosphate battery + + + Lithium-ION battery + + + Nickel metal hydride battery + + + + Enumeration of battery functions + + Battery function is unknown + + + Battery supports all flight systems + + + Battery for the propulsion system + + + Avionics battery + + + Payload battery + + + + Enumeration of VTOL states + + MAV is not configured as VTOL + + + VTOL is in transition from multicopter to fixed-wing + + + VTOL is in transition from fixed-wing to multicopter + + + VTOL is in multicopter state + + + VTOL is in fixed-wing state + + + + Enumeration of landed detector states + + MAV landed state is unknown + + + MAV is landed (on ground) + + + MAV is in air + + + + Enumeration of the ADSB altimeter types + + Altitude reported from a Baro source using QNH reference + + + Altitude reported from a GNSS source + + + + ADSB classification for the type of vehicle emitting the transponder signal + + + + + + + + + + + + + + + + + + + + + + + These flags indicate status such as data validity of each data source. Set = data valid + + + + + + + + + + Bitmask of options for the MAV_CMD_DO_REPOSITION + + The aircraft should immediately transition into guided. This should not be set for follow me applications + + + + + Flags in EKF_STATUS message + + True if the attitude estimate is good + + + + True if the horizontal velocity estimate is good + + + + True if the vertical velocity estimate is good + + + + True if the horizontal position (relative) estimate is good + + + + True if the horizontal position (absolute) estimate is good + + + + True if the vertical position (absolute) estimate is good + + + + True if the vertical position (above ground) estimate is good + + + + True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) + + + + True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate + + + + True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate + + + + True if the EKF has detected a GPS glitch + + + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Autopilot type / class. defined in MAV_AUTOPILOT ENUM + System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h + A bitfield for use for autopilot-specific flags. + System status flag, see MAV_STATE ENUM + MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version + + + The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout. + Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + Battery voltage, in millivolts (1 = 1 millivolt) + Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + Autopilot-specific errors + Autopilot-specific errors + Autopilot-specific errors + Autopilot-specific errors + + + The system time is the time of the master clock, typically the computer clock of the main onboard computer. + Timestamp of the master clock in microseconds since UNIX epoch. + Timestamp of the component clock since boot time in milliseconds. + + + + A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. + Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) + PING sequence + 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + + + Request to control this MAV + System the GCS requests control for + 0: request control of this MAV, 1: Release control of this MAV + 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + + + Accept / deny control of this MAV + ID of the GCS this message + 0: request control of this MAV, 1: Release control of this MAV + 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + + + Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety. + key + + + THIS INTERFACE IS DEPRECATED. USE COMMAND_LONG with MAV_CMD_DO_SET_MODE INSTEAD. Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. + The system setting the mode + The new base mode + The new autopilot-specific mode. This field can be ignored by an autopilot. + + + + Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code. + System ID + Component ID + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + + + Request all parameters of this component. After his request, all parameters are emitted. + System ID + Component ID + + + Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Onboard parameter value + Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + Total number of onboard parameters + Index of this onboard parameter + + + Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message. + System ID + Component ID + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Onboard parameter value + Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + + + The global position, as returned by the Global Positioning System (GPS). This is + NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. + GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + Number of satellites visible. If unknown, set to 255 + + + The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites. + Number of satellites visible + Global satellite ID + 0: Satellite not used, 1: used for localization + Elevation (0: right on top of receiver, 90: on the horizon) of satellite + Direction of satellite, 0: 0 deg, 255: 360 deg. + Signal to noise ratio of satellite + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (milliseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X acceleration (raw) + Y acceleration (raw) + Z acceleration (raw) + Angular speed around X axis (raw) + Angular speed around Y axis (raw) + Angular speed around Z axis (raw) + X Magnetic field (raw) + Y Magnetic field (raw) + Z Magnetic field (raw) + + + The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Absolute pressure (raw) + Differential pressure 1 (raw, 0 if nonexistant) + Differential pressure 2 (raw, 0 if nonexistant) + Raw Temperature measurement (raw) + + + The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. + Timestamp (milliseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). + Timestamp (milliseconds since system boot) + Roll angle (rad, -pi..+pi) + Pitch angle (rad, -pi..+pi) + Yaw angle (rad, -pi..+pi) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). + Timestamp (milliseconds since system boot) + Quaternion component 1, w (1 in null-rotation) + Quaternion component 2, x (0 in null-rotation) + Quaternion component 3, y (0 in null-rotation) + Quaternion component 4, z (0 in null-rotation) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + + + The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + Timestamp (milliseconds since system boot) + X Position + Y Position + Z Position + X Speed + Y Speed + Z Speed + + + The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the resolution of float is not sufficient. + Timestamp (milliseconds since system boot) + Latitude, expressed as degrees * 1E7 + Longitude, expressed as degrees * 1E7 + Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) + Altitude above ground in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude, positive north), expressed as m/s * 100 + Ground Y Speed (Longitude, positive east), expressed as m/s * 100 + Ground Z Speed (Altitude, positive down), expressed as m/s * 100 + Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + + + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX. + Timestamp (milliseconds since system boot) + Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + + + The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + Timestamp (milliseconds since system boot) + Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + + + The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. + Timestamp (microseconds since system boot) + Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + Servo output 1 value, in microseconds + Servo output 2 value, in microseconds + Servo output 3 value, in microseconds + Servo output 4 value, in microseconds + Servo output 5 value, in microseconds + Servo output 6 value, in microseconds + Servo output 7 value, in microseconds + Servo output 8 value, in microseconds + + + Request a partial list of mission items from the system/component. http://qgroundcontrol.org/mavlink/waypoint_protocol. If start and end index are the same, just send one waypoint. + System ID + Component ID + Start index, 0 by default + End index, -1 by default (-1: send list to end). Else a valid index of the list + + + This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED! + System ID + Component ID + Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + End index, equal or greater than start index. + + + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See also http://qgroundcontrol.org/mavlink/waypoint_protocol. + System ID + Component ID + Sequence + The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1, see MAV_CMD enum + PARAM2, see MAV_CMD enum + PARAM3, see MAV_CMD enum + PARAM4, see MAV_CMD enum + PARAM5 / local: x position, global: latitude + PARAM6 / y position: global: longitude + PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + + + Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. http://qgroundcontrol.org/mavlink/waypoint_protocol + System ID + Component ID + Sequence + + + Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between). + System ID + Component ID + Sequence + + + Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item. + Sequence + + + Request the overall list of mission items from the system/component. + System ID + Component ID + + + This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of MISSIONs. + System ID + Component ID + Number of mission items in the sequence + + + Delete all mission items at once. + System ID + Component ID + + + A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next MISSION. + Sequence + + + Ack message during MISSION handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). + System ID + Component ID + See MAV_MISSION_RESULT enum + + + As local waypoints exist, the global MISSION reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor. + System ID + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84, in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + + + Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + + + Bind a RC channel to a parameter. The parameter should change accoding to the RC channel value. + System ID + Component ID + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. + Initial parameter value + Scale, maps the RC range [-1, 1] to a parameter value + Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + + + Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. http://qgroundcontrol.org/mavlink/waypoint_protocol + System ID + Component ID + Sequence + + + Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/MISSIONs to accept and which to reject. Safety areas are often enforced by national or competition regulations. + System ID + Component ID + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + Read out the safety zone the MAV currently assumes. + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). + Timestamp (milliseconds since system boot) + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + Attitude covariance + + + The state of the fixed wing navigation and position controller. + Current desired roll in degrees + Current desired pitch in degrees + Current desired heading in degrees + Bearing to current MISSION/target in degrees + Distance to active MISSION in meters + Current altitude error in meters + Current airspeed error in meters/second + Current crosstrack error on x-y plane in meters + + + The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset. + Timestamp (milliseconds since system boot) + Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + Class id of the estimator this estimate originated from. + Latitude, expressed as degrees * 1E7 + Longitude, expressed as degrees * 1E7 + Altitude in meters, expressed as * 1000 (millimeters), above MSL + Altitude above ground in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s + Ground Y Speed (Longitude), expressed as m/s + Ground Z Speed (Altitude), expressed as m/s + Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + + + The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp + Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + Class id of the estimator this estimate originated from. + X Position + Y Position + Z Position + X Speed (m/s) + Y Speed (m/s) + Z Speed (m/s) + X Acceleration (m/s^2) + Y Acceleration (m/s^2) + Z Acceleration (m/s^2) + Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + + + The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + Timestamp (milliseconds since system boot) + Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + + + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + The target requested to send the message stream. + The target requested to send the message stream. + The ID of the requested data stream + The requested message rate + 1 to start sending, 0 to stop sending. + + + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + The ID of the requested data stream + The message rate + 1 stream is enabled, 0 stream is stopped. + + + This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled an buttons are also transmit as boolean values of their + The system to be controlled. + X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + + + The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of UINT16_MAX means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + System ID + Component ID + RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + + + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See alsohttp://qgroundcontrol.org/mavlink/waypoint_protocol. + System ID + Component ID + Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1, see MAV_CMD enum + PARAM2, see MAV_CMD enum + PARAM3, see MAV_CMD enum + PARAM4, see MAV_CMD enum + PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + + + Metrics typically displayed on a HUD for fixed wing aircraft + Current airspeed in m/s + Current ground speed in m/s + Current heading in degrees, in compass units (0..360, 0=north) + Current throttle setting in integer percent, 0 to 100 + Current altitude (MSL), in meters + Current climb rate in meters/second + + + Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value. + System ID + Component ID + The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h + The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1, see MAV_CMD enum + PARAM2, see MAV_CMD enum + PARAM3, see MAV_CMD enum + PARAM4, see MAV_CMD enum + PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + + + Send a command with up to seven parameters to the MAV + System which should execute the command + Component which should execute the command, 0 for all components + Command ID, as defined by MAV_CMD enum. + 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + Parameter 1, as defined by MAV_CMD enum. + Parameter 2, as defined by MAV_CMD enum. + Parameter 3, as defined by MAV_CMD enum. + Parameter 4, as defined by MAV_CMD enum. + Parameter 5, as defined by MAV_CMD enum. + Parameter 6, as defined by MAV_CMD enum. + Parameter 7, as defined by MAV_CMD enum. + + + Report status of a command. Includes feedback wether the command was executed. + Command ID, as defined by MAV_CMD enum. + See MAV_RESULT enum + + + Setpoint in roll, pitch, yaw and thrust from the operator + Timestamp in milliseconds since system boot + Desired roll rate in radians per second + Desired pitch rate in radians per second + Desired yaw rate in radians per second + Collective thrust, normalized to 0 .. 1 + Flight mode switch position, 0.. 255 + Override mode switch position, 0.. 255 + + + Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system). + Timestamp in milliseconds since system boot + System ID + Component ID + Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + Body roll rate in radians per second + Body roll rate in radians per second + Body roll rate in radians per second + Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + + + Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way. + Timestamp in milliseconds since system boot + Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + Body roll rate in radians per second + Body roll rate in radians per second + Body roll rate in radians per second + Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + + + Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system). + Timestamp in milliseconds since system boot + System ID + Component ID + Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in NED frame in meters + Y Position in NED frame in meters + Z Position in NED frame in meters (note, altitude is negative in NED) + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way. + Timestamp in milliseconds since system boot + Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in NED frame in meters + Y Position in NED frame in meters + Z Position in NED frame in meters (note, altitude is negative in NED) + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system). + Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + System ID + Component ID + Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in WGS84 frame in 1e7 * meters + Y Position in WGS84 frame in 1e7 * meters + Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way. + Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in WGS84 frame in 1e7 * meters + Y Position in WGS84 frame in 1e7 * meters + Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + Timestamp (milliseconds since system boot) + X Position + Y Position + Z Position + Roll + Pitch + Yaw + + + DEPRECATED PACKET! Suffers from missing airspeed fields and singularities due to Euler angles. Please use HIL_STATE_QUATERNION instead. Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Body frame roll / phi angular speed (rad/s) + Body frame pitch / theta angular speed (rad/s) + Body frame yaw / psi angular speed (rad/s) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + + + Sent from autopilot to simulation. Hardware in the loop control outputs + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Control output -1 .. 1 + Control output -1 .. 1 + Control output -1 .. 1 + Throttle 0 .. 1 + Aux 1, -1 .. 1 + Aux 2, -1 .. 1 + Aux 3, -1 .. 1 + Aux 4, -1 .. 1 + System mode (MAV_MODE) + Navigation mode (MAV_NAV_MODE) + + + Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + RC channel 1 value, in microseconds + RC channel 2 value, in microseconds + RC channel 3 value, in microseconds + RC channel 4 value, in microseconds + RC channel 5 value, in microseconds + RC channel 6 value, in microseconds + RC channel 7 value, in microseconds + RC channel 8 value, in microseconds + RC channel 9 value, in microseconds + RC channel 10 value, in microseconds + RC channel 11 value, in microseconds + RC channel 12 value, in microseconds + Receive signal strength indicator, 0: 0%, 255: 100% + + + Optical flow from a flow sensor (e.g. optical mouse sensor) + Timestamp (UNIX) + Sensor ID + Flow in pixels * 10 in x-sensor direction (dezi-pixels) + Flow in pixels * 10 in y-sensor direction (dezi-pixels) + Flow in meters in x-sensor direction, angular-speed compensated + Flow in meters in y-sensor direction, angular-speed compensated + Optical flow quality / confidence. 0: bad, 255: maximum quality + Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X speed + Global Y speed + Global Z speed + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + The IMU readings in SI units in NED body frame + Timestamp (microseconds, synced to UNIX time or since system boot) + X acceleration (m/s^2) + Y acceleration (m/s^2) + Z acceleration (m/s^2) + Angular speed around X axis (rad / sec) + Angular speed around Y axis (rad / sec) + Angular speed around Z axis (rad / sec) + X Magnetic field (Gauss) + Y Magnetic field (Gauss) + Z Magnetic field (Gauss) + Absolute pressure in millibar + Differential pressure in millibar + Altitude calculated from pressure + Temperature in degrees celsius + Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + + + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor) + Timestamp (microseconds, synced to UNIX time or since system boot) + Sensor ID + Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + RH rotation around X axis (rad) + RH rotation around Y axis (rad) + RH rotation around Z axis (rad) + Temperature * 100 in centi-degrees Celsius + Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + Time in microseconds since the distance was sampled. + Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + + + The IMU readings in SI units in NED body frame + Timestamp (microseconds, synced to UNIX time or since system boot) + X acceleration (m/s^2) + Y acceleration (m/s^2) + Z acceleration (m/s^2) + Angular speed around X axis in body frame (rad / sec) + Angular speed around Y axis in body frame (rad / sec) + Angular speed around Z axis in body frame (rad / sec) + X Magnetic field (Gauss) + Y Magnetic field (Gauss) + Z Magnetic field (Gauss) + Absolute pressure in millibar + Differential pressure (airspeed) in millibar + Altitude calculated from pressure + Temperature in degrees celsius + Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + + + + Status of simulation environment, if used + True attitude quaternion component 1, w (1 in null-rotation) + True attitude quaternion component 2, x (0 in null-rotation) + True attitude quaternion component 3, y (0 in null-rotation) + True attitude quaternion component 4, z (0 in null-rotation) + Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + X acceleration m/s/s + Y acceleration m/s/s + Z acceleration m/s/s + Angular speed around X axis rad/s + Angular speed around Y axis rad/s + Angular speed around Z axis rad/s + Latitude in degrees + Longitude in degrees + Altitude in meters + Horizontal position standard deviation + Vertical position standard deviation + True velocity in m/s in NORTH direction in earth-fixed NED frame + True velocity in m/s in EAST direction in earth-fixed NED frame + True velocity in m/s in DOWN direction in earth-fixed NED frame + + + + Status generated by radio and injected into MAVLink stream. + Local signal strength + Remote signal strength + Remaining free buffer space in percent. + Background noise level + Remote background noise level + Receive errors + Count of error corrected packets + + + File transfer message + Network ID (0 for broadcast) + System ID (0 for broadcast) + Component ID (0 for broadcast) + Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + + + Time synchronization message. + Time sync timestamp 1 + Time sync timestamp 2 + + + Camera-IMU triggering and synchronisation message. + Timestamp for the image frame in microseconds + Image frame sequence + + + The global position, as returned by the Global Positioning System (GPS). This is + NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 + GPS ground speed (m/s * 100). If unknown, set to: 65535 + GPS velocity in cm/s in NORTH direction in earth-fixed NED frame + GPS velocity in cm/s in EAST direction in earth-fixed NED frame + GPS velocity in cm/s in DOWN direction in earth-fixed NED frame + Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + Number of satellites visible. If unknown, set to 255 + + + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor) + Timestamp (microseconds, synced to UNIX time or since system boot) + Sensor ID + Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + RH rotation around X axis (rad) + RH rotation around Y axis (rad) + RH rotation around Z axis (rad) + Temperature * 100 in centi-degrees Celsius + Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + Time in microseconds since the distance was sampled. + Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + + + Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + Body frame roll / phi angular speed (rad/s) + Body frame pitch / theta angular speed (rad/s) + Body frame yaw / psi angular speed (rad/s) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + Indicated airspeed, expressed as m/s * 100 + True airspeed, expressed as m/s * 100 + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + + + The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (milliseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. + System ID + Component ID + First log id (0 for first available) + Last log id (0xffff for last available) + + + Reply to LOG_REQUEST_LIST + Log id + Total number of logs + High log number + UTC timestamp of log in seconds since 1970, or 0 if not available + Size of the log (may be approximate) in bytes + + + Request a chunk of a log + System ID + Component ID + Log id (from LOG_ENTRY reply) + Offset into the log + Number of bytes + + + Reply to LOG_REQUEST_DATA + Log id (from LOG_ENTRY reply) + Offset into the log + Number of bytes (zero for end of log) + log data + + + Erase all logs + System ID + Component ID + + + Stop log transfer and resume normal logging + System ID + Component ID + + + data for injecting into the onboard GPS (used for DGPS) + System ID + Component ID + data length + raw data (110 is enough for 12 satellites of RTCMv2) + + + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS frame). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + Number of satellites visible. If unknown, set to 255 + Number of DGPS satellites + Age of DGPS info + + + Power supply status + 5V rail voltage in millivolts + servo rail voltage in millivolts + power supply status flags (see MAV_POWER_STATUS enum) + + + Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate. + See SERIAL_CONTROL_DEV enum + See SERIAL_CONTROL_FLAG enum + Timeout for reply data in milliseconds + Baudrate of transfer. Zero means no change. + how many bytes in this transfer + serial data + + + RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting + Time since boot of last baseline message received in ms. + Identification of connected RTK receiver. + GPS Week Number of last baseline + GPS Time of Week of last baseline + GPS-specific health report for RTK data. + Rate of baseline messages being received by GPS, in HZ + Current number of sats used for RTK calculation. + Coordinate system of baseline. 0 == ECEF, 1 == NED + Current baseline in ECEF x or NED north component in mm. + Current baseline in ECEF y or NED east component in mm. + Current baseline in ECEF z or NED down component in mm. + Current estimate of baseline accuracy. + Current number of integer ambiguity hypotheses. + + + RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting + Time since boot of last baseline message received in ms. + Identification of connected RTK receiver. + GPS Week Number of last baseline + GPS Time of Week of last baseline + GPS-specific health report for RTK data. + Rate of baseline messages being received by GPS, in HZ + Current number of sats used for RTK calculation. + Coordinate system of baseline. 0 == ECEF, 1 == NED + Current baseline in ECEF x or NED north component in mm. + Current baseline in ECEF y or NED east component in mm. + Current baseline in ECEF z or NED down component in mm. + Current estimate of baseline accuracy. + Current number of integer ambiguity hypotheses. + + + The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (milliseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + total data size in bytes (set on ACK only) + Width of a matrix or image + Height of a matrix or image + number of packets beeing sent (set on ACK only) + payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + JPEG quality out of [1,100] + + + sequence number (starting with 0 on every transmission) + image data bytes + + + Time since system boot + Minimum distance the sensor can measure in centimeters + Maximum distance the sensor can measure in centimeters + Current distance reading + Type from MAV_DISTANCE_SENSOR enum. + Onboard ID of the sensor + Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. + Measurement covariance in centimeters, 0 for unknown / invalid readings + + + Request for terrain data and terrain status + Latitude of SW corner of first grid (degrees *10^7) + Longitude of SW corner of first grid (in degrees *10^7) + Grid spacing in meters + Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + + + Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST + Latitude of SW corner of first grid (degrees *10^7) + Longitude of SW corner of first grid (in degrees *10^7) + Grid spacing in meters + bit within the terrain request mask + Terrain data in meters AMSL + + + Request that the vehicle report terrain height at the given location. Used by GCS to check if vehicle has all terrain data needed for a mission. + Latitude (degrees *10^7) + Longitude (degrees *10^7) + + + Response from a TERRAIN_CHECK request + Latitude (degrees *10^7) + Longitude (degrees *10^7) + grid spacing (zero if terrain at this location unavailable) + Terrain height in meters AMSL + Current vehicle height above lat/lon terrain height (meters) + Number of 4x4 terrain blocks waiting to be received or read from disk + Number of 4x4 terrain blocks in memory + + + Barometer readings for 2nd barometer + Timestamp (milliseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + Motion capture attitude and position + Timestamp (micros since boot or Unix epoch) + Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + X position in meters (NED) + Y position in meters (NED) + Z position in meters (NED) + + + Set the vehicle attitude and body angular rates. + Timestamp (micros since boot or Unix epoch) + Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + System ID + Component ID + Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + + + Set the vehicle attitude and body angular rates. + Timestamp (micros since boot or Unix epoch) + Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + + + The current system altitude. + Timestamp (milliseconds since system boot) + This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. + This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + This is the altitude above the home position. It resets on each change of the current home position. + This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + + + The autopilot is requesting a resource (file, binary, other type of data) + Request ID. This ID should be re-used when sending back URI contents + The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + + + Barometer readings for 3rd barometer + Timestamp (milliseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + current motion information from a designated system + Timestamp in milliseconds since system boot + bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + AMSL, in meters + target velocity (0,0,0) for unknown + linear target acceleration (0,0,0) for unknown + (1 0 0 0 for unknown) + (0 0 0 for unknown) + eph epv + button states or switches of a tracker device + + + The smoothed, monotonic system state used to feed the control loops of the system. + Timestamp (micros since boot or Unix epoch) + X acceleration in body frame + Y acceleration in body frame + Z acceleration in body frame + X velocity in body frame + Y velocity in body frame + Z velocity in body frame + X position in local frame + Y position in local frame + Z position in local frame + Airspeed, set to -1 if unknown + Variance of body velocity estimate + Variance in local position + The attitude, represented as Quaternion + Angular rate in roll axis + Angular rate in pitch axis + Angular rate in yaw axis + + + Battery information + Battery ID + Function of the battery + Type (chemistry) of the battery + Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. + Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. + Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate + Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + + + Version and capability of autopilot software + bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) + Firmware version number + Middleware version number + Operating system version number + HW / board version (last 8 bytes should be silicon ID, if any) + Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + ID of the board vendor + ID of the product + UID if provided by hardware + + + The location of a landing area captured from a downward facing camera + Timestamp (micros since boot or Unix epoch) + The ID of the target if multiple targets are present + MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. + X-axis angular offset (in radians) of the target from the center of the image + Y-axis angular offset (in radians) of the target from the center of the image + Distance to the target from the vehicle in meters + Size in radians of target along x-axis + Size in radians of target along y-axis + + + + Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovaton test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovaton test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user. + Timestamp (micros since boot or Unix epoch) + Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. + Velocity innovation test ratio + Horizontal position innovation test ratio + Vertical position innovation test ratio + Magnetometer innovation test ratio + Height above terrain innovation test ratio + True airspeed innovation test ratio + Horizontal position 1-STD accuracy relative to the EKF local origin (m) + Vertical position 1-STD accuracy relative to the EKF local origin (m) + + + Timestamp (micros since boot or Unix epoch) + Wind in X (NED) direction in m/s + Wind in Y (NED) direction in m/s + Wind in Z (NED) direction in m/s + Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. + Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. + AMSL altitude (m) this measurement was taken at + Horizontal speed 1-STD accuracy + Vertical speed 1-STD accuracy + + + Vibration levels and accelerometer clipping + Timestamp (micros since boot or Unix epoch) + Vibration levels on X-axis + Vibration levels on Y-axis + Vibration levels on Z-axis + first accelerometer clipping count + second accelerometer clipping count + third accelerometer clipping count + + + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION command. The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The position the system will return to and land on. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84, in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + Local X position of this position in the local coordinate frame + Local Y position of this position in the local coordinate frame + Local Z position of this position in the local coordinate frame + World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + + + The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. + System ID. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84, in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + Local X position of this position in the local coordinate frame + Local Y position of this position in the local coordinate frame + Local Z position of this position in the local coordinate frame + World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + + + This interface replaces DATA_STREAM + The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + + + Provides state for additional features + The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + + + The location and information of an ADSB vehicle + ICAO address + Latitude, expressed as degrees * 1E7 + Longitude, expressed as degrees * 1E7 + Type from ADSB_ALTITUDE_TYPE enum + Altitude(ASL) in millimeters + Course over ground in centidegrees + The horizontal velocity in centimeters/second + The vertical velocity in centimeters/second, positive is up + The callsign, 8+null + Type from ADSB_EMITTER_TYPE enum + Time since last communication in seconds + Flags to indicate various statuses including valid data fields + Squawk code + + + Message implementing parts of the V2 payload specs in V1 frames for transitional support. + Network ID (0 for broadcast) + System ID (0 for broadcast) + Component ID (0 for broadcast) + A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + + + Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Starting address of the debug variables + Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + Memory contents at specified address + + + Name + Timestamp + x + y + z + + + Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Timestamp (milliseconds since system boot) + Name of the debug variable + Floating point value + + + Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Timestamp (milliseconds since system boot) + Name of the debug variable + Signed integer value + + + Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). + Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + Status text message, without null termination character + + + Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N. + Timestamp (milliseconds since system boot) + index of debug variable + DEBUG value + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/matrixpilot.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/matrixpilot.xml new file mode 100644 index 0000000..29d368d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/matrixpilot.xml @@ -0,0 +1,284 @@ + + + common.xml + + + + + + + + Action required when performing CMD_PREFLIGHT_STORAGE + + Read all parameters from storage + + + Write all parameters to storage + + + Clear all parameters in storage + + + Read specific parameters from storage + + + Write specific parameters to storage + + + Clear specific parameters in storage + + + do nothing + + + + + + Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. + Storage action: Action defined by MAV_PREFLIGHT_STORAGE_ACTION_ADVANCED + Storage area as defined by parameter database + Storage flags as defined by parameter database + Empty + Empty + Empty + Empty + + + + + + + + + Depreciated but used as a compiler flag. Do not remove + System ID + Component ID + + + Reqest reading of flexifunction data + System ID + Component ID + Type of flexifunction data requested + index into data where needed + + + Flexifunction type and parameters for component at function index from buffer + System ID + Component ID + Function index + Total count of functions + Address in the flexifunction data, Set to 0xFFFF to use address in target memory + Size of the + Settings data + + + Flexifunction type and parameters for component at function index from buffer + System ID + Component ID + Function index + result of acknowledge, 0=fail, 1=good + + + Acknowldge sucess or failure of a flexifunction command + System ID + Component ID + 0=inputs, 1=outputs + index of first directory entry to write + count of directory entries to write + Settings data + + + Acknowldge sucess or failure of a flexifunction command + System ID + Component ID + 0=inputs, 1=outputs + index of first directory entry to write + count of directory entries to write + result of acknowledge, 0=fail, 1=good + + + Acknowldge sucess or failure of a flexifunction command + System ID + Component ID + Flexifunction command type + + + Acknowldge sucess or failure of a flexifunction command + Command acknowledged + result of acknowledge + + + Backwards compatible MAVLink version of SERIAL_UDB_EXTRA - F2: Format Part A + Serial UDB Extra Time + Serial UDB Extra Status + Serial UDB Extra Latitude + Serial UDB Extra Longitude + Serial UDB Extra Altitude + Serial UDB Extra Waypoint Index + Serial UDB Extra Rmat 0 + Serial UDB Extra Rmat 1 + Serial UDB Extra Rmat 2 + Serial UDB Extra Rmat 3 + Serial UDB Extra Rmat 4 + Serial UDB Extra Rmat 5 + Serial UDB Extra Rmat 6 + Serial UDB Extra Rmat 7 + Serial UDB Extra Rmat 8 + Serial UDB Extra GPS Course Over Ground + Serial UDB Extra Speed Over Ground + Serial UDB Extra CPU Load + Serial UDB Extra Voltage in MilliVolts + Serial UDB Extra 3D IMU Air Speed + Serial UDB Extra Estimated Wind 0 + Serial UDB Extra Estimated Wind 1 + Serial UDB Extra Estimated Wind 2 + Serial UDB Extra Magnetic Field Earth 0 + Serial UDB Extra Magnetic Field Earth 1 + Serial UDB Extra Magnetic Field Earth 2 + Serial UDB Extra Number of Sattelites in View + Serial UDB Extra GPS Horizontal Dilution of Precision + + + Backwards compatible version of SERIAL_UDB_EXTRA - F2: Part B + Serial UDB Extra Time + Serial UDB Extra PWM Input Channel 1 + Serial UDB Extra PWM Input Channel 2 + Serial UDB Extra PWM Input Channel 3 + Serial UDB Extra PWM Input Channel 4 + Serial UDB Extra PWM Input Channel 5 + Serial UDB Extra PWM Input Channel 6 + Serial UDB Extra PWM Input Channel 7 + Serial UDB Extra PWM Input Channel 8 + Serial UDB Extra PWM Input Channel 9 + Serial UDB Extra PWM Input Channel 10 + Serial UDB Extra PWM Output Channel 1 + Serial UDB Extra PWM Output Channel 2 + Serial UDB Extra PWM Output Channel 3 + Serial UDB Extra PWM Output Channel 4 + Serial UDB Extra PWM Output Channel 5 + Serial UDB Extra PWM Output Channel 6 + Serial UDB Extra PWM Output Channel 7 + Serial UDB Extra PWM Output Channel 8 + Serial UDB Extra PWM Output Channel 9 + Serial UDB Extra PWM Output Channel 10 + Serial UDB Extra IMU Location X + Serial UDB Extra IMU Location Y + Serial UDB Extra IMU Location Z + Serial UDB Extra Status Flags + Serial UDB Extra Oscillator Failure Count + Serial UDB Extra IMU Velocity X + Serial UDB Extra IMU Velocity Y + Serial UDB Extra IMU Velocity Z + Serial UDB Extra Current Waypoint Goal X + Serial UDB Extra Current Waypoint Goal Y + Serial UDB Extra Current Waypoint Goal Z + Serial UDB Extra Stack Memory Free + + + Backwards compatible version of SERIAL_UDB_EXTRA F4: format + Serial UDB Extra Roll Stabilization with Ailerons Enabled + Serial UDB Extra Roll Stabilization with Rudder Enabled + Serial UDB Extra Pitch Stabilization Enabled + Serial UDB Extra Yaw Stabilization using Rudder Enabled + Serial UDB Extra Yaw Stabilization using Ailerons Enabled + Serial UDB Extra Navigation with Ailerons Enabled + Serial UDB Extra Navigation with Rudder Enabled + Serial UDB Extra Type of Alitude Hold when in Stabilized Mode + Serial UDB Extra Type of Alitude Hold when in Waypoint Mode + Serial UDB Extra Firmware racing mode enabled + + + Backwards compatible version of SERIAL_UDB_EXTRA F5: format + Serial UDB YAWKP_AILERON Gain for Proporional control of navigation + Serial UDB YAWKD_AILERON Gain for Rate control of navigation + Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization + Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization + YAW_STABILIZATION_AILERON Proportional control + Gain For Boosting Manual Aileron control When Plane Stabilized + + + Backwards compatible version of SERIAL_UDB_EXTRA F6: format + Serial UDB Extra PITCHGAIN Proportional Control + Serial UDB Extra Pitch Rate Control + Serial UDB Extra Rudder to Elevator Mix + Serial UDB Extra Roll to Elevator Mix + Gain For Boosting Manual Elevator control When Plane Stabilized + + + Backwards compatible version of SERIAL_UDB_EXTRA F7: format + Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation + Serial UDB YAWKD_RUDDER Gain for Rate control of navigation + Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization + Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization + SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized + Serial UDB Extra Return To Landing - Angle to Pitch Plane Down + + + Backwards compatible version of SERIAL_UDB_EXTRA F8: format + Serial UDB Extra HEIGHT_TARGET_MAX + Serial UDB Extra HEIGHT_TARGET_MIN + Serial UDB Extra ALT_HOLD_THROTTLE_MIN + Serial UDB Extra ALT_HOLD_THROTTLE_MAX + Serial UDB Extra ALT_HOLD_PITCH_MIN + Serial UDB Extra ALT_HOLD_PITCH_MAX + Serial UDB Extra ALT_HOLD_PITCH_HIGH + + + Backwards compatible version of SERIAL_UDB_EXTRA F13: format + Serial UDB Extra GPS Week Number + Serial UDB Extra MP Origin Latitude + Serial UDB Extra MP Origin Longitude + Serial UDB Extra MP Origin Altitude Above Sea Level + + + Backwards compatible version of SERIAL_UDB_EXTRA F14: format + Serial UDB Extra Wind Estimation Enabled + Serial UDB Extra Type of GPS Unit + Serial UDB Extra Dead Reckoning Enabled + Serial UDB Extra Type of UDB Hardware + Serial UDB Extra Type of Airframe + Serial UDB Extra Reboot Regitster of DSPIC + Serial UDB Extra Last dspic Trap Flags + Serial UDB Extra Type Program Address of Last Trap + Serial UDB Extra Number of Ocillator Failures + Serial UDB Extra UDB Internal Clock Configuration + Serial UDB Extra Type of Flight Plan + + + Backwards compatible version of SERIAL_UDB_EXTRA F15 and F16: format + Serial UDB Extra Model Name Of Vehicle + Serial UDB Extra Registraton Number of Vehicle + + + Serial UDB Extra Name of Expected Lead Pilot + Serial UDB Extra URL of Lead Pilot or Team + + + The altitude measured by sensors and IMU + Timestamp (milliseconds since system boot) + GPS altitude in meters, expressed as * 1000 (millimeters), above MSL + IMU altitude above ground in meters, expressed as * 1000 (millimeters) + barometeric altitude above ground in meters, expressed as * 1000 (millimeters) + Optical flow altitude above ground in meters, expressed as * 1000 (millimeters) + Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters) + Extra altitude above ground in meters, expressed as * 1000 (millimeters) + + + The airspeed measured by sensors and IMU + Timestamp (milliseconds since system boot) + Airspeed estimate from IMU, cm/s + Pitot measured forward airpseed, cm/s + Hot wire anenometer measured airspeed, cm/s + Ultrasonic measured airspeed, cm/s + Angle of attack sensor, degrees * 10 + Yaw angle sensor, degrees * 10 + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/minimal.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/minimal.xml new file mode 100644 index 0000000..88985a5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/minimal.xml @@ -0,0 +1,189 @@ + + + 2 + + + Micro air vehicle / autopilot classes. This identifies the individual model. + + Generic autopilot, full support for everything + + + PIXHAWK autopilot, http://pixhawk.ethz.ch + + + SLUGS autopilot, http://slugsuav.soe.ucsc.edu + + + ArduPilotMega / ArduCopter, http://diydrones.com + + + OpenPilot, http://openpilot.org + + + Generic autopilot only supporting simple waypoints + + + Generic autopilot supporting waypoints and other simple navigation commands + + + Generic autopilot supporting the full mission command set + + + No valid autopilot, e.g. a GCS or other MAVLink component + + + PPZ UAV - http://nongnu.org/paparazzi + + + UAV Dev Board + + + FlexiPilot + + + + + Generic micro air vehicle. + + + Fixed wing aircraft. + + + Quadrotor + + + Coaxial helicopter + + + Normal helicopter with tail rotor. + + + Ground installation + + + Operator control unit / ground control station + + + Airship, controlled + + + Free balloon, uncontrolled + + + Rocket + + + Ground rover + + + Surface vessel, boat, ship + + + Submarine + + + Hexarotor + + + Octorotor + + + Octorotor + + + Flapping wing + + + + These flags encode the MAV mode. + + 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. + + + 0b01000000 remote control input is enabled. + + + 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. + + + 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. + + + 0b00001000 guided mode enabled, system flies MISSIONs / mission items. + + + 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. + + + 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. + + + 0b00000001 Reserved for future use. + + + + These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. + + First bit: 10000000 + + + Second bit: 01000000 + + + Third bit: 00100000 + + + Fourth bit: 00010000 + + + Fifth bit: 00001000 + + + Sixt bit: 00000100 + + + Seventh bit: 00000010 + + + Eighth bit: 00000001 + + + + + Uninitialized system, state is unknown. + + + System is booting up. + + + System is calibrating and not flight-ready. + + + System is grounded and on standby. It can be launched any time. + + + System is active and might be already airborne. Motors are engaged. + + + System is in a non-normal flight mode. It can however still navigate. + + + System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. + + + System just initialized its power-down sequence, will shut down now. + + + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Autopilot type / class. defined in MAV_AUTOPILOT ENUM + System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + A bitfield for use for autopilot-specific flags. + System status flag, see MAV_STATE ENUM + MAVLink version + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/paparazzi.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/paparazzi.xml new file mode 100644 index 0000000..2200075 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/paparazzi.xml @@ -0,0 +1,38 @@ + + + common.xml + 3 + + + + + + Message encoding a mission script item. This message is emitted upon a request for the next script item. + System ID + Component ID + Sequence + The name of the mission script, NULL terminated. + + + Request script item with the sequence number seq. The response of the system to this message should be a SCRIPT_ITEM message. + System ID + Component ID + Sequence + + + Request the overall list of mission items from the system/component. + System ID + Component ID + + + This message is emitted as response to SCRIPT_REQUEST_LIST by the MAV to get the number of mission scripts. + System ID + Component ID + Number of script items in the sequence + + + This message informs about the currently active SCRIPT. + Active Sequence + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/python_array_test.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/python_array_test.xml new file mode 100644 index 0000000..f230d01 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/python_array_test.xml @@ -0,0 +1,67 @@ + + + +common.xml + + + Array test #0. + Stub field + Value array + Value array + Value array + Value array + + + Array test #1. + Value array + + + Array test #3. + Stub field + Value array + + + Array test #4. + Value array + Stub field + + + Array test #5. + Value array + Value array + + + Array test #6. + Stub field + Stub field + Stub field + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + + + Array test #7. + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + + + Array test #8. + Stub field + Value array + Value array + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/rosflight.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/rosflight.xml new file mode 100644 index 0000000..4cbee6f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/rosflight.xml @@ -0,0 +1,153 @@ + + + common.xml + + + + + + + + + + + + + + + + + + + + + + Pass commanded values directly to actuators + + + Command roll rate, pitch rate, yaw rate, and throttle + + + Command roll angle, pitch angle, yaw rate, and throttle + + + Command roll angle, pitch angle, yaw rate, and altitude above ground + + + + + Convenience value for specifying no fields should be ignored + + + Field value1 should be ignored + + + Field value2 should be ignored + + + Field value3 should be ignored + + + Field value4 should be ignored + + + + + + + + + + + + + + + + + + + Offboard control mode, see OFFBOARD_CONTROL_MODE + Bitfield specifying which fields should be ignored, see OFFBOARD_CONTROL_IGNORE + x control channel interpreted according to mode + y control channel, interpreted according to mode + z control channel, interpreted according to mode + F control channel, interpreted according to mode + + + Measurement timestamp as microseconds since boot + Acceleration along X axis + Acceleration along Y axis + Acceleration along Z axis + Angular speed around X axis + Angular speed around Y axis + Angular speed around Z axis + Internal temperature measurement + + + Magnetic field along X axis + Magnetic field along Y axis + Magnetic field along Z axis + + + Calculated Altitude (m) + Measured Differential Pressure (Pa) + Measured Temperature (K) + + + Measured Velocity + Measured Differential Pressure (Pa) + Measured Temperature (K) + + + Measurement timestamp as microseconds since boot + Acceleration along X axis + Acceleration along Y axis + Acceleration along Z axis + Angular speed around X axis + Angular speed around Y axis + Angular speed around Z axis + Internal temperature measurement + True if there is an image associated with this measurement + + + Name of the command struct + Type of command struct + Type of command struct + x value in the command struct + y value in the command struct + z value in the command struct + F value in the command struct + + + Sensor type + Range Measurement (m) + Max Range (m) + Min Range (m) + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/slugs.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/slugs.xml new file mode 100644 index 0000000..a985eab --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/slugs.xml @@ -0,0 +1,339 @@ + + + common.xml + + + + + + Does nothing. + 1 to arm, 0 to disarm + + + + + + Return vehicle to base. + 0: return to base, 1: track mobile base + + + Stops the vehicle from returning to base and resumes flight. + + + Turns the vehicle's visible or infrared lights on or off. + 0: visible lights, 1: infrared lights + 0: turn on, 1: turn off + + + Requests vehicle to send current mid-level commands to ground station. + + + Requests storage of mid-level commands. + Mid-level command storage: 0: read from flash/EEPROM, 1: write to flash/EEPROM + + + + + + Slugs-specific navigation modes. + + No change to SLUGS mode. + + + Vehicle is in liftoff mode. + + + Vehicle is in passthrough mode, being controlled by a pilot. + + + Vehicle is in waypoint mode, navigating to waypoints. + + + Vehicle is executing mid-level commands. + + + Vehicle is returning to the home location. + + + Vehicle is landing. + + + Lost connection with vehicle. + + + Vehicle is in selective passthrough mode, where selected surfaces are being manually controlled. + + + Vehicle is in ISR mode, performing reconaissance at a point specified by ISR_LOCATION message. + + + Vehicle is patrolling along lines between waypoints. + + + Vehicle is grounded or an error has occurred. + + + + + These flags encode the control surfaces for selective passthrough mode. If a bit is set then the pilot console + has control of the surface, and if not then the autopilot has control of the surface. + + 0b10000000 Throttle control passes through to pilot console. + + + 0b01000000 Left aileron control passes through to pilot console. + + + 0b00100000 Right aileron control passes through to pilot console. + + + 0b00010000 Rudder control passes through to pilot console. + + + 0b00001000 Left elevator control passes through to pilot console. + + + 0b00000100 Right elevator control passes through to pilot console. + + + 0b00000010 Left flap control passes through to pilot console. + + + 0b00000001 Right flap control passes through to pilot console. + + + + + + + + Sensor and DSC control loads. + Sensor DSC Load + Control DSC Load + Battery Voltage in millivolts + + + + Accelerometer and gyro biases. + Accelerometer X bias (m/s) + Accelerometer Y bias (m/s) + Accelerometer Z bias (m/s) + Gyro X bias (rad/s) + Gyro Y bias (rad/s) + Gyro Z bias (rad/s) + + + + Configurable diagnostic messages. + Diagnostic float 1 + Diagnostic float 2 + Diagnostic float 3 + Diagnostic short 1 + Diagnostic short 2 + Diagnostic short 3 + + + + Data used in the navigation algorithm. + Measured Airspeed prior to the nav filter in m/s + Commanded Roll + Commanded Pitch + Commanded Turn rate + Y component of the body acceleration + Total Distance to Run on this leg of Navigation + Remaining distance to Run on this leg of Navigation + Origin WP + Destination WP + Commanded altitude in 0.1 m + + + + Configurable data log probes to be used inside Simulink + Log value 1 + Log value 2 + Log value 3 + Log value 4 + Log value 5 + Log value 6 + + + + Pilot console PWM messges. + Year reported by Gps + Month reported by Gps + Day reported by Gps + Hour reported by Gps + Min reported by Gps + Sec reported by Gps + Clock Status. See table 47 page 211 OEMStar Manual + Visible satellites reported by Gps + Used satellites in Solution + GPS+GLONASS satellites in Solution + GPS and GLONASS usage mask (bit 0 GPS_used? bit_4 GLONASS_used?) + Percent used GPS + + + + Mid Level commands sent from the GS to the autopilot. These are only sent when being operated in mid-level commands mode from the ground. + The system setting the commands + Commanded Altitude in meters + Commanded Airspeed in m/s + Commanded Turnrate in rad/s + + + + This message sets the control surfaces for selective passthrough mode. + The system setting the commands + Bitfield containing the passthrough configuration, see CONTROL_SURFACE_FLAG ENUM. + + + + Orders generated to the SLUGS camera mount. + The system reporting the action + Order the mount to pan: -1 left, 0 No pan motion, +1 right + Order the mount to tilt: -1 down, 0 No tilt motion, +1 up + Order the zoom values 0 to 10 + Orders the camera mount to move home. The other fields are ignored when this field is set. 1: move home, 0 ignored + + + + Control for surface; pending and order to origin. + The system setting the commands + ID control surface send 0: throttle 1: aileron 2: elevator 3: rudder + Pending + Order to origin + + + + + + + Transmits the last known position of the mobile GS to the UAV. Very relevant when Track Mobile is enabled + The system reporting the action + Mobile Latitude + Mobile Longitude + + + + Control for camara. + The system setting the commands + ID 0: brightness 1: aperture 2: iris 3: ICR 4: backlight + 1: up/on 2: down/off 3: auto/reset/no action + + + + Transmits the position of watch + The system reporting the action + ISR Latitude + ISR Longitude + ISR Height + Option 1 + Option 2 + Option 3 + + + + + + + Transmits the readings from the voltage and current sensors + It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM + Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V + Depends on the value of r2Type (0) Current consumption in uS of PWM, 20 uS = 90Amp (1) Distance in cm (2) Distance in cm (3) Absolute value + + + + Transmits the actual Pan, Tilt and Zoom values of the camera unit + The actual Zoom Value + The Pan value in 10ths of degree + The Tilt value in 10ths of degree + + + + Transmits the actual status values UAV in flight + The ID system reporting the action + Latitude UAV + Longitude UAV + Altitude UAV + Speed UAV + Course UAV + + + + This contains the status of the GPS readings + Number of times checksum has failed + The quality indicator, 0=fix not available or invalid, 1=GPS fix, 2=C/A differential GPS, 6=Dead reckoning mode, 7=Manual input mode (fixed position), 8=Simulator mode, 9= WAAS a + Indicates if GN, GL or GP messages are being received + A = data valid, V = data invalid + Magnetic variation, degrees + Magnetic variation direction E/W. Easterly variation (E) subtracts from True course and Westerly variation (W) adds to True course + Positioning system mode indicator. A - Autonomous;D-Differential; E-Estimated (dead reckoning) mode;M-Manual input; N-Data not valid + + + + Transmits the diagnostics data from the Novatel OEMStar GPS + The Time Status. See Table 8 page 27 Novatel OEMStar Manual + Status Bitfield. See table 69 page 350 Novatel OEMstar Manual + solution Status. See table 44 page 197 + position type. See table 43 page 196 + velocity type. See table 43 page 196 + Age of the position solution in seconds + Times the CRC has failed since boot + + + + Diagnostic data Sensor MCU + Float field 1 + Float field 2 + Int 16 field 1 + Int 8 field 1 + + + + + The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions. This message allows the sensor and control MCUs to communicate version numbers on startup. + The onboard software version + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/test.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/test.xml new file mode 100644 index 0000000..02bc032 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/test.xml @@ -0,0 +1,31 @@ + + + 3 + + + Test all field types + char + string + uint8_t + uint16_t + uint32_t + uint64_t + int8_t + int16_t + int32_t + int64_t + float + double + uint8_t_array + uint16_t_array + uint32_t_array + uint64_t_array + int8_t_array + int16_t_array + int32_t_array + int64_t_array + float_array + double_array + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/ualberta.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/ualberta.xml new file mode 100644 index 0000000..bb57e84 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/message_definitions/ualberta.xml @@ -0,0 +1,76 @@ + + + common.xml + + + Available autopilot modes for ualberta uav + + Raw input pulse widts sent to output + + + Inputs are normalized using calibration, the converted back to raw pulse widths for output + + + dfsdfs + + + dfsfds + + + dfsdfsdfs + + + + Navigation filter mode + + + AHRS mode + + + INS/GPS initialization mode + + + INS/GPS mode + + + + Mode currently commanded by pilot + + sdf + + + dfs + + + Rotomotion mode + + + + + + Accelerometer and Gyro biases from the navigation filter + Timestamp (microseconds) + b_f[0] + b_f[1] + b_f[2] + b_f[0] + b_f[1] + b_f[2] + + + Complete set of calibration parameters for the radio + Aileron setpoints: left, center, right + Elevator setpoints: nose down, center, nose up + Rudder setpoints: nose left, center, nose right + Tail gyro mode/gain setpoints: heading hold, rate mode + Pitch curve setpoints (every 25%) + Throttle curve setpoints (every 25%) + + + System status specific to ualberta uav + System mode, see UALBERTA_AUTOPILOT_MODE ENUM + Navigation mode, see UALBERTA_NAV_MODE ENUM + Pilot mode, see UALBERTA_PILOT_MODE + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/protocol.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/protocol.h new file mode 100644 index 0000000..bf20708 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/protocol.h @@ -0,0 +1,339 @@ +#ifndef _MAVLINK_PROTOCOL_H_ +#define _MAVLINK_PROTOCOL_H_ + +#include "string.h" +#include "mavlink_types.h" + +/* + If you want MAVLink on a system that is native big-endian, + you need to define NATIVE_BIG_ENDIAN +*/ +#ifdef NATIVE_BIG_ENDIAN +# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN) +#else +# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN) +#endif + +#ifndef MAVLINK_STACK_BUFFER +#define MAVLINK_STACK_BUFFER 0 +#endif + +#ifndef MAVLINK_AVOID_GCC_STACK_BUG +# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__) +#endif + +#ifndef MAVLINK_ASSERT +#define MAVLINK_ASSERT(x) +#endif + +#ifndef MAVLINK_START_UART_SEND +#define MAVLINK_START_UART_SEND(chan, length) +#endif + +#ifndef MAVLINK_END_UART_SEND +#define MAVLINK_END_UART_SEND(chan, length) +#endif + +/* option to provide alternative implementation of mavlink_helpers.h */ +#ifdef MAVLINK_SEPARATE_HELPERS + + #define MAVLINK_HELPER + + /* decls in sync with those in mavlink_helpers.h */ + #ifndef MAVLINK_GET_CHANNEL_STATUS + MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan); + #endif + MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan); + #if MAVLINK_CRC_EXTRA + MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length, uint8_t crc_extra); + MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length, uint8_t crc_extra); + #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, + uint8_t length, uint8_t crc_extra); + #endif + #else + MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length); + MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length); + #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length); + #endif + #endif // MAVLINK_CRC_EXTRA + MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg); + MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg); + MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c); + MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, + mavlink_status_t* status, + uint8_t c, + mavlink_message_t* r_message, + mavlink_status_t* r_mavlink_status); + MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); + MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); + MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, + uint8_t* r_bit_index, uint8_t* buffer); + #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); + MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg); + #endif + +#else + + #define MAVLINK_HELPER static inline + #include "mavlink_helpers.h" + +#endif // MAVLINK_SEPARATE_HELPERS + +/** + * @brief Get the required buffer size for this message + */ +static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg) +{ + return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; +} + +#if MAVLINK_NEED_BYTE_SWAP +static inline void byte_swap_2(char *dst, const char *src) +{ + dst[0] = src[1]; + dst[1] = src[0]; +} +static inline void byte_swap_4(char *dst, const char *src) +{ + dst[0] = src[3]; + dst[1] = src[2]; + dst[2] = src[1]; + dst[3] = src[0]; +} +static inline void byte_swap_8(char *dst, const char *src) +{ + dst[0] = src[7]; + dst[1] = src[6]; + dst[2] = src[5]; + dst[3] = src[4]; + dst[4] = src[3]; + dst[5] = src[2]; + dst[6] = src[1]; + dst[7] = src[0]; +} +#elif !MAVLINK_ALIGNED_FIELDS +static inline void byte_copy_2(char *dst, const char *src) +{ + dst[0] = src[0]; + dst[1] = src[1]; +} +static inline void byte_copy_4(char *dst, const char *src) +{ + dst[0] = src[0]; + dst[1] = src[1]; + dst[2] = src[2]; + dst[3] = src[3]; +} +static inline void byte_copy_8(char *dst, const char *src) +{ + memcpy(dst, src, 8); +} +#endif + +#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b +#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b +#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b + +#if MAVLINK_NEED_BYTE_SWAP +#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) +#elif !MAVLINK_ALIGNED_FIELDS +#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) +#else +#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b +#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b +#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b +#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b +#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b +#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b +#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b +#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b +#endif + +/* + like memcpy(), but if src is NULL, do a memset to zero +*/ +static inline void mav_array_memcpy(void *dest, const void *src, size_t n) +{ + if (src == NULL) { + memset(dest, 0, n); + } else { + memcpy(dest, src, n); + } +} + +/* + * Place a char array into a buffer + */ +static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) +{ + mav_array_memcpy(&buf[wire_offset], b, array_length); + +} + +/* + * Place a uint8_t array into a buffer + */ +static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) +{ + mav_array_memcpy(&buf[wire_offset], b, array_length); + +} + +/* + * Place a int8_t array into a buffer + */ +static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) +{ + mav_array_memcpy(&buf[wire_offset], b, array_length); + +} + +#if MAVLINK_NEED_BYTE_SWAP +#define _MAV_PUT_ARRAY(TYPE, V) \ +static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ +{ \ + if (b == NULL) { \ + memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \ + } else { \ + uint16_t i; \ + for (i=0; imsgid = MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif +} + +/** + * @brief Pack a camera_stamped_small_imu message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_us Measurement timestamp as microseconds since boot + * @param xacc Acceleration along X axis + * @param yacc Acceleration along Y axis + * @param zacc Acceleration along Z axis + * @param xgyro Angular speed around X axis + * @param ygyro Angular speed around Y axis + * @param zgyro Angular speed around Z axis + * @param temperature Internal temperature measurement + * @param image True if there is an image associated with this measurement + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_camera_stamped_small_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_boot_us,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float temperature,uint8_t image) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_boot_us); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, temperature); + _mav_put_uint8_t(buf, 36, image); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#else + mavlink_camera_stamped_small_imu_t packet; + packet.time_boot_us = time_boot_us; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.temperature = temperature; + packet.image = image; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif +} + +/** + * @brief Encode a camera_stamped_small_imu struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param camera_stamped_small_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_camera_stamped_small_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_stamped_small_imu_t* camera_stamped_small_imu) +{ + return mavlink_msg_camera_stamped_small_imu_pack(system_id, component_id, msg, camera_stamped_small_imu->time_boot_us, camera_stamped_small_imu->xacc, camera_stamped_small_imu->yacc, camera_stamped_small_imu->zacc, camera_stamped_small_imu->xgyro, camera_stamped_small_imu->ygyro, camera_stamped_small_imu->zgyro, camera_stamped_small_imu->temperature, camera_stamped_small_imu->image); +} + +/** + * @brief Encode a camera_stamped_small_imu struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param camera_stamped_small_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_camera_stamped_small_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_stamped_small_imu_t* camera_stamped_small_imu) +{ + return mavlink_msg_camera_stamped_small_imu_pack_chan(system_id, component_id, chan, msg, camera_stamped_small_imu->time_boot_us, camera_stamped_small_imu->xacc, camera_stamped_small_imu->yacc, camera_stamped_small_imu->zacc, camera_stamped_small_imu->xgyro, camera_stamped_small_imu->ygyro, camera_stamped_small_imu->zgyro, camera_stamped_small_imu->temperature, camera_stamped_small_imu->image); +} + +/** + * @brief Send a camera_stamped_small_imu message + * @param chan MAVLink channel to send the message + * + * @param time_boot_us Measurement timestamp as microseconds since boot + * @param xacc Acceleration along X axis + * @param yacc Acceleration along Y axis + * @param zacc Acceleration along Z axis + * @param xgyro Angular speed around X axis + * @param ygyro Angular speed around Y axis + * @param zgyro Angular speed around Z axis + * @param temperature Internal temperature measurement + * @param image True if there is an image associated with this measurement + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_camera_stamped_small_imu_send(mavlink_channel_t chan, uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature, uint8_t image) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_boot_us); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, temperature); + _mav_put_uint8_t(buf, 36, image); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, buf, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, buf, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif +#else + mavlink_camera_stamped_small_imu_t packet; + packet.time_boot_us = time_boot_us; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.temperature = temperature; + packet.image = image; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_camera_stamped_small_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature, uint8_t image) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_boot_us); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, temperature); + _mav_put_uint8_t(buf, 36, image); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, buf, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, buf, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif +#else + mavlink_camera_stamped_small_imu_t *packet = (mavlink_camera_stamped_small_imu_t *)msgbuf; + packet->time_boot_us = time_boot_us; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->temperature = temperature; + packet->image = image; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, (const char *)packet, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, (const char *)packet, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE CAMERA_STAMPED_SMALL_IMU UNPACKING + + +/** + * @brief Get field time_boot_us from camera_stamped_small_imu message + * + * @return Measurement timestamp as microseconds since boot + */ +static inline uint64_t mavlink_msg_camera_stamped_small_imu_get_time_boot_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field xacc from camera_stamped_small_imu message + * + * @return Acceleration along X axis + */ +static inline float mavlink_msg_camera_stamped_small_imu_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yacc from camera_stamped_small_imu message + * + * @return Acceleration along Y axis + */ +static inline float mavlink_msg_camera_stamped_small_imu_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field zacc from camera_stamped_small_imu message + * + * @return Acceleration along Z axis + */ +static inline float mavlink_msg_camera_stamped_small_imu_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field xgyro from camera_stamped_small_imu message + * + * @return Angular speed around X axis + */ +static inline float mavlink_msg_camera_stamped_small_imu_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field ygyro from camera_stamped_small_imu message + * + * @return Angular speed around Y axis + */ +static inline float mavlink_msg_camera_stamped_small_imu_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field zgyro from camera_stamped_small_imu message + * + * @return Angular speed around Z axis + */ +static inline float mavlink_msg_camera_stamped_small_imu_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field temperature from camera_stamped_small_imu message + * + * @return Internal temperature measurement + */ +static inline float mavlink_msg_camera_stamped_small_imu_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field image from camera_stamped_small_imu message + * + * @return True if there is an image associated with this measurement + */ +static inline uint8_t mavlink_msg_camera_stamped_small_imu_get_image(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Decode a camera_stamped_small_imu message into a struct + * + * @param msg The message to decode + * @param camera_stamped_small_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_camera_stamped_small_imu_decode(const mavlink_message_t* msg, mavlink_camera_stamped_small_imu_t* camera_stamped_small_imu) +{ +#if MAVLINK_NEED_BYTE_SWAP + camera_stamped_small_imu->time_boot_us = mavlink_msg_camera_stamped_small_imu_get_time_boot_us(msg); + camera_stamped_small_imu->xacc = mavlink_msg_camera_stamped_small_imu_get_xacc(msg); + camera_stamped_small_imu->yacc = mavlink_msg_camera_stamped_small_imu_get_yacc(msg); + camera_stamped_small_imu->zacc = mavlink_msg_camera_stamped_small_imu_get_zacc(msg); + camera_stamped_small_imu->xgyro = mavlink_msg_camera_stamped_small_imu_get_xgyro(msg); + camera_stamped_small_imu->ygyro = mavlink_msg_camera_stamped_small_imu_get_ygyro(msg); + camera_stamped_small_imu->zgyro = mavlink_msg_camera_stamped_small_imu_get_zgyro(msg); + camera_stamped_small_imu->temperature = mavlink_msg_camera_stamped_small_imu_get_temperature(msg); + camera_stamped_small_imu->image = mavlink_msg_camera_stamped_small_imu_get_image(msg); +#else + memcpy(camera_stamped_small_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_diff_pressure.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_diff_pressure.h new file mode 100644 index 0000000..f7277c0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_diff_pressure.h @@ -0,0 +1,257 @@ +// MESSAGE DIFF_PRESSURE PACKING + +#define MAVLINK_MSG_ID_DIFF_PRESSURE 184 + +typedef struct __mavlink_diff_pressure_t +{ + float velocity; /*< Measured Velocity*/ + float diff_pressure; /*< Measured Differential Pressure (Pa)*/ + float temperature; /*< Measured Temperature (K)*/ +} mavlink_diff_pressure_t; + +#define MAVLINK_MSG_ID_DIFF_PRESSURE_LEN 12 +#define MAVLINK_MSG_ID_184_LEN 12 + +#define MAVLINK_MSG_ID_DIFF_PRESSURE_CRC 169 +#define MAVLINK_MSG_ID_184_CRC 169 + + + +#define MAVLINK_MESSAGE_INFO_DIFF_PRESSURE { \ + "DIFF_PRESSURE", \ + 3, \ + { { "velocity", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_diff_pressure_t, velocity) }, \ + { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_diff_pressure_t, diff_pressure) }, \ + { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_diff_pressure_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a diff_pressure message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param velocity Measured Velocity + * @param diff_pressure Measured Differential Pressure (Pa) + * @param temperature Measured Temperature (K) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_diff_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float velocity, float diff_pressure, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DIFF_PRESSURE_LEN]; + _mav_put_float(buf, 0, velocity); + _mav_put_float(buf, 4, diff_pressure); + _mav_put_float(buf, 8, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#else + mavlink_diff_pressure_t packet; + packet.velocity = velocity; + packet.diff_pressure = diff_pressure; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DIFF_PRESSURE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN, MAVLINK_MSG_ID_DIFF_PRESSURE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif +} + +/** + * @brief Pack a diff_pressure message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param velocity Measured Velocity + * @param diff_pressure Measured Differential Pressure (Pa) + * @param temperature Measured Temperature (K) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_diff_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float velocity,float diff_pressure,float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DIFF_PRESSURE_LEN]; + _mav_put_float(buf, 0, velocity); + _mav_put_float(buf, 4, diff_pressure); + _mav_put_float(buf, 8, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#else + mavlink_diff_pressure_t packet; + packet.velocity = velocity; + packet.diff_pressure = diff_pressure; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DIFF_PRESSURE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN, MAVLINK_MSG_ID_DIFF_PRESSURE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif +} + +/** + * @brief Encode a diff_pressure struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param diff_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_diff_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_diff_pressure_t* diff_pressure) +{ + return mavlink_msg_diff_pressure_pack(system_id, component_id, msg, diff_pressure->velocity, diff_pressure->diff_pressure, diff_pressure->temperature); +} + +/** + * @brief Encode a diff_pressure struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param diff_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_diff_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_diff_pressure_t* diff_pressure) +{ + return mavlink_msg_diff_pressure_pack_chan(system_id, component_id, chan, msg, diff_pressure->velocity, diff_pressure->diff_pressure, diff_pressure->temperature); +} + +/** + * @brief Send a diff_pressure message + * @param chan MAVLink channel to send the message + * + * @param velocity Measured Velocity + * @param diff_pressure Measured Differential Pressure (Pa) + * @param temperature Measured Temperature (K) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_diff_pressure_send(mavlink_channel_t chan, float velocity, float diff_pressure, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DIFF_PRESSURE_LEN]; + _mav_put_float(buf, 0, velocity); + _mav_put_float(buf, 4, diff_pressure); + _mav_put_float(buf, 8, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, buf, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN, MAVLINK_MSG_ID_DIFF_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, buf, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif +#else + mavlink_diff_pressure_t packet; + packet.velocity = velocity; + packet.diff_pressure = diff_pressure; + packet.temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN, MAVLINK_MSG_ID_DIFF_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_DIFF_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_diff_pressure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float velocity, float diff_pressure, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, velocity); + _mav_put_float(buf, 4, diff_pressure); + _mav_put_float(buf, 8, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, buf, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN, MAVLINK_MSG_ID_DIFF_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, buf, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif +#else + mavlink_diff_pressure_t *packet = (mavlink_diff_pressure_t *)msgbuf; + packet->velocity = velocity; + packet->diff_pressure = diff_pressure; + packet->temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN, MAVLINK_MSG_ID_DIFF_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE DIFF_PRESSURE UNPACKING + + +/** + * @brief Get field velocity from diff_pressure message + * + * @return Measured Velocity + */ +static inline float mavlink_msg_diff_pressure_get_velocity(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field diff_pressure from diff_pressure message + * + * @return Measured Differential Pressure (Pa) + */ +static inline float mavlink_msg_diff_pressure_get_diff_pressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field temperature from diff_pressure message + * + * @return Measured Temperature (K) + */ +static inline float mavlink_msg_diff_pressure_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Decode a diff_pressure message into a struct + * + * @param msg The message to decode + * @param diff_pressure C-struct to decode the message contents into + */ +static inline void mavlink_msg_diff_pressure_decode(const mavlink_message_t* msg, mavlink_diff_pressure_t* diff_pressure) +{ +#if MAVLINK_NEED_BYTE_SWAP + diff_pressure->velocity = mavlink_msg_diff_pressure_get_velocity(msg); + diff_pressure->diff_pressure = mavlink_msg_diff_pressure_get_diff_pressure(msg); + diff_pressure->temperature = mavlink_msg_diff_pressure_get_temperature(msg); +#else + memcpy(diff_pressure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_named_command_struct.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_named_command_struct.h new file mode 100644 index 0000000..2aa1064 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_named_command_struct.h @@ -0,0 +1,345 @@ +// MESSAGE NAMED_COMMAND_STRUCT PACKING + +#define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT 186 + +typedef struct __mavlink_named_command_struct_t +{ + float x; /*< x value in the command struct*/ + float y; /*< y value in the command struct*/ + float z; /*< z value in the command struct*/ + float F; /*< F value in the command struct*/ + char name[10]; /*< Name of the command struct*/ + uint8_t type; /*< Type of command struct*/ + uint8_t ignore; /*< Type of command struct*/ +} mavlink_named_command_struct_t; + +#define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN 28 +#define MAVLINK_MSG_ID_186_LEN 28 + +#define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC 169 +#define MAVLINK_MSG_ID_186_CRC 169 + +#define MAVLINK_MSG_NAMED_COMMAND_STRUCT_FIELD_NAME_LEN 10 + +#define MAVLINK_MESSAGE_INFO_NAMED_COMMAND_STRUCT { \ + "NAMED_COMMAND_STRUCT", \ + 7, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_named_command_struct_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_command_struct_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_named_command_struct_t, z) }, \ + { "F", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_named_command_struct_t, F) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 10, 16, offsetof(mavlink_named_command_struct_t, name) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_named_command_struct_t, type) }, \ + { "ignore", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_named_command_struct_t, ignore) }, \ + } \ +} + + +/** + * @brief Pack a named_command_struct message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param name Name of the command struct + * @param type Type of command struct + * @param ignore Type of command struct + * @param x x value in the command struct + * @param y y value in the command struct + * @param z z value in the command struct + * @param F F value in the command struct + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_command_struct_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *name, uint8_t type, uint8_t ignore, float x, float y, float z, float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 26, type); + _mav_put_uint8_t(buf, 27, ignore); + _mav_put_char_array(buf, 16, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#else + mavlink_named_command_struct_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.F = F; + packet.type = type; + packet.ignore = ignore; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif +} + +/** + * @brief Pack a named_command_struct message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param name Name of the command struct + * @param type Type of command struct + * @param ignore Type of command struct + * @param x x value in the command struct + * @param y y value in the command struct + * @param z z value in the command struct + * @param F F value in the command struct + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_command_struct_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *name,uint8_t type,uint8_t ignore,float x,float y,float z,float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 26, type); + _mav_put_uint8_t(buf, 27, ignore); + _mav_put_char_array(buf, 16, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#else + mavlink_named_command_struct_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.F = F; + packet.type = type; + packet.ignore = ignore; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif +} + +/** + * @brief Encode a named_command_struct struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param named_command_struct C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_command_struct_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_command_struct_t* named_command_struct) +{ + return mavlink_msg_named_command_struct_pack(system_id, component_id, msg, named_command_struct->name, named_command_struct->type, named_command_struct->ignore, named_command_struct->x, named_command_struct->y, named_command_struct->z, named_command_struct->F); +} + +/** + * @brief Encode a named_command_struct struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param named_command_struct C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_command_struct_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_command_struct_t* named_command_struct) +{ + return mavlink_msg_named_command_struct_pack_chan(system_id, component_id, chan, msg, named_command_struct->name, named_command_struct->type, named_command_struct->ignore, named_command_struct->x, named_command_struct->y, named_command_struct->z, named_command_struct->F); +} + +/** + * @brief Send a named_command_struct message + * @param chan MAVLink channel to send the message + * + * @param name Name of the command struct + * @param type Type of command struct + * @param ignore Type of command struct + * @param x x value in the command struct + * @param y y value in the command struct + * @param z z value in the command struct + * @param F F value in the command struct + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_named_command_struct_send(mavlink_channel_t chan, const char *name, uint8_t type, uint8_t ignore, float x, float y, float z, float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 26, type); + _mav_put_uint8_t(buf, 27, ignore); + _mav_put_char_array(buf, 16, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, buf, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, buf, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif +#else + mavlink_named_command_struct_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.F = F; + packet.type = type; + packet.ignore = ignore; + mav_array_memcpy(packet.name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_named_command_struct_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *name, uint8_t type, uint8_t ignore, float x, float y, float z, float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 26, type); + _mav_put_uint8_t(buf, 27, ignore); + _mav_put_char_array(buf, 16, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, buf, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, buf, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif +#else + mavlink_named_command_struct_t *packet = (mavlink_named_command_struct_t *)msgbuf; + packet->x = x; + packet->y = y; + packet->z = z; + packet->F = F; + packet->type = type; + packet->ignore = ignore; + mav_array_memcpy(packet->name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, (const char *)packet, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, (const char *)packet, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE NAMED_COMMAND_STRUCT UNPACKING + + +/** + * @brief Get field name from named_command_struct message + * + * @return Name of the command struct + */ +static inline uint16_t mavlink_msg_named_command_struct_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 10, 16); +} + +/** + * @brief Get field type from named_command_struct message + * + * @return Type of command struct + */ +static inline uint8_t mavlink_msg_named_command_struct_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 26); +} + +/** + * @brief Get field ignore from named_command_struct message + * + * @return Type of command struct + */ +static inline uint8_t mavlink_msg_named_command_struct_get_ignore(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 27); +} + +/** + * @brief Get field x from named_command_struct message + * + * @return x value in the command struct + */ +static inline float mavlink_msg_named_command_struct_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from named_command_struct message + * + * @return y value in the command struct + */ +static inline float mavlink_msg_named_command_struct_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from named_command_struct message + * + * @return z value in the command struct + */ +static inline float mavlink_msg_named_command_struct_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field F from named_command_struct message + * + * @return F value in the command struct + */ +static inline float mavlink_msg_named_command_struct_get_F(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a named_command_struct message into a struct + * + * @param msg The message to decode + * @param named_command_struct C-struct to decode the message contents into + */ +static inline void mavlink_msg_named_command_struct_decode(const mavlink_message_t* msg, mavlink_named_command_struct_t* named_command_struct) +{ +#if MAVLINK_NEED_BYTE_SWAP + named_command_struct->x = mavlink_msg_named_command_struct_get_x(msg); + named_command_struct->y = mavlink_msg_named_command_struct_get_y(msg); + named_command_struct->z = mavlink_msg_named_command_struct_get_z(msg); + named_command_struct->F = mavlink_msg_named_command_struct_get_F(msg); + mavlink_msg_named_command_struct_get_name(msg, named_command_struct->name); + named_command_struct->type = mavlink_msg_named_command_struct_get_type(msg); + named_command_struct->ignore = mavlink_msg_named_command_struct_get_ignore(msg); +#else + memcpy(named_command_struct, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_offboard_control.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_offboard_control.h new file mode 100644 index 0000000..39ca729 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_offboard_control.h @@ -0,0 +1,329 @@ +// MESSAGE OFFBOARD_CONTROL PACKING + +#define MAVLINK_MSG_ID_OFFBOARD_CONTROL 180 + +typedef struct __mavlink_offboard_control_t +{ + float x; /*< x control channel interpreted according to mode*/ + float y; /*< y control channel, interpreted according to mode*/ + float z; /*< z control channel, interpreted according to mode*/ + float F; /*< F control channel, interpreted according to mode*/ + uint8_t mode; /*< Offboard control mode, see OFFBOARD_CONTROL_MODE*/ + uint8_t ignore; /*< Bitfield specifying which fields should be ignored, see OFFBOARD_CONTROL_IGNORE*/ +} mavlink_offboard_control_t; + +#define MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN 18 +#define MAVLINK_MSG_ID_180_LEN 18 + +#define MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC 93 +#define MAVLINK_MSG_ID_180_CRC 93 + + + +#define MAVLINK_MESSAGE_INFO_OFFBOARD_CONTROL { \ + "OFFBOARD_CONTROL", \ + 6, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_offboard_control_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_offboard_control_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_offboard_control_t, z) }, \ + { "F", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_offboard_control_t, F) }, \ + { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_offboard_control_t, mode) }, \ + { "ignore", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_offboard_control_t, ignore) }, \ + } \ +} + + +/** + * @brief Pack a offboard_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param mode Offboard control mode, see OFFBOARD_CONTROL_MODE + * @param ignore Bitfield specifying which fields should be ignored, see OFFBOARD_CONTROL_IGNORE + * @param x x control channel interpreted according to mode + * @param y y control channel, interpreted according to mode + * @param z z control channel, interpreted according to mode + * @param F F control channel, interpreted according to mode + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_offboard_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t mode, uint8_t ignore, float x, float y, float z, float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 16, mode); + _mav_put_uint8_t(buf, 17, ignore); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#else + mavlink_offboard_control_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.F = F; + packet.mode = mode; + packet.ignore = ignore; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_OFFBOARD_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN, MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif +} + +/** + * @brief Pack a offboard_control message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mode Offboard control mode, see OFFBOARD_CONTROL_MODE + * @param ignore Bitfield specifying which fields should be ignored, see OFFBOARD_CONTROL_IGNORE + * @param x x control channel interpreted according to mode + * @param y y control channel, interpreted according to mode + * @param z z control channel, interpreted according to mode + * @param F F control channel, interpreted according to mode + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_offboard_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t mode,uint8_t ignore,float x,float y,float z,float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 16, mode); + _mav_put_uint8_t(buf, 17, ignore); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#else + mavlink_offboard_control_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.F = F; + packet.mode = mode; + packet.ignore = ignore; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_OFFBOARD_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN, MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif +} + +/** + * @brief Encode a offboard_control struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param offboard_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_offboard_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_offboard_control_t* offboard_control) +{ + return mavlink_msg_offboard_control_pack(system_id, component_id, msg, offboard_control->mode, offboard_control->ignore, offboard_control->x, offboard_control->y, offboard_control->z, offboard_control->F); +} + +/** + * @brief Encode a offboard_control struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param offboard_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_offboard_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_offboard_control_t* offboard_control) +{ + return mavlink_msg_offboard_control_pack_chan(system_id, component_id, chan, msg, offboard_control->mode, offboard_control->ignore, offboard_control->x, offboard_control->y, offboard_control->z, offboard_control->F); +} + +/** + * @brief Send a offboard_control message + * @param chan MAVLink channel to send the message + * + * @param mode Offboard control mode, see OFFBOARD_CONTROL_MODE + * @param ignore Bitfield specifying which fields should be ignored, see OFFBOARD_CONTROL_IGNORE + * @param x x control channel interpreted according to mode + * @param y y control channel, interpreted according to mode + * @param z z control channel, interpreted according to mode + * @param F F control channel, interpreted according to mode + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_offboard_control_send(mavlink_channel_t chan, uint8_t mode, uint8_t ignore, float x, float y, float z, float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 16, mode); + _mav_put_uint8_t(buf, 17, ignore); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, buf, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN, MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, buf, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif +#else + mavlink_offboard_control_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.F = F; + packet.mode = mode; + packet.ignore = ignore; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN, MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_offboard_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t mode, uint8_t ignore, float x, float y, float z, float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 16, mode); + _mav_put_uint8_t(buf, 17, ignore); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, buf, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN, MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, buf, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif +#else + mavlink_offboard_control_t *packet = (mavlink_offboard_control_t *)msgbuf; + packet->x = x; + packet->y = y; + packet->z = z; + packet->F = F; + packet->mode = mode; + packet->ignore = ignore; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, (const char *)packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN, MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, (const char *)packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE OFFBOARD_CONTROL UNPACKING + + +/** + * @brief Get field mode from offboard_control message + * + * @return Offboard control mode, see OFFBOARD_CONTROL_MODE + */ +static inline uint8_t mavlink_msg_offboard_control_get_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field ignore from offboard_control message + * + * @return Bitfield specifying which fields should be ignored, see OFFBOARD_CONTROL_IGNORE + */ +static inline uint8_t mavlink_msg_offboard_control_get_ignore(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field x from offboard_control message + * + * @return x control channel interpreted according to mode + */ +static inline float mavlink_msg_offboard_control_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from offboard_control message + * + * @return y control channel, interpreted according to mode + */ +static inline float mavlink_msg_offboard_control_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from offboard_control message + * + * @return z control channel, interpreted according to mode + */ +static inline float mavlink_msg_offboard_control_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field F from offboard_control message + * + * @return F control channel, interpreted according to mode + */ +static inline float mavlink_msg_offboard_control_get_F(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a offboard_control message into a struct + * + * @param msg The message to decode + * @param offboard_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_offboard_control_decode(const mavlink_message_t* msg, mavlink_offboard_control_t* offboard_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + offboard_control->x = mavlink_msg_offboard_control_get_x(msg); + offboard_control->y = mavlink_msg_offboard_control_get_y(msg); + offboard_control->z = mavlink_msg_offboard_control_get_z(msg); + offboard_control->F = mavlink_msg_offboard_control_get_F(msg); + offboard_control->mode = mavlink_msg_offboard_control_get_mode(msg); + offboard_control->ignore = mavlink_msg_offboard_control_get_ignore(msg); +#else + memcpy(offboard_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_rosflight_cmd.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_rosflight_cmd.h new file mode 100644 index 0000000..281fd65 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_rosflight_cmd.h @@ -0,0 +1,209 @@ +// MESSAGE ROSFLIGHT_CMD PACKING + +#define MAVLINK_MSG_ID_ROSFLIGHT_CMD 188 + +typedef struct __mavlink_rosflight_cmd_t +{ + uint8_t command; /*< */ +} mavlink_rosflight_cmd_t; + +#define MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN 1 +#define MAVLINK_MSG_ID_188_LEN 1 + +#define MAVLINK_MSG_ID_ROSFLIGHT_CMD_CRC 249 +#define MAVLINK_MSG_ID_188_CRC 249 + + + +#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_CMD { \ + "ROSFLIGHT_CMD", \ + 1, \ + { { "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rosflight_cmd_t, command) }, \ + } \ +} + + +/** + * @brief Pack a rosflight_cmd message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param command + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_cmd_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t command) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN]; + _mav_put_uint8_t(buf, 0, command); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#else + mavlink_rosflight_cmd_t packet; + packet.command = command; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_CMD; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif +} + +/** + * @brief Pack a rosflight_cmd message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param command + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_cmd_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t command) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN]; + _mav_put_uint8_t(buf, 0, command); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#else + mavlink_rosflight_cmd_t packet; + packet.command = command; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_CMD; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif +} + +/** + * @brief Encode a rosflight_cmd struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rosflight_cmd C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_cmd_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rosflight_cmd_t* rosflight_cmd) +{ + return mavlink_msg_rosflight_cmd_pack(system_id, component_id, msg, rosflight_cmd->command); +} + +/** + * @brief Encode a rosflight_cmd struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rosflight_cmd C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_cmd_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rosflight_cmd_t* rosflight_cmd) +{ + return mavlink_msg_rosflight_cmd_pack_chan(system_id, component_id, chan, msg, rosflight_cmd->command); +} + +/** + * @brief Send a rosflight_cmd message + * @param chan MAVLink channel to send the message + * + * @param command + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rosflight_cmd_send(mavlink_channel_t chan, uint8_t command) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN]; + _mav_put_uint8_t(buf, 0, command); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif +#else + mavlink_rosflight_cmd_t packet; + packet.command = command; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rosflight_cmd_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t command) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, command); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif +#else + mavlink_rosflight_cmd_t *packet = (mavlink_rosflight_cmd_t *)msgbuf; + packet->command = command; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ROSFLIGHT_CMD UNPACKING + + +/** + * @brief Get field command from rosflight_cmd message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_cmd_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Decode a rosflight_cmd message into a struct + * + * @param msg The message to decode + * @param rosflight_cmd C-struct to decode the message contents into + */ +static inline void mavlink_msg_rosflight_cmd_decode(const mavlink_message_t* msg, mavlink_rosflight_cmd_t* rosflight_cmd) +{ +#if MAVLINK_NEED_BYTE_SWAP + rosflight_cmd->command = mavlink_msg_rosflight_cmd_get_command(msg); +#else + memcpy(rosflight_cmd, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_rosflight_cmd_ack.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_rosflight_cmd_ack.h new file mode 100644 index 0000000..4e8d931 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_rosflight_cmd_ack.h @@ -0,0 +1,233 @@ +// MESSAGE ROSFLIGHT_CMD_ACK PACKING + +#define MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK 189 + +typedef struct __mavlink_rosflight_cmd_ack_t +{ + uint8_t command; /*< */ + uint8_t success; /*< */ +} mavlink_rosflight_cmd_ack_t; + +#define MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN 2 +#define MAVLINK_MSG_ID_189_LEN 2 + +#define MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_CRC 113 +#define MAVLINK_MSG_ID_189_CRC 113 + + + +#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_CMD_ACK { \ + "ROSFLIGHT_CMD_ACK", \ + 2, \ + { { "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rosflight_cmd_ack_t, command) }, \ + { "success", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_rosflight_cmd_ack_t, success) }, \ + } \ +} + + +/** + * @brief Pack a rosflight_cmd_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param command + * @param success + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_cmd_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t command, uint8_t success) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN]; + _mav_put_uint8_t(buf, 0, command); + _mav_put_uint8_t(buf, 1, success); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#else + mavlink_rosflight_cmd_ack_t packet; + packet.command = command; + packet.success = success; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif +} + +/** + * @brief Pack a rosflight_cmd_ack message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param command + * @param success + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_cmd_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t command,uint8_t success) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN]; + _mav_put_uint8_t(buf, 0, command); + _mav_put_uint8_t(buf, 1, success); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#else + mavlink_rosflight_cmd_ack_t packet; + packet.command = command; + packet.success = success; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif +} + +/** + * @brief Encode a rosflight_cmd_ack struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rosflight_cmd_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_cmd_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rosflight_cmd_ack_t* rosflight_cmd_ack) +{ + return mavlink_msg_rosflight_cmd_ack_pack(system_id, component_id, msg, rosflight_cmd_ack->command, rosflight_cmd_ack->success); +} + +/** + * @brief Encode a rosflight_cmd_ack struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rosflight_cmd_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_cmd_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rosflight_cmd_ack_t* rosflight_cmd_ack) +{ + return mavlink_msg_rosflight_cmd_ack_pack_chan(system_id, component_id, chan, msg, rosflight_cmd_ack->command, rosflight_cmd_ack->success); +} + +/** + * @brief Send a rosflight_cmd_ack message + * @param chan MAVLink channel to send the message + * + * @param command + * @param success + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rosflight_cmd_ack_send(mavlink_channel_t chan, uint8_t command, uint8_t success) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN]; + _mav_put_uint8_t(buf, 0, command); + _mav_put_uint8_t(buf, 1, success); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif +#else + mavlink_rosflight_cmd_ack_t packet; + packet.command = command; + packet.success = success; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rosflight_cmd_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t command, uint8_t success) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, command); + _mav_put_uint8_t(buf, 1, success); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif +#else + mavlink_rosflight_cmd_ack_t *packet = (mavlink_rosflight_cmd_ack_t *)msgbuf; + packet->command = command; + packet->success = success; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ROSFLIGHT_CMD_ACK UNPACKING + + +/** + * @brief Get field command from rosflight_cmd_ack message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_cmd_ack_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field success from rosflight_cmd_ack message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_cmd_ack_get_success(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a rosflight_cmd_ack message into a struct + * + * @param msg The message to decode + * @param rosflight_cmd_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_rosflight_cmd_ack_decode(const mavlink_message_t* msg, mavlink_rosflight_cmd_ack_t* rosflight_cmd_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + rosflight_cmd_ack->command = mavlink_msg_rosflight_cmd_ack_get_command(msg); + rosflight_cmd_ack->success = mavlink_msg_rosflight_cmd_ack_get_success(msg); +#else + memcpy(rosflight_cmd_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_rosflight_output_raw.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_rosflight_output_raw.h new file mode 100644 index 0000000..03e14f7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_rosflight_output_raw.h @@ -0,0 +1,225 @@ +// MESSAGE ROSFLIGHT_OUTPUT_RAW PACKING + +#define MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW 190 + +typedef struct __mavlink_rosflight_output_raw_t +{ + uint64_t stamp; /*< */ + float values[8]; /*< */ +} mavlink_rosflight_output_raw_t; + +#define MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN 40 +#define MAVLINK_MSG_ID_190_LEN 40 + +#define MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC 230 +#define MAVLINK_MSG_ID_190_CRC 230 + +#define MAVLINK_MSG_ROSFLIGHT_OUTPUT_RAW_FIELD_VALUES_LEN 8 + +#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_OUTPUT_RAW { \ + "ROSFLIGHT_OUTPUT_RAW", \ + 2, \ + { { "stamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rosflight_output_raw_t, stamp) }, \ + { "values", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_rosflight_output_raw_t, values) }, \ + } \ +} + + +/** + * @brief Pack a rosflight_output_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param stamp + * @param values + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t stamp, const float *values) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN]; + _mav_put_uint64_t(buf, 0, stamp); + _mav_put_float_array(buf, 8, values, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#else + mavlink_rosflight_output_raw_t packet; + packet.stamp = stamp; + mav_array_memcpy(packet.values, values, sizeof(float)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif +} + +/** + * @brief Pack a rosflight_output_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param stamp + * @param values + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t stamp,const float *values) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN]; + _mav_put_uint64_t(buf, 0, stamp); + _mav_put_float_array(buf, 8, values, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#else + mavlink_rosflight_output_raw_t packet; + packet.stamp = stamp; + mav_array_memcpy(packet.values, values, sizeof(float)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif +} + +/** + * @brief Encode a rosflight_output_raw struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rosflight_output_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rosflight_output_raw_t* rosflight_output_raw) +{ + return mavlink_msg_rosflight_output_raw_pack(system_id, component_id, msg, rosflight_output_raw->stamp, rosflight_output_raw->values); +} + +/** + * @brief Encode a rosflight_output_raw struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rosflight_output_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_output_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rosflight_output_raw_t* rosflight_output_raw) +{ + return mavlink_msg_rosflight_output_raw_pack_chan(system_id, component_id, chan, msg, rosflight_output_raw->stamp, rosflight_output_raw->values); +} + +/** + * @brief Send a rosflight_output_raw message + * @param chan MAVLink channel to send the message + * + * @param stamp + * @param values + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rosflight_output_raw_send(mavlink_channel_t chan, uint64_t stamp, const float *values) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN]; + _mav_put_uint64_t(buf, 0, stamp); + _mav_put_float_array(buf, 8, values, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, buf, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, buf, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif +#else + mavlink_rosflight_output_raw_t packet; + packet.stamp = stamp; + mav_array_memcpy(packet.values, values, sizeof(float)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rosflight_output_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t stamp, const float *values) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, stamp); + _mav_put_float_array(buf, 8, values, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, buf, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, buf, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif +#else + mavlink_rosflight_output_raw_t *packet = (mavlink_rosflight_output_raw_t *)msgbuf; + packet->stamp = stamp; + mav_array_memcpy(packet->values, values, sizeof(float)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ROSFLIGHT_OUTPUT_RAW UNPACKING + + +/** + * @brief Get field stamp from rosflight_output_raw message + * + * @return + */ +static inline uint64_t mavlink_msg_rosflight_output_raw_get_stamp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field values from rosflight_output_raw message + * + * @return + */ +static inline uint16_t mavlink_msg_rosflight_output_raw_get_values(const mavlink_message_t* msg, float *values) +{ + return _MAV_RETURN_float_array(msg, values, 8, 8); +} + +/** + * @brief Decode a rosflight_output_raw message into a struct + * + * @param msg The message to decode + * @param rosflight_output_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_rosflight_output_raw_decode(const mavlink_message_t* msg, mavlink_rosflight_output_raw_t* rosflight_output_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + rosflight_output_raw->stamp = mavlink_msg_rosflight_output_raw_get_stamp(msg); + mavlink_msg_rosflight_output_raw_get_values(msg, rosflight_output_raw->values); +#else + memcpy(rosflight_output_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_rosflight_status.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_rosflight_status.h new file mode 100644 index 0000000..0e53c95 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_rosflight_status.h @@ -0,0 +1,377 @@ +// MESSAGE ROSFLIGHT_STATUS PACKING + +#define MAVLINK_MSG_ID_ROSFLIGHT_STATUS 191 + +typedef struct __mavlink_rosflight_status_t +{ + int16_t num_errors; /*< */ + int16_t loop_time_us; /*< */ + uint8_t armed; /*< */ + uint8_t failsafe; /*< */ + uint8_t rc_override; /*< */ + uint8_t offboard; /*< */ + uint8_t error_code; /*< */ + uint8_t control_mode; /*< */ +} mavlink_rosflight_status_t; + +#define MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN 10 +#define MAVLINK_MSG_ID_191_LEN 10 + +#define MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC 183 +#define MAVLINK_MSG_ID_191_CRC 183 + + + +#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_STATUS { \ + "ROSFLIGHT_STATUS", \ + 8, \ + { { "num_errors", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_rosflight_status_t, num_errors) }, \ + { "loop_time_us", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_rosflight_status_t, loop_time_us) }, \ + { "armed", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_rosflight_status_t, armed) }, \ + { "failsafe", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_rosflight_status_t, failsafe) }, \ + { "rc_override", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_rosflight_status_t, rc_override) }, \ + { "offboard", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_rosflight_status_t, offboard) }, \ + { "error_code", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_rosflight_status_t, error_code) }, \ + { "control_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_rosflight_status_t, control_mode) }, \ + } \ +} + + +/** + * @brief Pack a rosflight_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param armed + * @param failsafe + * @param rc_override + * @param offboard + * @param error_code + * @param control_mode + * @param num_errors + * @param loop_time_us + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t armed, uint8_t failsafe, uint8_t rc_override, uint8_t offboard, uint8_t error_code, uint8_t control_mode, int16_t num_errors, int16_t loop_time_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN]; + _mav_put_int16_t(buf, 0, num_errors); + _mav_put_int16_t(buf, 2, loop_time_us); + _mav_put_uint8_t(buf, 4, armed); + _mav_put_uint8_t(buf, 5, failsafe); + _mav_put_uint8_t(buf, 6, rc_override); + _mav_put_uint8_t(buf, 7, offboard); + _mav_put_uint8_t(buf, 8, error_code); + _mav_put_uint8_t(buf, 9, control_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#else + mavlink_rosflight_status_t packet; + packet.num_errors = num_errors; + packet.loop_time_us = loop_time_us; + packet.armed = armed; + packet.failsafe = failsafe; + packet.rc_override = rc_override; + packet.offboard = offboard; + packet.error_code = error_code; + packet.control_mode = control_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif +} + +/** + * @brief Pack a rosflight_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param armed + * @param failsafe + * @param rc_override + * @param offboard + * @param error_code + * @param control_mode + * @param num_errors + * @param loop_time_us + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t armed,uint8_t failsafe,uint8_t rc_override,uint8_t offboard,uint8_t error_code,uint8_t control_mode,int16_t num_errors,int16_t loop_time_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN]; + _mav_put_int16_t(buf, 0, num_errors); + _mav_put_int16_t(buf, 2, loop_time_us); + _mav_put_uint8_t(buf, 4, armed); + _mav_put_uint8_t(buf, 5, failsafe); + _mav_put_uint8_t(buf, 6, rc_override); + _mav_put_uint8_t(buf, 7, offboard); + _mav_put_uint8_t(buf, 8, error_code); + _mav_put_uint8_t(buf, 9, control_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#else + mavlink_rosflight_status_t packet; + packet.num_errors = num_errors; + packet.loop_time_us = loop_time_us; + packet.armed = armed; + packet.failsafe = failsafe; + packet.rc_override = rc_override; + packet.offboard = offboard; + packet.error_code = error_code; + packet.control_mode = control_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif +} + +/** + * @brief Encode a rosflight_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rosflight_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rosflight_status_t* rosflight_status) +{ + return mavlink_msg_rosflight_status_pack(system_id, component_id, msg, rosflight_status->armed, rosflight_status->failsafe, rosflight_status->rc_override, rosflight_status->offboard, rosflight_status->error_code, rosflight_status->control_mode, rosflight_status->num_errors, rosflight_status->loop_time_us); +} + +/** + * @brief Encode a rosflight_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rosflight_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rosflight_status_t* rosflight_status) +{ + return mavlink_msg_rosflight_status_pack_chan(system_id, component_id, chan, msg, rosflight_status->armed, rosflight_status->failsafe, rosflight_status->rc_override, rosflight_status->offboard, rosflight_status->error_code, rosflight_status->control_mode, rosflight_status->num_errors, rosflight_status->loop_time_us); +} + +/** + * @brief Send a rosflight_status message + * @param chan MAVLink channel to send the message + * + * @param armed + * @param failsafe + * @param rc_override + * @param offboard + * @param error_code + * @param control_mode + * @param num_errors + * @param loop_time_us + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rosflight_status_send(mavlink_channel_t chan, uint8_t armed, uint8_t failsafe, uint8_t rc_override, uint8_t offboard, uint8_t error_code, uint8_t control_mode, int16_t num_errors, int16_t loop_time_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN]; + _mav_put_int16_t(buf, 0, num_errors); + _mav_put_int16_t(buf, 2, loop_time_us); + _mav_put_uint8_t(buf, 4, armed); + _mav_put_uint8_t(buf, 5, failsafe); + _mav_put_uint8_t(buf, 6, rc_override); + _mav_put_uint8_t(buf, 7, offboard); + _mav_put_uint8_t(buf, 8, error_code); + _mav_put_uint8_t(buf, 9, control_mode); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, buf, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, buf, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif +#else + mavlink_rosflight_status_t packet; + packet.num_errors = num_errors; + packet.loop_time_us = loop_time_us; + packet.armed = armed; + packet.failsafe = failsafe; + packet.rc_override = rc_override; + packet.offboard = offboard; + packet.error_code = error_code; + packet.control_mode = control_mode; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rosflight_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t armed, uint8_t failsafe, uint8_t rc_override, uint8_t offboard, uint8_t error_code, uint8_t control_mode, int16_t num_errors, int16_t loop_time_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int16_t(buf, 0, num_errors); + _mav_put_int16_t(buf, 2, loop_time_us); + _mav_put_uint8_t(buf, 4, armed); + _mav_put_uint8_t(buf, 5, failsafe); + _mav_put_uint8_t(buf, 6, rc_override); + _mav_put_uint8_t(buf, 7, offboard); + _mav_put_uint8_t(buf, 8, error_code); + _mav_put_uint8_t(buf, 9, control_mode); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, buf, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, buf, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif +#else + mavlink_rosflight_status_t *packet = (mavlink_rosflight_status_t *)msgbuf; + packet->num_errors = num_errors; + packet->loop_time_us = loop_time_us; + packet->armed = armed; + packet->failsafe = failsafe; + packet->rc_override = rc_override; + packet->offboard = offboard; + packet->error_code = error_code; + packet->control_mode = control_mode; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ROSFLIGHT_STATUS UNPACKING + + +/** + * @brief Get field armed from rosflight_status message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_status_get_armed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field failsafe from rosflight_status message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_status_get_failsafe(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field rc_override from rosflight_status message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_status_get_rc_override(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field offboard from rosflight_status message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_status_get_offboard(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field error_code from rosflight_status message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_status_get_error_code(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field control_mode from rosflight_status message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_status_get_control_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 9); +} + +/** + * @brief Get field num_errors from rosflight_status message + * + * @return + */ +static inline int16_t mavlink_msg_rosflight_status_get_num_errors(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Get field loop_time_us from rosflight_status message + * + * @return + */ +static inline int16_t mavlink_msg_rosflight_status_get_loop_time_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 2); +} + +/** + * @brief Decode a rosflight_status message into a struct + * + * @param msg The message to decode + * @param rosflight_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_rosflight_status_decode(const mavlink_message_t* msg, mavlink_rosflight_status_t* rosflight_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + rosflight_status->num_errors = mavlink_msg_rosflight_status_get_num_errors(msg); + rosflight_status->loop_time_us = mavlink_msg_rosflight_status_get_loop_time_us(msg); + rosflight_status->armed = mavlink_msg_rosflight_status_get_armed(msg); + rosflight_status->failsafe = mavlink_msg_rosflight_status_get_failsafe(msg); + rosflight_status->rc_override = mavlink_msg_rosflight_status_get_rc_override(msg); + rosflight_status->offboard = mavlink_msg_rosflight_status_get_offboard(msg); + rosflight_status->error_code = mavlink_msg_rosflight_status_get_error_code(msg); + rosflight_status->control_mode = mavlink_msg_rosflight_status_get_control_mode(msg); +#else + memcpy(rosflight_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_rosflight_version.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_rosflight_version.h new file mode 100644 index 0000000..3d9fcb9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_rosflight_version.h @@ -0,0 +1,209 @@ +// MESSAGE ROSFLIGHT_VERSION PACKING + +#define MAVLINK_MSG_ID_ROSFLIGHT_VERSION 192 + +typedef struct __mavlink_rosflight_version_t +{ + char version[50]; /*< */ +} mavlink_rosflight_version_t; + +#define MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN 50 +#define MAVLINK_MSG_ID_192_LEN 50 + +#define MAVLINK_MSG_ID_ROSFLIGHT_VERSION_CRC 134 +#define MAVLINK_MSG_ID_192_CRC 134 + +#define MAVLINK_MSG_ROSFLIGHT_VERSION_FIELD_VERSION_LEN 50 + +#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_VERSION { \ + "ROSFLIGHT_VERSION", \ + 1, \ + { { "version", NULL, MAVLINK_TYPE_CHAR, 50, 0, offsetof(mavlink_rosflight_version_t, version) }, \ + } \ +} + + +/** + * @brief Pack a rosflight_version message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param version + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *version) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN]; + + _mav_put_char_array(buf, 0, version, 50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#else + mavlink_rosflight_version_t packet; + + mav_array_memcpy(packet.version, version, sizeof(char)*50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_VERSION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif +} + +/** + * @brief Pack a rosflight_version message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param version + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *version) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN]; + + _mav_put_char_array(buf, 0, version, 50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#else + mavlink_rosflight_version_t packet; + + mav_array_memcpy(packet.version, version, sizeof(char)*50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_VERSION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif +} + +/** + * @brief Encode a rosflight_version struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rosflight_version C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rosflight_version_t* rosflight_version) +{ + return mavlink_msg_rosflight_version_pack(system_id, component_id, msg, rosflight_version->version); +} + +/** + * @brief Encode a rosflight_version struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rosflight_version C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rosflight_version_t* rosflight_version) +{ + return mavlink_msg_rosflight_version_pack_chan(system_id, component_id, chan, msg, rosflight_version->version); +} + +/** + * @brief Send a rosflight_version message + * @param chan MAVLink channel to send the message + * + * @param version + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rosflight_version_send(mavlink_channel_t chan, const char *version) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN]; + + _mav_put_char_array(buf, 0, version, 50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, buf, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, buf, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif +#else + mavlink_rosflight_version_t packet; + + mav_array_memcpy(packet.version, version, sizeof(char)*50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rosflight_version_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *version) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + + _mav_put_char_array(buf, 0, version, 50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, buf, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, buf, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif +#else + mavlink_rosflight_version_t *packet = (mavlink_rosflight_version_t *)msgbuf; + + mav_array_memcpy(packet->version, version, sizeof(char)*50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ROSFLIGHT_VERSION UNPACKING + + +/** + * @brief Get field version from rosflight_version message + * + * @return + */ +static inline uint16_t mavlink_msg_rosflight_version_get_version(const mavlink_message_t* msg, char *version) +{ + return _MAV_RETURN_char_array(msg, version, 50, 0); +} + +/** + * @brief Decode a rosflight_version message into a struct + * + * @param msg The message to decode + * @param rosflight_version C-struct to decode the message contents into + */ +static inline void mavlink_msg_rosflight_version_decode(const mavlink_message_t* msg, mavlink_rosflight_version_t* rosflight_version) +{ +#if MAVLINK_NEED_BYTE_SWAP + mavlink_msg_rosflight_version_get_version(msg, rosflight_version->version); +#else + memcpy(rosflight_version, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_small_baro.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_small_baro.h new file mode 100644 index 0000000..19ecc32 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_small_baro.h @@ -0,0 +1,257 @@ +// MESSAGE SMALL_BARO PACKING + +#define MAVLINK_MSG_ID_SMALL_BARO 183 + +typedef struct __mavlink_small_baro_t +{ + float altitude; /*< Calculated Altitude (m)*/ + float pressure; /*< Measured Differential Pressure (Pa)*/ + float temperature; /*< Measured Temperature (K)*/ +} mavlink_small_baro_t; + +#define MAVLINK_MSG_ID_SMALL_BARO_LEN 12 +#define MAVLINK_MSG_ID_183_LEN 12 + +#define MAVLINK_MSG_ID_SMALL_BARO_CRC 206 +#define MAVLINK_MSG_ID_183_CRC 206 + + + +#define MAVLINK_MESSAGE_INFO_SMALL_BARO { \ + "SMALL_BARO", \ + 3, \ + { { "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_small_baro_t, altitude) }, \ + { "pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_small_baro_t, pressure) }, \ + { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_small_baro_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a small_baro message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param altitude Calculated Altitude (m) + * @param pressure Measured Differential Pressure (Pa) + * @param temperature Measured Temperature (K) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_baro_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float altitude, float pressure, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_BARO_LEN]; + _mav_put_float(buf, 0, altitude); + _mav_put_float(buf, 4, pressure); + _mav_put_float(buf, 8, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#else + mavlink_small_baro_t packet; + packet.altitude = altitude; + packet.pressure = pressure; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_BARO; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_BARO_LEN, MAVLINK_MSG_ID_SMALL_BARO_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif +} + +/** + * @brief Pack a small_baro message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param altitude Calculated Altitude (m) + * @param pressure Measured Differential Pressure (Pa) + * @param temperature Measured Temperature (K) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_baro_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float altitude,float pressure,float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_BARO_LEN]; + _mav_put_float(buf, 0, altitude); + _mav_put_float(buf, 4, pressure); + _mav_put_float(buf, 8, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#else + mavlink_small_baro_t packet; + packet.altitude = altitude; + packet.pressure = pressure; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_BARO; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_BARO_LEN, MAVLINK_MSG_ID_SMALL_BARO_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif +} + +/** + * @brief Encode a small_baro struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param small_baro C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_baro_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_small_baro_t* small_baro) +{ + return mavlink_msg_small_baro_pack(system_id, component_id, msg, small_baro->altitude, small_baro->pressure, small_baro->temperature); +} + +/** + * @brief Encode a small_baro struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param small_baro C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_baro_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_small_baro_t* small_baro) +{ + return mavlink_msg_small_baro_pack_chan(system_id, component_id, chan, msg, small_baro->altitude, small_baro->pressure, small_baro->temperature); +} + +/** + * @brief Send a small_baro message + * @param chan MAVLink channel to send the message + * + * @param altitude Calculated Altitude (m) + * @param pressure Measured Differential Pressure (Pa) + * @param temperature Measured Temperature (K) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_small_baro_send(mavlink_channel_t chan, float altitude, float pressure, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_BARO_LEN]; + _mav_put_float(buf, 0, altitude); + _mav_put_float(buf, 4, pressure); + _mav_put_float(buf, 8, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, buf, MAVLINK_MSG_ID_SMALL_BARO_LEN, MAVLINK_MSG_ID_SMALL_BARO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, buf, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif +#else + mavlink_small_baro_t packet; + packet.altitude = altitude; + packet.pressure = pressure; + packet.temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, (const char *)&packet, MAVLINK_MSG_ID_SMALL_BARO_LEN, MAVLINK_MSG_ID_SMALL_BARO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, (const char *)&packet, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SMALL_BARO_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_small_baro_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float altitude, float pressure, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, altitude); + _mav_put_float(buf, 4, pressure); + _mav_put_float(buf, 8, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, buf, MAVLINK_MSG_ID_SMALL_BARO_LEN, MAVLINK_MSG_ID_SMALL_BARO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, buf, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif +#else + mavlink_small_baro_t *packet = (mavlink_small_baro_t *)msgbuf; + packet->altitude = altitude; + packet->pressure = pressure; + packet->temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, (const char *)packet, MAVLINK_MSG_ID_SMALL_BARO_LEN, MAVLINK_MSG_ID_SMALL_BARO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, (const char *)packet, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SMALL_BARO UNPACKING + + +/** + * @brief Get field altitude from small_baro message + * + * @return Calculated Altitude (m) + */ +static inline float mavlink_msg_small_baro_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field pressure from small_baro message + * + * @return Measured Differential Pressure (Pa) + */ +static inline float mavlink_msg_small_baro_get_pressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field temperature from small_baro message + * + * @return Measured Temperature (K) + */ +static inline float mavlink_msg_small_baro_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Decode a small_baro message into a struct + * + * @param msg The message to decode + * @param small_baro C-struct to decode the message contents into + */ +static inline void mavlink_msg_small_baro_decode(const mavlink_message_t* msg, mavlink_small_baro_t* small_baro) +{ +#if MAVLINK_NEED_BYTE_SWAP + small_baro->altitude = mavlink_msg_small_baro_get_altitude(msg); + small_baro->pressure = mavlink_msg_small_baro_get_pressure(msg); + small_baro->temperature = mavlink_msg_small_baro_get_temperature(msg); +#else + memcpy(small_baro, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_small_imu.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_small_imu.h new file mode 100644 index 0000000..c60cfde --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_small_imu.h @@ -0,0 +1,377 @@ +// MESSAGE SMALL_IMU PACKING + +#define MAVLINK_MSG_ID_SMALL_IMU 181 + +typedef struct __mavlink_small_imu_t +{ + uint64_t time_boot_us; /*< Measurement timestamp as microseconds since boot*/ + float xacc; /*< Acceleration along X axis*/ + float yacc; /*< Acceleration along Y axis*/ + float zacc; /*< Acceleration along Z axis*/ + float xgyro; /*< Angular speed around X axis*/ + float ygyro; /*< Angular speed around Y axis*/ + float zgyro; /*< Angular speed around Z axis*/ + float temperature; /*< Internal temperature measurement*/ +} mavlink_small_imu_t; + +#define MAVLINK_MSG_ID_SMALL_IMU_LEN 36 +#define MAVLINK_MSG_ID_181_LEN 36 + +#define MAVLINK_MSG_ID_SMALL_IMU_CRC 67 +#define MAVLINK_MSG_ID_181_CRC 67 + + + +#define MAVLINK_MESSAGE_INFO_SMALL_IMU { \ + "SMALL_IMU", \ + 8, \ + { { "time_boot_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_small_imu_t, time_boot_us) }, \ + { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_small_imu_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_small_imu_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_small_imu_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_small_imu_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_small_imu_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_small_imu_t, zgyro) }, \ + { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_small_imu_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a small_imu message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_us Measurement timestamp as microseconds since boot + * @param xacc Acceleration along X axis + * @param yacc Acceleration along Y axis + * @param zacc Acceleration along Z axis + * @param xgyro Angular speed around X axis + * @param ygyro Angular speed around Y axis + * @param zgyro Angular speed around Z axis + * @param temperature Internal temperature measurement + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_boot_us); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#else + mavlink_small_imu_t packet; + packet.time_boot_us = time_boot_us; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif +} + +/** + * @brief Pack a small_imu message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_us Measurement timestamp as microseconds since boot + * @param xacc Acceleration along X axis + * @param yacc Acceleration along Y axis + * @param zacc Acceleration along Z axis + * @param xgyro Angular speed around X axis + * @param ygyro Angular speed around Y axis + * @param zgyro Angular speed around Z axis + * @param temperature Internal temperature measurement + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_boot_us,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_boot_us); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#else + mavlink_small_imu_t packet; + packet.time_boot_us = time_boot_us; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif +} + +/** + * @brief Encode a small_imu struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param small_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_small_imu_t* small_imu) +{ + return mavlink_msg_small_imu_pack(system_id, component_id, msg, small_imu->time_boot_us, small_imu->xacc, small_imu->yacc, small_imu->zacc, small_imu->xgyro, small_imu->ygyro, small_imu->zgyro, small_imu->temperature); +} + +/** + * @brief Encode a small_imu struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param small_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_small_imu_t* small_imu) +{ + return mavlink_msg_small_imu_pack_chan(system_id, component_id, chan, msg, small_imu->time_boot_us, small_imu->xacc, small_imu->yacc, small_imu->zacc, small_imu->xgyro, small_imu->ygyro, small_imu->zgyro, small_imu->temperature); +} + +/** + * @brief Send a small_imu message + * @param chan MAVLink channel to send the message + * + * @param time_boot_us Measurement timestamp as microseconds since boot + * @param xacc Acceleration along X axis + * @param yacc Acceleration along Y axis + * @param zacc Acceleration along Z axis + * @param xgyro Angular speed around X axis + * @param ygyro Angular speed around Y axis + * @param zgyro Angular speed around Z axis + * @param temperature Internal temperature measurement + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_small_imu_send(mavlink_channel_t chan, uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_boot_us); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, buf, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, buf, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif +#else + mavlink_small_imu_t packet; + packet.time_boot_us = time_boot_us; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, (const char *)&packet, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, (const char *)&packet, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SMALL_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_small_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_boot_us); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, buf, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, buf, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif +#else + mavlink_small_imu_t *packet = (mavlink_small_imu_t *)msgbuf; + packet->time_boot_us = time_boot_us; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, (const char *)packet, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, (const char *)packet, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SMALL_IMU UNPACKING + + +/** + * @brief Get field time_boot_us from small_imu message + * + * @return Measurement timestamp as microseconds since boot + */ +static inline uint64_t mavlink_msg_small_imu_get_time_boot_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field xacc from small_imu message + * + * @return Acceleration along X axis + */ +static inline float mavlink_msg_small_imu_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yacc from small_imu message + * + * @return Acceleration along Y axis + */ +static inline float mavlink_msg_small_imu_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field zacc from small_imu message + * + * @return Acceleration along Z axis + */ +static inline float mavlink_msg_small_imu_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field xgyro from small_imu message + * + * @return Angular speed around X axis + */ +static inline float mavlink_msg_small_imu_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field ygyro from small_imu message + * + * @return Angular speed around Y axis + */ +static inline float mavlink_msg_small_imu_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field zgyro from small_imu message + * + * @return Angular speed around Z axis + */ +static inline float mavlink_msg_small_imu_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field temperature from small_imu message + * + * @return Internal temperature measurement + */ +static inline float mavlink_msg_small_imu_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Decode a small_imu message into a struct + * + * @param msg The message to decode + * @param small_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_small_imu_decode(const mavlink_message_t* msg, mavlink_small_imu_t* small_imu) +{ +#if MAVLINK_NEED_BYTE_SWAP + small_imu->time_boot_us = mavlink_msg_small_imu_get_time_boot_us(msg); + small_imu->xacc = mavlink_msg_small_imu_get_xacc(msg); + small_imu->yacc = mavlink_msg_small_imu_get_yacc(msg); + small_imu->zacc = mavlink_msg_small_imu_get_zacc(msg); + small_imu->xgyro = mavlink_msg_small_imu_get_xgyro(msg); + small_imu->ygyro = mavlink_msg_small_imu_get_ygyro(msg); + small_imu->zgyro = mavlink_msg_small_imu_get_zgyro(msg); + small_imu->temperature = mavlink_msg_small_imu_get_temperature(msg); +#else + memcpy(small_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_small_mag.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_small_mag.h new file mode 100644 index 0000000..acd1f98 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_small_mag.h @@ -0,0 +1,257 @@ +// MESSAGE SMALL_MAG PACKING + +#define MAVLINK_MSG_ID_SMALL_MAG 182 + +typedef struct __mavlink_small_mag_t +{ + float xmag; /*< Magnetic field along X axis*/ + float ymag; /*< Magnetic field along Y axis*/ + float zmag; /*< Magnetic field along Z axis*/ +} mavlink_small_mag_t; + +#define MAVLINK_MSG_ID_SMALL_MAG_LEN 12 +#define MAVLINK_MSG_ID_182_LEN 12 + +#define MAVLINK_MSG_ID_SMALL_MAG_CRC 218 +#define MAVLINK_MSG_ID_182_CRC 218 + + + +#define MAVLINK_MESSAGE_INFO_SMALL_MAG { \ + "SMALL_MAG", \ + 3, \ + { { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_small_mag_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_small_mag_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_small_mag_t, zmag) }, \ + } \ +} + + +/** + * @brief Pack a small_mag message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param xmag Magnetic field along X axis + * @param ymag Magnetic field along Y axis + * @param zmag Magnetic field along Z axis + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_mag_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float xmag, float ymag, float zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_MAG_LEN]; + _mav_put_float(buf, 0, xmag); + _mav_put_float(buf, 4, ymag); + _mav_put_float(buf, 8, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#else + mavlink_small_mag_t packet; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_MAG; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_MAG_LEN, MAVLINK_MSG_ID_SMALL_MAG_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif +} + +/** + * @brief Pack a small_mag message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param xmag Magnetic field along X axis + * @param ymag Magnetic field along Y axis + * @param zmag Magnetic field along Z axis + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_mag_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float xmag,float ymag,float zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_MAG_LEN]; + _mav_put_float(buf, 0, xmag); + _mav_put_float(buf, 4, ymag); + _mav_put_float(buf, 8, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#else + mavlink_small_mag_t packet; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_MAG; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_MAG_LEN, MAVLINK_MSG_ID_SMALL_MAG_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif +} + +/** + * @brief Encode a small_mag struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param small_mag C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_mag_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_small_mag_t* small_mag) +{ + return mavlink_msg_small_mag_pack(system_id, component_id, msg, small_mag->xmag, small_mag->ymag, small_mag->zmag); +} + +/** + * @brief Encode a small_mag struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param small_mag C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_mag_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_small_mag_t* small_mag) +{ + return mavlink_msg_small_mag_pack_chan(system_id, component_id, chan, msg, small_mag->xmag, small_mag->ymag, small_mag->zmag); +} + +/** + * @brief Send a small_mag message + * @param chan MAVLink channel to send the message + * + * @param xmag Magnetic field along X axis + * @param ymag Magnetic field along Y axis + * @param zmag Magnetic field along Z axis + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_small_mag_send(mavlink_channel_t chan, float xmag, float ymag, float zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_MAG_LEN]; + _mav_put_float(buf, 0, xmag); + _mav_put_float(buf, 4, ymag); + _mav_put_float(buf, 8, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, buf, MAVLINK_MSG_ID_SMALL_MAG_LEN, MAVLINK_MSG_ID_SMALL_MAG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, buf, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif +#else + mavlink_small_mag_t packet; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, (const char *)&packet, MAVLINK_MSG_ID_SMALL_MAG_LEN, MAVLINK_MSG_ID_SMALL_MAG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, (const char *)&packet, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SMALL_MAG_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_small_mag_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float xmag, float ymag, float zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, xmag); + _mav_put_float(buf, 4, ymag); + _mav_put_float(buf, 8, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, buf, MAVLINK_MSG_ID_SMALL_MAG_LEN, MAVLINK_MSG_ID_SMALL_MAG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, buf, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif +#else + mavlink_small_mag_t *packet = (mavlink_small_mag_t *)msgbuf; + packet->xmag = xmag; + packet->ymag = ymag; + packet->zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, (const char *)packet, MAVLINK_MSG_ID_SMALL_MAG_LEN, MAVLINK_MSG_ID_SMALL_MAG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, (const char *)packet, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SMALL_MAG UNPACKING + + +/** + * @brief Get field xmag from small_mag message + * + * @return Magnetic field along X axis + */ +static inline float mavlink_msg_small_mag_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field ymag from small_mag message + * + * @return Magnetic field along Y axis + */ +static inline float mavlink_msg_small_mag_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field zmag from small_mag message + * + * @return Magnetic field along Z axis + */ +static inline float mavlink_msg_small_mag_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Decode a small_mag message into a struct + * + * @param msg The message to decode + * @param small_mag C-struct to decode the message contents into + */ +static inline void mavlink_msg_small_mag_decode(const mavlink_message_t* msg, mavlink_small_mag_t* small_mag) +{ +#if MAVLINK_NEED_BYTE_SWAP + small_mag->xmag = mavlink_msg_small_mag_get_xmag(msg); + small_mag->ymag = mavlink_msg_small_mag_get_ymag(msg); + small_mag->zmag = mavlink_msg_small_mag_get_zmag(msg); +#else + memcpy(small_mag, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_small_range.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_small_range.h new file mode 100644 index 0000000..6693473 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/mavlink_msg_small_range.h @@ -0,0 +1,281 @@ +// MESSAGE SMALL_RANGE PACKING + +#define MAVLINK_MSG_ID_SMALL_RANGE 187 + +typedef struct __mavlink_small_range_t +{ + float range; /*< Range Measurement (m)*/ + float max_range; /*< Max Range (m)*/ + float min_range; /*< Min Range (m)*/ + uint8_t type; /*< Sensor type*/ +} mavlink_small_range_t; + +#define MAVLINK_MSG_ID_SMALL_RANGE_LEN 13 +#define MAVLINK_MSG_ID_187_LEN 13 + +#define MAVLINK_MSG_ID_SMALL_RANGE_CRC 60 +#define MAVLINK_MSG_ID_187_CRC 60 + + + +#define MAVLINK_MESSAGE_INFO_SMALL_RANGE { \ + "SMALL_RANGE", \ + 4, \ + { { "range", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_small_range_t, range) }, \ + { "max_range", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_small_range_t, max_range) }, \ + { "min_range", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_small_range_t, min_range) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_small_range_t, type) }, \ + } \ +} + + +/** + * @brief Pack a small_range message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type Sensor type + * @param range Range Measurement (m) + * @param max_range Max Range (m) + * @param min_range Min Range (m) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_range_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t type, float range, float max_range, float min_range) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_RANGE_LEN]; + _mav_put_float(buf, 0, range); + _mav_put_float(buf, 4, max_range); + _mav_put_float(buf, 8, min_range); + _mav_put_uint8_t(buf, 12, type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#else + mavlink_small_range_t packet; + packet.range = range; + packet.max_range = max_range; + packet.min_range = min_range; + packet.type = type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_RANGE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_RANGE_LEN, MAVLINK_MSG_ID_SMALL_RANGE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif +} + +/** + * @brief Pack a small_range message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param type Sensor type + * @param range Range Measurement (m) + * @param max_range Max Range (m) + * @param min_range Min Range (m) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_range_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t type,float range,float max_range,float min_range) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_RANGE_LEN]; + _mav_put_float(buf, 0, range); + _mav_put_float(buf, 4, max_range); + _mav_put_float(buf, 8, min_range); + _mav_put_uint8_t(buf, 12, type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#else + mavlink_small_range_t packet; + packet.range = range; + packet.max_range = max_range; + packet.min_range = min_range; + packet.type = type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_RANGE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_RANGE_LEN, MAVLINK_MSG_ID_SMALL_RANGE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif +} + +/** + * @brief Encode a small_range struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param small_range C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_range_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_small_range_t* small_range) +{ + return mavlink_msg_small_range_pack(system_id, component_id, msg, small_range->type, small_range->range, small_range->max_range, small_range->min_range); +} + +/** + * @brief Encode a small_range struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param small_range C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_range_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_small_range_t* small_range) +{ + return mavlink_msg_small_range_pack_chan(system_id, component_id, chan, msg, small_range->type, small_range->range, small_range->max_range, small_range->min_range); +} + +/** + * @brief Send a small_range message + * @param chan MAVLink channel to send the message + * + * @param type Sensor type + * @param range Range Measurement (m) + * @param max_range Max Range (m) + * @param min_range Min Range (m) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_small_range_send(mavlink_channel_t chan, uint8_t type, float range, float max_range, float min_range) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_RANGE_LEN]; + _mav_put_float(buf, 0, range); + _mav_put_float(buf, 4, max_range); + _mav_put_float(buf, 8, min_range); + _mav_put_uint8_t(buf, 12, type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, buf, MAVLINK_MSG_ID_SMALL_RANGE_LEN, MAVLINK_MSG_ID_SMALL_RANGE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, buf, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif +#else + mavlink_small_range_t packet; + packet.range = range; + packet.max_range = max_range; + packet.min_range = min_range; + packet.type = type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, (const char *)&packet, MAVLINK_MSG_ID_SMALL_RANGE_LEN, MAVLINK_MSG_ID_SMALL_RANGE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, (const char *)&packet, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SMALL_RANGE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_small_range_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, float range, float max_range, float min_range) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, range); + _mav_put_float(buf, 4, max_range); + _mav_put_float(buf, 8, min_range); + _mav_put_uint8_t(buf, 12, type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, buf, MAVLINK_MSG_ID_SMALL_RANGE_LEN, MAVLINK_MSG_ID_SMALL_RANGE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, buf, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif +#else + mavlink_small_range_t *packet = (mavlink_small_range_t *)msgbuf; + packet->range = range; + packet->max_range = max_range; + packet->min_range = min_range; + packet->type = type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, (const char *)packet, MAVLINK_MSG_ID_SMALL_RANGE_LEN, MAVLINK_MSG_ID_SMALL_RANGE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, (const char *)packet, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SMALL_RANGE UNPACKING + + +/** + * @brief Get field type from small_range message + * + * @return Sensor type + */ +static inline uint8_t mavlink_msg_small_range_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field range from small_range message + * + * @return Range Measurement (m) + */ +static inline float mavlink_msg_small_range_get_range(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field max_range from small_range message + * + * @return Max Range (m) + */ +static inline float mavlink_msg_small_range_get_max_range(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field min_range from small_range message + * + * @return Min Range (m) + */ +static inline float mavlink_msg_small_range_get_min_range(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Decode a small_range message into a struct + * + * @param msg The message to decode + * @param small_range C-struct to decode the message contents into + */ +static inline void mavlink_msg_small_range_decode(const mavlink_message_t* msg, mavlink_small_range_t* small_range) +{ +#if MAVLINK_NEED_BYTE_SWAP + small_range->range = mavlink_msg_small_range_get_range(msg); + small_range->max_range = mavlink_msg_small_range_get_max_range(msg); + small_range->min_range = mavlink_msg_small_range_get_min_range(msg); + small_range->type = mavlink_msg_small_range_get_type(msg); +#else + memcpy(small_range, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/rosflight.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/rosflight.h new file mode 100644 index 0000000..90e59c6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/rosflight.h @@ -0,0 +1,153 @@ +/** @file + * @brief MAVLink comm protocol generated from rosflight.xml + * @see http://mavlink.org + */ +#ifndef MAVLINK_ROSFLIGHT_H +#define MAVLINK_ROSFLIGHT_H + +#ifndef MAVLINK_H + #error Wrong include order: MAVLINK_ROSFLIGHT.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call. +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 37, 4, 0, 0, 27, 25, 0, 0, 0, 0, 0, 68, 26, 185, 229, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 53, 51, 53, 51, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 44, 64, 84, 9, 254, 16, 12, 36, 44, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 22, 13, 255, 14, 18, 43, 8, 22, 14, 36, 43, 41, 32, 243, 14, 93, 0, 100, 36, 60, 30, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 36, 12, 12, 12, 37, 28, 13, 1, 2, 40, 10, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 32, 52, 53, 6, 2, 38, 0, 254, 36, 30, 18, 18, 51, 9, 0} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 78, 196, 0, 0, 15, 3, 0, 0, 0, 0, 0, 153, 183, 51, 59, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 138, 108, 32, 185, 84, 34, 174, 124, 237, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 46, 29, 223, 85, 6, 229, 203, 1, 195, 109, 168, 181, 47, 72, 131, 127, 0, 103, 154, 178, 200, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 93, 67, 218, 206, 169, 209, 169, 60, 249, 113, 230, 183, 134, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 163, 105, 0, 0, 0, 0, 0, 0, 0, 0, 0, 90, 104, 85, 95, 130, 184, 0, 8, 204, 49, 170, 44, 83, 46, 0} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ALTITUDE, MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3, MAVLINK_MESSAGE_INFO_FOLLOW_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_LANDING_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OFFBOARD_CONTROL, MAVLINK_MESSAGE_INFO_SMALL_IMU, MAVLINK_MESSAGE_INFO_SMALL_MAG, MAVLINK_MESSAGE_INFO_SMALL_BARO, MAVLINK_MESSAGE_INFO_DIFF_PRESSURE, MAVLINK_MESSAGE_INFO_CAMERA_STAMPED_SMALL_IMU, MAVLINK_MESSAGE_INFO_NAMED_COMMAND_STRUCT, MAVLINK_MESSAGE_INFO_SMALL_RANGE, MAVLINK_MESSAGE_INFO_ROSFLIGHT_CMD, MAVLINK_MESSAGE_INFO_ROSFLIGHT_CMD_ACK, MAVLINK_MESSAGE_INFO_ROSFLIGHT_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_ROSFLIGHT_STATUS, MAVLINK_MESSAGE_INFO_ROSFLIGHT_VERSION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS, MAVLINK_MESSAGE_INFO_WIND_COV, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VIBRATION, MAVLINK_MESSAGE_INFO_HOME_POSITION, MAVLINK_MESSAGE_INFO_SET_HOME_POSITION, MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL, MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE, MAVLINK_MESSAGE_INFO_ADSB_VEHICLE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_ROSFLIGHT + +// ENUM DEFINITIONS + + +/** @brief */ +#ifndef HAVE_ENUM_ROSFLIGHT_CMD +#define HAVE_ENUM_ROSFLIGHT_CMD +typedef enum ROSFLIGHT_CMD +{ + ROSFLIGHT_CMD_RC_CALIBRATION=0, /* | */ + ROSFLIGHT_CMD_ACCEL_CALIBRATION=1, /* | */ + ROSFLIGHT_CMD_GYRO_CALIBRATION=2, /* | */ + ROSFLIGHT_CMD_BARO_CALIBRATION=3, /* | */ + ROSFLIGHT_CMD_AIRSPEED_CALIBRATION=4, /* | */ + ROSFLIGHT_CMD_READ_PARAMS=5, /* | */ + ROSFLIGHT_CMD_WRITE_PARAMS=6, /* | */ + ROSFLIGHT_CMD_SET_PARAM_DEFAULTS=7, /* | */ + ROSFLIGHT_CMD_REBOOT=8, /* | */ + ROSFLIGHT_CMD_REBOOT_TO_BOOTLOADER=9, /* | */ + ROSFLIGHT_CMD_SEND_VERSION=10, /* | */ + ROSFLIGHT_CMD_ENUM_END=11, /* | */ +} ROSFLIGHT_CMD; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_ROSFLIGHT_CMD_RESPONSE +#define HAVE_ENUM_ROSFLIGHT_CMD_RESPONSE +typedef enum ROSFLIGHT_CMD_RESPONSE +{ + ROSFLIGHT_CMD_FAILED=0, /* | */ + ROSFLIGHT_CMD_SUCCESS=1, /* | */ + ROSFLIGHT_CMD_RESPONSE_ENUM_END=2, /* | */ +} ROSFLIGHT_CMD_RESPONSE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_OFFBOARD_CONTROL_MODE +#define HAVE_ENUM_OFFBOARD_CONTROL_MODE +typedef enum OFFBOARD_CONTROL_MODE +{ + MODE_PASS_THROUGH=0, /* Pass commanded values directly to actuators | */ + MODE_ROLLRATE_PITCHRATE_YAWRATE_THROTTLE=1, /* Command roll rate, pitch rate, yaw rate, and throttle | */ + MODE_ROLL_PITCH_YAWRATE_THROTTLE=2, /* Command roll angle, pitch angle, yaw rate, and throttle | */ + MODE_ROLL_PITCH_YAWRATE_ALTITUDE=3, /* Command roll angle, pitch angle, yaw rate, and altitude above ground | */ + OFFBOARD_CONTROL_MODE_ENUM_END=4, /* | */ +} OFFBOARD_CONTROL_MODE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_OFFBOARD_CONTROL_IGNORE +#define HAVE_ENUM_OFFBOARD_CONTROL_IGNORE +typedef enum OFFBOARD_CONTROL_IGNORE +{ + IGNORE_NONE=0, /* Convenience value for specifying no fields should be ignored | */ + IGNORE_VALUE1=1, /* Field value1 should be ignored | */ + IGNORE_VALUE2=2, /* Field value2 should be ignored | */ + IGNORE_VALUE3=4, /* Field value3 should be ignored | */ + IGNORE_VALUE4=8, /* Field value4 should be ignored | */ + OFFBOARD_CONTROL_IGNORE_ENUM_END=9, /* | */ +} OFFBOARD_CONTROL_IGNORE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_ROSFLIGHT_ERROR_CODE +#define HAVE_ENUM_ROSFLIGHT_ERROR_CODE +typedef enum ROSFLIGHT_ERROR_CODE +{ + ROSFLIGHT_ERROR_NONE=0, /* | */ + ROSFLIGHT_ERROR_INVALID_MIXER=1, /* | */ + ROSFLIGHT_ERROR_IMU_NOT_RESPONDING=2, /* | */ + ROSFLIGHT_ERROR_RC_LOST=4, /* | */ + ROSFLIGHT_ERROR_UNHEALTHY_ESTIMATOR=8, /* | */ + ROSFLIGHT_ERROR_TIME_GOING_BACKWARDS=16, /* | */ + ROSFLIGHT_ERROR_UNCALIBRATED_IMU=32, /* | */ + ROSFLIGHT_ERROR_CODE_ENUM_END=33, /* | */ +} ROSFLIGHT_ERROR_CODE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_ROSFLIGHT_RANGE_TYPE +#define HAVE_ENUM_ROSFLIGHT_RANGE_TYPE +typedef enum ROSFLIGHT_RANGE_TYPE +{ + ROSFLIGHT_RANGE_SONAR=0, /* | */ + ROSFLIGHT_RANGE_LIDAR=1, /* | */ + ROSFLIGHT_RANGE_TYPE_ENUM_END=2, /* | */ +} ROSFLIGHT_RANGE_TYPE; +#endif + +#include "../common/common.h" + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_offboard_control.h" +#include "./mavlink_msg_small_imu.h" +#include "./mavlink_msg_small_mag.h" +#include "./mavlink_msg_small_baro.h" +#include "./mavlink_msg_diff_pressure.h" +#include "./mavlink_msg_camera_stamped_small_imu.h" +#include "./mavlink_msg_named_command_struct.h" +#include "./mavlink_msg_small_range.h" +#include "./mavlink_msg_rosflight_cmd.h" +#include "./mavlink_msg_rosflight_cmd_ack.h" +#include "./mavlink_msg_rosflight_output_raw.h" +#include "./mavlink_msg_rosflight_status.h" +#include "./mavlink_msg_rosflight_version.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // MAVLINK_ROSFLIGHT_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/testsuite.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/testsuite.h new file mode 100644 index 0000000..6ff769e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavlink/v1.0/rosflight/testsuite.h @@ -0,0 +1,650 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from rosflight.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef ROSFLIGHT_TESTSUITE_H +#define ROSFLIGHT_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL +static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); +static void mavlink_test_rosflight(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_test_common(system_id, component_id, last_msg); + mavlink_test_rosflight(system_id, component_id, last_msg); +} +#endif + +#include "../common/testsuite.h" + + +static void mavlink_test_offboard_control(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_offboard_control_t packet_in = { + 17.0,45.0,73.0,101.0,53,120 + }; + mavlink_offboard_control_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.x = packet_in.x; + packet1.y = packet_in.y; + packet1.z = packet_in.z; + packet1.F = packet_in.F; + packet1.mode = packet_in.mode; + packet1.ignore = packet_in.ignore; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_offboard_control_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_offboard_control_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_offboard_control_pack(system_id, component_id, &msg , packet1.mode , packet1.ignore , packet1.x , packet1.y , packet1.z , packet1.F ); + mavlink_msg_offboard_control_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_offboard_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.mode , packet1.ignore , packet1.x , packet1.y , packet1.z , packet1.F ); + mavlink_msg_offboard_control_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; i + * + * MAVLink adapter header + */ + +#ifndef MAVROSFLIGHT_MAVLINK_BRIDGE_H +#define MAVROSFLIGHT_MAVLINK_BRIDGE_H + +#include + +#endif // MAVROSFLIGHT_MAVLINK_BRIDGE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/mavlink_comm.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/mavlink_comm.h new file mode 100644 index 0000000..f85e95c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/mavlink_comm.h @@ -0,0 +1,196 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file mavlink_comm.h + * \author Daniel Koch + */ + +#ifndef MAVROSFLIGHT_MAVLINK_COMM_H +#define MAVROSFLIGHT_MAVLINK_COMM_H + +#include +#include + +#include +#include +#include + +#include +#include +#include + +#include + +#define MAVLINK_SERIAL_READ_BUF_SIZE 256 + +namespace mavrosflight +{ + +class MavlinkComm +{ +public: + + /** + * \brief Instantiates the class and begins communication on the specified serial port + * \param port Name of the serial port (e.g. "/dev/ttyUSB0") + * \param baud_rate Serial communication baud rate + */ + MavlinkComm(); + + /** + * \brief Stops communication and closes the serial port before the object is destroyed + */ + ~MavlinkComm(); + + /** + * \brief Opens the port and begins communication + */ + void open(); + + /** + * \brief Stops communication and closes the port + */ + void close(); + + /** + * \brief Register a listener for mavlink messages + * \param listener Pointer to an object that implements the MavlinkListenerInterface interface + */ + void register_mavlink_listener(MavlinkListenerInterface * const listener); + + /** + * \brief Unregister a listener for mavlink messages + * \param listener Pointer to an object that implements the MavlinkListenerInterface interface + */ + void unregister_mavlink_listener(MavlinkListenerInterface * const listener); + + /** + * \brief Send a mavlink message + * \param msg The message to send + */ + void send_message(const mavlink_message_t &msg); + +protected: + virtual bool is_open() = 0; + virtual void do_open() = 0; + virtual void do_close() = 0; + virtual void do_async_read(const boost::asio::mutable_buffers_1 &buffer, boost::function handler) = 0; + virtual void do_async_write(const boost::asio::const_buffers_1 &buffer, boost::function handler) = 0; + + boost::asio::io_service io_service_; //!< boost io service provider + +private: + + //=========================================================================== + // definitions + //=========================================================================== + + /** + * \brief Struct for buffering the contents of a mavlink message + */ + struct WriteBuffer + { + uint8_t data[MAVLINK_MAX_PACKET_LEN]; + size_t len; + size_t pos; + + WriteBuffer() : len(0), pos(0) {} + + WriteBuffer(const uint8_t * buf, uint16_t len) : len(len), pos(0) + { + assert(len <= MAVLINK_MAX_PACKET_LEN); //! \todo Do something less catastrophic here + memcpy(data, buf, len); + } + + const uint8_t * dpos() const { return data + pos; } + + size_t nbytes() const { return len - pos; } + }; + + /** + * \brief Convenience typedef for mutex lock + */ + typedef boost::lock_guard mutex_lock; + + //=========================================================================== + // methods + //=========================================================================== + + /** + * \brief Initiate an asynchronous read operation + */ + void async_read(); + + /** + * \brief Handler for end of asynchronous read operation + * \param error Error code + * \param bytes_transferred Number of bytes received + */ + void async_read_end(const boost::system::error_code& error, size_t bytes_transferred); + + /** + * \brief Initialize an asynchronous write operation + * \param check_write_state If true, only start another write operation if a write sequence is not already running + */ + void async_write(bool check_write_state); + + /** + * \brief Handler for end of asynchronous write operation + * \param error Error code + * \param bytes_transferred Number of bytes sent + */ + void async_write_end(const boost::system::error_code& error, size_t bytes_transferred); + + //=========================================================================== + // member variables + //=========================================================================== + + std::vector listeners_; //!< listeners for mavlink messages + + boost::thread io_thread_; //!< thread on which the io service runs + boost::recursive_mutex mutex_; //!< mutex for threadsafe operation + + uint8_t sysid_; + uint8_t compid_; + + uint8_t read_buf_raw_[MAVLINK_SERIAL_READ_BUF_SIZE]; + + mavlink_message_t msg_in_; + mavlink_status_t status_in_; + + std::list write_queue_; //!< queue of buffers to be written to the serial port + bool write_in_progress_; //!< flag for whether async_write is already running +}; + +} // namespace mavrosflight + +#endif // MAVROSFLIGHT_MAVLINK_COMM_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/mavlink_listener_interface.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/mavlink_listener_interface.h new file mode 100644 index 0000000..91238e7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/mavlink_listener_interface.h @@ -0,0 +1,61 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file mavlink_listener_interface.h + * \author Daniel Koch + */ + +#ifndef MAVROSFLIGHT_MAVLINK_LISTENER_INTERFACE_H +#define MAVROSFLIGHT_MAVLINK_LISTENER_INTERFACE_H + +#include + +namespace mavrosflight +{ + +/** + * \brief Describes an interface classes can implement to receive and handle mavlink messages + */ +class MavlinkListenerInterface +{ +public: + + /** + * \brief The handler function for mavlink messages to be implemented by derived classes + * \param msg The mavlink message to handle + */ + virtual void handle_mavlink_message(const mavlink_message_t &msg) = 0; +}; + +} // namespace mavrosflight + +#endif // MAVROSFLIGHT_MAVLINK_LISTENER_INTERFACE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/mavlink_serial.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/mavlink_serial.h new file mode 100644 index 0000000..aa5b786 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/mavlink_serial.h @@ -0,0 +1,99 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file mavlink_serial.h + * \author Daniel Koch + */ + +#ifndef MAVROSFLIGHT_MAVLINK_SERIAL_H +#define MAVROSFLIGHT_MAVLINK_SERIAL_H + +#include + +#include +#include + +#include + +namespace mavrosflight +{ + +class MavlinkSerial : public MavlinkComm +{ +public: + + /** + * \brief Instantiates the class and begins communication on the specified serial port + * \param port Name of the serial port (e.g. "/dev/ttyUSB0") + * \param baud_rate Serial communication baud rate + */ + MavlinkSerial(std::string port, int baud_rate); + + /** + * \brief Stops communication and closes the serial port before the object is destroyed + */ + ~MavlinkSerial(); + +private: + + //=========================================================================== + // methods + //=========================================================================== + + virtual bool is_open(); + virtual void do_open(); + virtual void do_close(); + + /** + * \brief Initiate an asynchronous read operation + */ + virtual void do_async_read(const boost::asio::mutable_buffers_1 &buffer, boost::function handler); + + /** + * \brief Initialize an asynchronous write operation + * \param check_write_state If true, only start another write operation if a write sequence is not already running + */ + virtual void do_async_write(const boost::asio::const_buffers_1 &buffer, boost::function handler); + + //=========================================================================== + // member variables + //=========================================================================== + + boost::asio::serial_port serial_port_; //!< boost serial port object + + std::string port_; + int baud_rate_; +}; + +} // namespace mavrosflight + +#endif // MAVROSFLIGHT_MAVLINK_SERIAL_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/mavlink_udp.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/mavlink_udp.h new file mode 100644 index 0000000..69c24a4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/mavlink_udp.h @@ -0,0 +1,97 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file mavlink_udp.h + * \author Daniel Koch + */ + +#ifndef MAVROSFLIGHT_MAVLINK_UDP_H +#define MAVROSFLIGHT_MAVLINK_UDP_H + +#include + +#include +#include + +#include + +namespace mavrosflight +{ + +class MavlinkUDP : public MavlinkComm +{ +public: + + /** + * \brief Instantiates the class and begins communication on the specified serial port + * \param bind_host Host where this node is running + * \param bind_port Port number for this node + * \param remote_host Host where the other node is running + * \param remote_port Port number for the other node + */ + MavlinkUDP(std::string bind_host, uint16_t bind_port, std::string remote_host, uint16_t remote_port); + + /** + * \brief Stops communication and closes the serial port before the object is destroyed + */ + ~MavlinkUDP(); + +private: + + //=========================================================================== + // methods + //=========================================================================== + + virtual bool is_open(); + virtual void do_open(); + virtual void do_close(); + virtual void do_async_read(const boost::asio::mutable_buffers_1 &buffer, boost::function handler); + virtual void do_async_write(const boost::asio::const_buffers_1 &buffer, boost::function handler); + + //=========================================================================== + // member variables + //=========================================================================== + + std::string bind_host_; + uint16_t bind_port_; + + std::string remote_host_; + uint16_t remote_port_; + + boost::asio::ip::udp::socket socket_; + boost::asio::ip::udp::endpoint bind_endpoint_; + boost::asio::ip::udp::endpoint remote_endpoint_; +}; + +} // namespace mavrosflight + +#endif // MAVROSFLIGHT_MAVLINK_UDP_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/mavrosflight.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/mavrosflight.h new file mode 100644 index 0000000..9b80381 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/mavrosflight.h @@ -0,0 +1,86 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file mavrosflight.h + * \author Daniel Koch + */ + +#ifndef MAVROSFLIGHT_MAVROSFLIGHT_H +#define MAVROSFLIGHT_MAVROSFLIGHT_H + +#include +#include +#include +#include + +#include +#include + +#include + +#include +#include + +namespace mavrosflight +{ + +class MavROSflight +{ +public: + + /** + * \brief Instantiates the class and begins communication on the specified serial port + * \param mavlink_comm Reference to a MavlinkComm object (serial or UDP) + * \param baud_rate Serial communication baud rate + */ + MavROSflight(MavlinkComm& mavlink_comm, uint8_t sysid = 1, uint8_t compid = 50); + + /** + * \brief Stops communication and closes the serial port before the object is destroyed + */ + ~MavROSflight(); + + // public member objects + MavlinkComm& comm; + ParamManager param; + TimeManager time; + +private: + + // member variables + uint8_t sysid_; + uint8_t compid_; +}; + +} // namespace mavrosflight + +#endif // MAVROSFLIGHT_MAVROSFLIGHT_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/param.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/param.h new file mode 100644 index 0000000..22da913 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/param.h @@ -0,0 +1,108 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file param.h + * \author Daniel Koch + */ + +#ifndef MAVROSFLIGHT_PARAM_H +#define MAVROSFLIGHT_PARAM_H + +#include +#include + +#include + +namespace mavrosflight +{ + +class Param +{ +public: + Param(); + Param(mavlink_param_value_t msg); + Param(std::string name, int index, MAV_PARAM_TYPE type, float raw_value); + + uint16_t pack_param_set_msg(uint8_t system, uint8_t component, mavlink_message_t *msg, + uint8_t target_system, uint8_t target_component); + + std::string getName() const; + int getIndex() const; + MAV_PARAM_TYPE getType() const; + double getValue() const; + + void requestSet(double value, mavlink_message_t *msg); + bool handleUpdate(const mavlink_param_value_t &msg); + +private: + void init(std::string name, int index, MAV_PARAM_TYPE type, float raw_value); + + void setFromRawValue(float raw_value); + float getRawValue(); + float getRawValue(double value); + double getCastValue(double value); + + template + double fromRawValue(float value) + { + T t_value = *(T*) &value; + return (double) t_value; + } + + template + float toRawValue(double value) + { + T t_value = (T) value; + return *(float*) &t_value; + } + + template + double toCastValue(double value) + { + return (double) ((T) value); + } + + MavlinkSerial *serial_; + + std::string name_; + int index_; + MAV_PARAM_TYPE type_; + double value_; + + bool set_in_progress_; + double new_value_; + float expected_raw_value_; +}; + +} // namespace mavrosflight + +#endif // MAVROSFLIGHT_PARAM_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/param_listener_interface.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/param_listener_interface.h new file mode 100644 index 0000000..fa32f78 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/param_listener_interface.h @@ -0,0 +1,75 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file param_listener_interface.h + * \author Daniel Koch + */ + +#ifndef MAVROSFLIGHT_PARAM_LISTENER_INTERFACE_H +#define MAVROSFLIGHT_PARAM_LISTENER_INTERFACE_H + +#include + +namespace mavrosflight +{ + +/** + * \brief Describes an interface classes can implement to receive and handle mavlink messages + */ +class ParamListenerInterface +{ +public: + + /** + * \brief Called when a parameter is received from the autopilot for the first time + * \param name The name of the parameter + * \param value The value of the parameter + */ + virtual void on_new_param_received(std::string name, double value) = 0; + + /** + * \brief Called when an updated value is received for a parameter + * \param name The name of the parameter + * \param value The updated value of the parameter + */ + virtual void on_param_value_updated(std::string name, double value) = 0; + + /** + * \brief Called when the status of whether there are unsaved parameters changes + * \param unsaved_changes True if there are parameters that have been set but not saved on the autopilot + */ + virtual void on_params_saved_change(bool unsaved_changes) = 0; +}; + +} // namespace mavrosflight + +#endif // MAVROSFLIGHT_PARAM_LISTENER_INTERFACE_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/param_manager.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/param_manager.h new file mode 100644 index 0000000..b9e61e7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/param_manager.h @@ -0,0 +1,106 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file param_manager.h + * \author Daniel Koch + */ + +#ifndef MAVROSFLIGHT_PARAM_MANAGER_H +#define MAVROSFLIGHT_PARAM_MANAGER_H + +#include +#include +#include +#include +#include + +#include +#include +#include + +namespace mavrosflight +{ + +class ParamManager : public MavlinkListenerInterface +{ +public: + ParamManager(MavlinkComm * const comm); + ~ParamManager(); + + virtual void handle_mavlink_message(const mavlink_message_t &msg); + + bool unsaved_changes(); + + bool get_param_value(std::string name, double *value); + bool set_param_value(std::string name, double value); + bool write_params(); + + void register_param_listener(ParamListenerInterface *listener); + void unregister_param_listener(ParamListenerInterface *listener); + + bool save_to_file(std::string filename); + bool load_from_file(std::string filename); + + int get_num_params(); + int get_params_received(); + bool got_all_params(); + + void request_params(); + +private: + + void request_param_list(); + void request_param(int index); + + void handle_param_value_msg(const mavlink_message_t &msg); + void handle_command_ack_msg(const mavlink_message_t &msg); + + bool is_param_id(std::string name); + + std::vector listeners_; + + MavlinkComm *comm_; + std::map params_; + + bool unsaved_changes_; + bool write_request_in_progress_; + + bool first_param_received_; + size_t num_params_; + size_t received_count_; + bool *received_; + bool got_all_params_; +}; + +} // namespace mavrosflight + +#endif // MAVROSFLIGHT_PARAM_MANAGER_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/serial_exception.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/serial_exception.h new file mode 100644 index 0000000..3849710 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/serial_exception.h @@ -0,0 +1,92 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file serial_exception.h + * \author Daniel Koch + */ + +#ifndef MAVROSFLIGHT_SERIAL_EXCEPTION_H +#define MAVROSFLIGHT_SERIAL_EXCEPTION_H + +#include +#include +#include + +#include + +namespace mavrosflight +{ + +/** + * \brief Describes an exception encountered while using the boost serial libraries + */ +class SerialException : public std::exception +{ +public: + explicit SerialException(const char * const description) + { + init(description); + } + + explicit SerialException(const std::string &description) + { + init(description.c_str()); + } + + explicit SerialException(const boost::system::system_error &err) + { + init(err.what()); + } + + SerialException(const SerialException &other) : what_(other.what_) {} + + ~SerialException() throw() {} + + virtual const char* what() const throw() + { + return what_.c_str(); + } + +private: + std::string what_; + + void init(const char * const description) + { + std::ostringstream ss; + ss << "Serial Error: " << description; + what_ = ss.str(); + } +}; + +} // namespace mavrosflight + +#endif // MAVROSFLIGHT_SERIAL_EXCEPTION_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/time_manager.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/time_manager.h new file mode 100644 index 0000000..f7e943a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/time_manager.h @@ -0,0 +1,77 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file time_manager.h + * \author Daniel Koch + */ + +#ifndef MAVROSFLIGHT_TIME_MANAGER_H +#define MAVROSFLIGHT_TIME_MANAGER_H + +#include +#include +#include + +#include + +#include +#include + +namespace mavrosflight +{ + +class TimeManager : MavlinkListenerInterface +{ +public: + TimeManager(MavlinkComm *comm); + + virtual void handle_mavlink_message(const mavlink_message_t &msg); + + ros::Time get_ros_time_ms(uint32_t boot_ms); + ros::Time get_ros_time_us(uint32_t boot_us); + +private: + MavlinkComm *comm_; + + ros::Timer time_sync_timer_; + void timer_callback(const ros::TimerEvent &event); + + double offset_alpha_; + int64_t offset_ns_; + ros::Duration offset_; + + bool initialized_; +}; + +} // namespace mavrosflight + +#endif // MAVROSFLIGHT_TIME_MANAGER_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/write_buffer.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/write_buffer.h new file mode 100644 index 0000000..3de78b3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/mavrosflight/write_buffer.h @@ -0,0 +1,71 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file write_buffer.h + * \author Daniel Koch + */ + +#ifndef MAVROSFLIGHT_WRITE_BUFFER_H +#define MAVROSFLIGHT_WRITE_BUFFER_H + +#include + +#include + +namespace mavrosflight +{ + +/** + * \brief Struct for buffering the contents of a mavlink message + */ +struct WriteBuffer +{ + uint8_t data[MAVLINK_MAX_PACKET_LEN]; + size_t len; + size_t pos; + + WriteBuffer() : len(0), pos(0) {} + + WriteBuffer(const uint8_t * buf, uint16_t len) : len(len), pos(0) + { + assert(len <= MAVLINK_MAX_PACKET_LEN); //! \todo Do something less catastrophic here + memcpy(data, buf, len); + } + + uint8_t * dpos() { return data + pos; } + + size_t nbytes() { return len - pos; } +}; + +} // namespace mavrosflight + +#endif // MAVROSFLIGHT_WRITE_BUFFER_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/rosflight_io.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/rosflight_io.h new file mode 100644 index 0000000..b006dec --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/include/rosflight/rosflight_io.h @@ -0,0 +1,194 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file rosflight_io.h + * \author Daniel Koch + */ + +#ifndef ROSFLIGHT_IO_MAVROSFLIGHT_ROS_H +#define ROSFLIGHT_IO_MAVROSFLIGHT_ROS_H + +#include +#include + +#include + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace rosflight_io +{ + +class rosflightIO : + public mavrosflight::MavlinkListenerInterface, + public mavrosflight::ParamListenerInterface +{ +public: + rosflightIO(); + ~rosflightIO(); + + virtual void handle_mavlink_message(const mavlink_message_t &msg); + + virtual void on_new_param_received(std::string name, double value); + virtual void on_param_value_updated(std::string name, double value); + virtual void on_params_saved_change(bool unsaved_changes); + +private: + + // handle mavlink messages + void handle_heartbeat_msg(const mavlink_message_t &msg); + void handle_status_msg(const mavlink_message_t &msg); + void handle_command_ack_msg(const mavlink_message_t &msg); + void handle_statustext_msg(const mavlink_message_t &msg); + void handle_attitude_quaternion_msg(const mavlink_message_t &msg); + void handle_small_imu_msg(const mavlink_message_t &msg); + void handle_rosflight_output_raw_msg(const mavlink_message_t &msg); + void handle_rc_channels_raw_msg(const mavlink_message_t &msg); + void handle_diff_pressure_msg(const mavlink_message_t &msg); + void handle_small_baro_msg(const mavlink_message_t &msg); + void handle_small_mag_msg(const mavlink_message_t &msg); + void handle_named_value_int_msg(const mavlink_message_t &msg); + void handle_named_value_float_msg(const mavlink_message_t &msg); + void handle_named_command_struct_msg(const mavlink_message_t &msg); + void handle_small_range_msg(const mavlink_message_t &msg); + void handle_version_msg(const mavlink_message_t &msg); + + // ROS message callbacks + void commandCallback(rosflight_msgs::Command::ConstPtr msg); + + // ROS service callbacks + bool paramGetSrvCallback(rosflight_msgs::ParamGet::Request &req, rosflight_msgs::ParamGet::Response &res); + bool paramSetSrvCallback(rosflight_msgs::ParamSet::Request &req, rosflight_msgs::ParamSet::Response &res); + bool paramWriteSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res); + bool paramSaveToFileCallback(rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res); + bool paramLoadFromFileCallback(rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res); + bool calibrateImuBiasSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res); + bool calibrateRCTrimSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res); + bool calibrateBaroSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res); + bool calibrateAirspeedSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res); + bool rebootSrvCallback(std_srvs::Trigger::Request & req, std_srvs::Trigger::Response &res); + bool rebootToBootloaderSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res); + + // timer callbacks + void paramTimerCallback(const ros::TimerEvent &e); + void versionTimerCallback(const ros::TimerEvent &e); + + // helpers + void request_version(); + void check_error_code(uint8_t current, uint8_t previous, ROSFLIGHT_ERROR_CODE code, std::string name); + + template inline T saturate(T value, T min, T max) + { + return value < min ? min : (value > max ? max : value); + } + + + ros::NodeHandle nh_; + + ros::Subscriber command_sub_; + + ros::Publisher unsaved_params_pub_; + ros::Publisher imu_pub_; + ros::Publisher imu_temp_pub_; + ros::Publisher output_raw_pub_; + ros::Publisher rc_raw_pub_; + ros::Publisher diff_pressure_pub_; + ros::Publisher temperature_pub_; + ros::Publisher baro_pub_; + ros::Publisher sonar_pub_; + ros::Publisher mag_pub_; + ros::Publisher attitude_pub_; + ros::Publisher euler_pub_; + ros::Publisher status_pub_; + ros::Publisher version_pub_; + ros::Publisher lidar_pub_; + std::map named_value_int_pubs_; + std::map named_value_float_pubs_; + std::map named_command_struct_pubs_; + + ros::ServiceServer param_get_srv_; + ros::ServiceServer param_set_srv_; + ros::ServiceServer param_write_srv_; + ros::ServiceServer param_save_to_file_srv_; + ros::ServiceServer param_load_from_file_srv_; + ros::ServiceServer imu_calibrate_bias_srv_; + ros::ServiceServer imu_calibrate_temp_srv_; + ros::ServiceServer calibrate_rc_srv_; + ros::ServiceServer calibrate_baro_srv_; + ros::ServiceServer calibrate_airspeed_srv_; + ros::ServiceServer reboot_srv_; + ros::ServiceServer reboot_bootloader_srv_; + + ros::Timer param_timer_; + ros::Timer version_timer_; + + geometry_msgs::Quaternion attitude_quat_; + mavlink_rosflight_status_t prev_status_; + + std::string frame_id_; + + mavrosflight::MavlinkComm *mavlink_comm_; + mavrosflight::MavROSflight *mavrosflight_; +}; + +} // namespace rosflight_io + +#endif // ROSFLIGHT_IO_MAVROSFLIGHT_ROS_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/package.xml new file mode 100644 index 0000000..5269347 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/package.xml @@ -0,0 +1,37 @@ + + + rosflight + 0.1.3 + Package for interfacing to the ROSflight autopilot firmware over MAVLink + + Daniel Koch + + Daniel Koch + James Jackson + + BSD + + http://rosflight.org + https://github.com/rosflight/rosflight + https://github.com/rosflight/rosflight/issues + + catkin + + roscpp + rosflight_msgs + geometry_msgs + sensor_msgs + std_msgs + std_srvs + tf + + boost + eigen + yaml-cpp + + git + pkg-config + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mag_cal.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mag_cal.cpp new file mode 100644 index 0000000..be5cfc1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mag_cal.cpp @@ -0,0 +1,531 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file mag.cpp + * \author Jerel Nielsen + * \author Devon Morris + */ + +#include +#include + +namespace rosflight +{ + +CalibrateMag::CalibrateMag() : + calibrating_(false), + nh_private_("~"), + reference_field_strength_(1.0), + mag_subscriber_(nh_, "/magnetometer", 1) +{ + A_ = Eigen::MatrixXd::Zero(3, 3); + b_ = Eigen::MatrixXd::Zero(3, 1); + ransac_iters_ = 100; + inlier_thresh_ = 200; + + calibration_time_ = nh_private_.param("calibration_time", 60.0); + measurement_skip_ = nh_private_.param("measurement_skip", 20); + + param_set_client_ = nh_.serviceClient("param_set"); + mag_subscriber_.registerCallback(boost::bind(&CalibrateMag::mag_callback, this, _1)); +} + +void CalibrateMag::run() +{ + // reset calibration parameters + bool success = true; + // reset soft iron parameters + success = success && set_param("MAG_A11_COMP", 1.0f); + success = success && set_param("MAG_A12_COMP", 0.0f); + success = success && set_param("MAG_A13_COMP", 0.0f); + success = success && set_param("MAG_A21_COMP", 0.0f); + success = success && set_param("MAG_A22_COMP", 1.0f); + success = success && set_param("MAG_A23_COMP", 0.0f); + success = success && set_param("MAG_A31_COMP", 0.0f); + success = success && set_param("MAG_A32_COMP", 0.0f); + success = success && set_param("MAG_A33_COMP", 1.0f); + + // reset hard iron parameters + success = success && set_param("MAG_X_BIAS", 0.0f); + success = success && set_param("MAG_Y_BIAS", 0.0f); + success = success && set_param("MAG_Z_BIAS", 0.0f); + + if (!success) + { + ROS_FATAL("Failed to reset calibration parameters"); + return; + } + + start_mag_calibration(); + + // wait for data to arrive + ros::Duration timeout(3.0); + ros::Time start = ros::Time::now(); + while (ros::Time::now() - start < timeout && first_time_ && ros::ok()) + { + ros::spinOnce(); + } + + if (first_time_) + { + ROS_FATAL("No messages on magnetometer topic, unable to calibrate"); + return; + } + + while(calibrating_ && ros::ok()) + { + ros::spinOnce(); + } + + if (! calibrating_) + { + //compute calibration + do_mag_calibration(); + + // set calibration parameters + // set soft iron parameters + success = success && set_param("MAG_A11_COMP", a11()); + success = success && set_param("MAG_A12_COMP", a12()); + success = success && set_param("MAG_A13_COMP", a13()); + success = success && set_param("MAG_A21_COMP", a21()); + success = success && set_param("MAG_A22_COMP", a22()); + success = success && set_param("MAG_A23_COMP", a23()); + success = success && set_param("MAG_A31_COMP", a31()); + success = success && set_param("MAG_A32_COMP", a32()); + success = success && set_param("MAG_A33_COMP", a33()); + + // set hard iron parameters + success = success && set_param("MAG_X_BIAS", bx()); + success = success && set_param("MAG_Y_BIAS", by()); + success = success && set_param("MAG_Z_BIAS", bz()); + } + +} + +void CalibrateMag::set_reference_magnetic_field_strength(double reference_magnetic_field) +{ + reference_field_strength_ = reference_magnetic_field; +} + +void CalibrateMag::start_mag_calibration() +{ + calibrating_ = true; + + first_time_ = true; + start_time_ = 0; + + measurement_prev_ = Eigen::Vector3d::Zero(); + measurements_.clear(); +} + +void CalibrateMag::do_mag_calibration() +{ + // fit ellipsoid to measurements according to Li paper but in RANSAC form + ROS_INFO("Collected %u measurements. Fitting ellipsoid.", (uint32_t)measurements_.size()); + Eigen::MatrixXd u = ellipsoidRANSAC(measurements_, ransac_iters_, inlier_thresh_); + + // magnetometer calibration parameters according to Renaudin paper + ROS_INFO("Computing calibration parameters."); + magCal(u, A_, b_); +} + +bool CalibrateMag::mag_callback(const sensor_msgs::MagneticField::ConstPtr& mag) +{ + + if (calibrating_) + { + if (first_time_) + { + first_time_ = false; + ROS_WARN_ONCE("Calibrating Mag, do the mag dance for %g seconds!", calibration_time_); + start_time_ = ros::Time::now().toSec(); + } + + + double elapsed = ros::Time::now().toSec() - start_time_; + + printf("\r%.1f seconds remaining", calibration_time_ - elapsed); + + // if still in calibration mode + if (elapsed < calibration_time_) + { + if (measurement_throttle_ > measurement_skip_) + { + Eigen::Vector3d measurement; + measurement << mag->magnetic_field.x, mag->magnetic_field.y, mag->magnetic_field.z; + + if (measurement != measurement_prev_) + { + measurements_.push_back(measurement); + } + measurement_prev_ = measurement; + } + measurement_throttle_++; + } + else + { + ROS_WARN("\rdone!"); + calibrating_ = false; + } + } + +} + +Eigen::MatrixXd CalibrateMag::ellipsoidRANSAC(EigenSTL::vector_Vector3d meas, int iters, double inlier_thresh) +{ + // initialize random number generator + std::random_device random_dev; + std::mt19937 generator(random_dev()); + + // RANSAC to find a good ellipsoid fit + int inlier_count_best = 0; // number of inliers for best fit + EigenSTL::vector_Vector3d inliers_best; // container for inliers to best fit + double dist_sum = 0; // sum distances of all measurements from ellipsoid surface + int dist_count = 0; // count number distances of all measurements from ellipsoid surface + for (unsigned i = 0; i < iters; i++) + { + // pick 9 random, unique measurements by shuffling measurements + // and grabbing the first 9 + std::shuffle(meas.begin(), meas.end(), generator); + EigenSTL::vector_Vector3d meas_sample; + for (unsigned j = 0; j < 9; j++) + { + meas_sample.push_back(meas[j]); + } + + // fit ellipsoid to 9 random points + Eigen::MatrixXd u = ellipsoidLS(meas_sample); + + // check if LS fit is actually an ellipsoid (paragraph of Li following eq. 2-4) + // unpack needed parts of u + double a = u(0); + double b = u(1); + double c = u(2); + double f = u(3); + double g = u(4); + double h = u(5); + double p = u(6); + double q = u(7); + double r = u(8); + double d = u(9); + + double I = a + b + c; + double J = a * b + b * c + a *c - f * f - g * g - h * h; + + if (4 * J - I * I <= 0) + { + continue; + } + + // eq. 15 of Renaudin and eqs. 1 and 4 of Li + Eigen::MatrixXd Q(3, 3); + Q << a, h, g, + h, b, f, + g, f, c; + + Eigen::MatrixXd ub(3, 1); + ub << 2 * p, + 2 * q, + 2 * r; + double k = d; + + // eq. 21 of Renaudin (should be negative according to eq. 16) + // this is the vector to the ellipsoid center + Eigen::MatrixXd bb = -0.5 * Q.inverse() * ub; + Eigen::Vector3d r_e; r_e << bb(0), bb(1), bb(2); + + // count inliers and store inliers + int inlier_count = 0; + EigenSTL::vector_Vector3d inliers; + for (unsigned j = 0; j < meas.size(); j++) + { + // compute the vector from ellipsoid center to surface along + // measurement vector and a one from the perturbed measurement + Eigen::Vector3d perturb = Eigen::Vector3d::Ones() * 0.1; + Eigen::Vector3d r_int = intersect(meas[j], r_e, Q, ub, k); + Eigen::Vector3d r_int_prime = intersect(meas[j] + perturb, r_e, Q, ub, k); + + // now compute the vector normal to the surface + Eigen::Vector3d r_align = r_int_prime - r_int; + Eigen::Vector3d r_normal = r_align.cross(r_int.cross(r_int_prime)); + Eigen::Vector3d i_normal = r_normal / r_normal.norm(); + + // get vector from surface to measurement and take dot product + // with surface normal vector to find distance from ellipsoid fit + Eigen::Vector3d r_sm = meas[j] - r_e - r_int; + double dist = r_sm.dot(i_normal); + dist_sum += dist; + dist_count++; + + // check measurement distance against inlier threshold + if (fabs(dist) < inlier_thresh) + { + inliers.push_back(meas[j]); + inlier_count++; + } + } + + // save best inliers and their count + if (inlier_count > inlier_count_best) + { + inliers_best.clear(); + for (unsigned j = 0; j < inliers.size(); j++) + { + inliers_best.push_back(inliers[j]); + } + inlier_count_best = inlier_count; + } + } + + // check average measurement distance from surface + double dist_avg = dist_sum / dist_count; + if (inlier_thresh > fabs(dist_avg)) + { + ROS_WARN("Inlier threshold is greater than average measurement distance from surface. Reduce inlier threshold."); + ROS_INFO("Inlier threshold = %7.1f, Average measurement distance = %7.1f", inlier_thresh_, dist_avg); + } + + // perform LS on set of best inliers + Eigen::MatrixXd u_final = ellipsoidLS(inliers_best); + + return u_final; +} + +Eigen::Vector3d CalibrateMag::intersect(Eigen::Vector3d r_m, Eigen::Vector3d r_e, Eigen::MatrixXd Q, Eigen::MatrixXd ub, double k) +{ + // form unit vector from ellipsoid center (r_e) pointing to measurement + Eigen::Vector3d r_em = r_m - r_e; + Eigen::Vector3d i_em = r_em / r_em.norm(); + + // solve quadratic equation for alpha, which determines how much to scale + // i_em to intersect the ellipsoid surface (this is in Jerel's notebook) + double A = (i_em.transpose() * Q * i_em)(0); + double B = (2 * (i_em.transpose() * Q * r_e + ub.transpose() * i_em))(0); + double C = (ub.transpose() * r_e + r_e.transpose() * Q * r_e)(0) + k; + double alpha = (-B + sqrt(B * B - 4 * A * C)) / (2 * A); + + // compute vector from ellipsoid center to its surface along measurement vector + Eigen::Vector3d r_int = r_e + alpha * i_em; + + return r_int; +} + +void CalibrateMag::eigSort(Eigen::MatrixXd &w, Eigen::MatrixXd &v) +{ + // create index array + int idx[w.cols()]; + for (unsigned i = 0; i < w.cols(); i++) + { + idx[i] = i; + } + + // do a bubble sort and keep track of where values go with the index array + int has_changed = 1; // true + Eigen::MatrixXd w_sort = w; + while (has_changed == 1) + { + has_changed = 0; // false + for (unsigned i = 0; i < w.cols()-1; i++) + { + if (w_sort(i) < w_sort(i+1)) + { + // switch values + double tmp = w_sort(i); + w_sort(i) = w_sort(i+1); + w_sort(i+1) = tmp; + + // switch indices + tmp = idx[i]; + idx[i] = idx[i+1]; + idx[i+1] = tmp; + + has_changed = 1; // true + } + } + } + + // add sorted eigenvalues/eigenvectors to output + Eigen::MatrixXd w1 = w; + Eigen::MatrixXd v1 = v; + for (unsigned i = 0; i < w.cols(); i++) + { + w1(i) = w(idx[i]); + v1.col(i) = v.col(idx[i]); + } + w = w1; + v = v1; +} + +/* + This function gets ellipsoid parameters via least squares on ellipsoidal data + according to the paper: Li, Qingde, and John G. Griffiths. "Least squares ellipsoid + specific fitting." Geometric modeling and processing, 2004. proceedings. IEEE, 2004. + */ +Eigen::MatrixXd CalibrateMag::ellipsoidLS(EigenSTL::vector_Vector3d meas) +{ + // form D matrix from eq. 6 + Eigen::MatrixXd D(10, meas.size()); + for (unsigned i = 0; i < D.cols(); i++) + { + // unpack measurement components + double x = meas[i](0); + double y = meas[i](1); + double z = meas[i](2); + + // fill in the D matrix + D(0, i) = x * x; + D(1, i) = y * y; + D(2, i) = z * z; + D(3, i) = 2 * y * z; + D(4, i) = 2 * x * z; + D(5, i) = 2 * x * y; + D(6, i) = 2 * x; + D(7, i) = 2 * y; + D(8, i) = 2 * z; + D(9, i) = 1; + } + + // form the C1 matrix from eq. 7 + double k = 4; + Eigen::MatrixXd C1 = Eigen::MatrixXd::Zero(6, 6); + C1(0, 0) = -1; + C1(0, 1) = k / 2 - 1; + C1(0, 2) = k / 2 - 1; + C1(1, 0) = k / 2 - 1; + C1(1, 1) = -1; + C1(1, 2) = k / 2 - 1; + C1(2, 0) = k / 2 - 1; + C1(2, 1) = k / 2 - 1; + C1(2, 2) = -1; + C1(3, 3) = -k; + C1(4, 4) = -k; + C1(5, 5) = -k; + + // decompose D*D^T according to eq. 11 + Eigen::MatrixXd DDt = D * D.transpose(); + Eigen::MatrixXd S11 = DDt.block(0, 0, 6, 6); + Eigen::MatrixXd S12 = DDt.block(0, 6, 6, 4); + Eigen::MatrixXd S22 = DDt.block(6, 6, 4, 4); + + // solve eigensystem in eq. 15 + Eigen::MatrixXd ES = C1.inverse() * (S11 - S12 * S22.inverse() * S12.transpose()); + Eigen::EigenSolver eigensolver(ES); + if (eigensolver.info() != Eigen::Success) + { + abort(); + } + Eigen::MatrixXd w = eigensolver.eigenvalues().real().transpose(); + Eigen::MatrixXd V = eigensolver.eigenvectors().real(); + + // sort eigenvalues and eigenvectors from most positive to most negative + eigSort(w, V); + + // compute solution vector defined in paragraph below eq. 15 + Eigen::MatrixXd u1 = V.col(0); + Eigen::MatrixXd u2 = -S22.inverse() * S12.transpose() * u1; + Eigen::MatrixXd u(10, 1); + u.block(0, 0, 6, 1) = u1; + u.block(6, 0, 4, 1) = u2; + + return u; +} + +/* + This function compute magnetometer calibration parameters according to Section 5.3 of the +paper: Renaudin, Valérie, Muhammad Haris Afzal, and Gérard Lachapelle. "Complete triaxis +magnetometer calibration in the magnetic domain." Journal of sensors 2010 (2010). +*/ +void CalibrateMag::magCal(Eigen::MatrixXd u, Eigen::MatrixXd &A, Eigen::MatrixXd &bb) +{ + // unpack coefficients + double a = u(0); + double b = u(1); + double c = u(2); + double f = u(3); + double g = u(4); + double h = u(5); + double p = u(6); + double q = u(7); + double r = u(8); + double d = u(9); + + // compute Q, u, and k according to eq. 15 of Renaudin and eqs. 1 and 4 of Li + Eigen::MatrixXd Q(3, 3); + Q << a, h, g, + h, b, f, + g, f, c; + + Eigen::MatrixXd ub(3, 1); + ub << 2 * p, + 2 * q, + 2 * r; + double k = d; + + // extract bb according to eq. 21 of Renaudin (should be negative according to eq. 16) + bb = -0.5 * Q.inverse() * ub; + + // eigendecomposition of Q according to eq. 22 of Renaudin + Eigen::EigenSolver eigensolver(Q); + if (eigensolver.info() != Eigen::Success) + { + abort(); + } + Eigen::MatrixXd D = eigensolver.eigenvalues().real().asDiagonal(); + Eigen::MatrixXd V = eigensolver.eigenvectors().real(); + + // compute alpha according to eq. 27 of Renaudin (the denominator needs to be multiplied by -1) + double Hm = reference_field_strength_; // (uT) Provo, UT magnetic field magnitude + Eigen::MatrixXd utVDiVtu = ub.transpose() * V * D.inverse() * V.transpose() * ub; + double alpha = (4. * Hm * Hm) / (utVDiVtu(0) - 4 * k); + + // now compute A from eq. 8 and 28 of Renaudin + A = V * (alpha * D).cwiseSqrt() * V.transpose(); +} + +bool CalibrateMag::set_param(std::string name, double value) +{ + rosflight_msgs::ParamSet srv; + srv.request.name = name; + srv.request.value = value; + + if (param_set_client_.call(srv)) + { + return srv.response.exists; + } + else + { + return false; + } + +} + +} // namespace mag_cal diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mag_cal_node.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mag_cal_node.cpp new file mode 100644 index 0000000..05e4b0f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mag_cal_node.cpp @@ -0,0 +1,49 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file mag_cal_node.cpp + * \author Devon Morris + */ + +#include +#include + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "calibrate_accel_temp"); + + rosflight::CalibrateMag calibrate; + calibrate.run(); + + ros::shutdown(); + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/mavlink_comm.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/mavlink_comm.cpp new file mode 100644 index 0000000..3f3f334 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/mavlink_comm.cpp @@ -0,0 +1,213 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file mavlink_comm.cpp + * \author Daniel Koch + */ + +#include + +namespace mavrosflight +{ + +using boost::asio::serial_port_base; + +MavlinkComm::MavlinkComm() : + io_service_(), + write_in_progress_(false) +{ +} + +MavlinkComm::~MavlinkComm() +{ +} + +void MavlinkComm::open() +{ + // open the port + do_open(); + + // start reading from the port + async_read(); + io_thread_ = boost::thread(boost::bind(&boost::asio::io_service::run, &this->io_service_)); +} + +void MavlinkComm::close() +{ + mutex_lock lock(mutex_); + + io_service_.stop(); + do_close(); + + if (io_thread_.joinable()) + { + io_thread_.join(); + } +} + +void MavlinkComm::register_mavlink_listener(MavlinkListenerInterface * const listener) +{ + if (listener == NULL) + return; + + bool already_registered = false; + for (int i = 0; i < listeners_.size(); i++) + { + if (listener == listeners_[i]) + { + already_registered = true; + break; + } + } + + if (!already_registered) + listeners_.push_back(listener); +} + +void MavlinkComm::unregister_mavlink_listener(MavlinkListenerInterface * const listener) +{ + if (listener == NULL) + return; + + for (int i = 0; i < listeners_.size(); i++) + { + if (listener == listeners_[i]) + { + listeners_.erase(listeners_.begin() + i); + i--; + } + } +} + +void MavlinkComm::async_read() +{ + if (!is_open()) return; + + do_async_read( + boost::asio::buffer(read_buf_raw_, MAVLINK_SERIAL_READ_BUF_SIZE), + boost::bind( + &MavlinkComm::async_read_end, + this, + boost::asio::placeholders::error, + boost::asio::placeholders::bytes_transferred)); +} + +void MavlinkComm::async_read_end(const boost::system::error_code &error, size_t bytes_transferred) +{ + if (!is_open()) return; + + if (error) + { + close(); + return; + } + + for (int i = 0; i < bytes_transferred; i++) + { + if (mavlink_parse_char(MAVLINK_COMM_0, read_buf_raw_[i], &msg_in_, &status_in_)) + { + for (int i = 0; i < listeners_.size(); i++) + { + listeners_[i]->handle_mavlink_message(msg_in_); + } + } + } + + async_read(); +} + +void MavlinkComm::send_message(const mavlink_message_t &msg) +{ + WriteBuffer *buffer = new WriteBuffer(); + buffer->len = mavlink_msg_to_send_buffer(buffer->data, &msg); + assert(buffer->len <= MAVLINK_MAX_PACKET_LEN); //! \todo Do something less catastrophic here + + { + mutex_lock lock(mutex_); + write_queue_.push_back(buffer); + } + + async_write(true); +} + +void MavlinkComm::async_write(bool check_write_state) +{ + if (check_write_state && write_in_progress_) + return; + + mutex_lock lock(mutex_); + if (write_queue_.empty()) + return; + + write_in_progress_ = true; + WriteBuffer *buffer = write_queue_.front(); + do_async_write( + boost::asio::buffer(buffer->dpos(), buffer->nbytes()), + boost::bind( + &MavlinkComm::async_write_end, + this, + boost::asio::placeholders::error, + boost::asio::placeholders::bytes_transferred)); + +} + +void MavlinkComm::async_write_end(const boost::system::error_code &error, std::size_t bytes_transferred) +{ + if (error) + { + std::cerr << error.message() << std::endl; + close(); + return; + } + + mutex_lock lock(mutex_); + if (write_queue_.empty()) + { + write_in_progress_ = false; + return; + } + + WriteBuffer *buffer = write_queue_.front(); + buffer->pos += bytes_transferred; + if (buffer->nbytes() == 0) + { + write_queue_.pop_front(); + delete buffer; + } + + if (write_queue_.empty()) + write_in_progress_ = false; + else + async_write(false); +} + +} // namespace mavrosflight diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/mavlink_serial.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/mavlink_serial.cpp new file mode 100644 index 0000000..c1bc955 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/mavlink_serial.cpp @@ -0,0 +1,95 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file mavlink_serial.cpp + * \author Daniel Koch + */ + +#include +#include + +namespace mavrosflight +{ + +using boost::asio::serial_port_base; + +MavlinkSerial::MavlinkSerial(std::string port, int baud_rate) : + MavlinkComm(), + serial_port_(io_service_), + port_(port), + baud_rate_(baud_rate) +{ +} + +MavlinkSerial::~MavlinkSerial() +{ + do_close(); +} + +bool MavlinkSerial::is_open() +{ + return serial_port_.is_open(); +} + +void MavlinkSerial::do_open() +{ + try + { + serial_port_.open(port_); + serial_port_.set_option(serial_port_base::baud_rate(baud_rate_)); + serial_port_.set_option(serial_port_base::character_size(8)); + serial_port_.set_option(serial_port_base::parity(serial_port_base::parity::none)); + serial_port_.set_option(serial_port_base::stop_bits(serial_port_base::stop_bits::one)); + serial_port_.set_option(serial_port_base::flow_control(serial_port_base::flow_control::none)); + } + catch (boost::system::system_error e) + { + throw SerialException(e); + } +} + +void MavlinkSerial::do_close() +{ + serial_port_.close(); +} + +void MavlinkSerial::do_async_read(const boost::asio::mutable_buffers_1 &buffer, boost::function handler) +{ + serial_port_.async_read_some(buffer, handler); +} + +void MavlinkSerial::do_async_write(const boost::asio::const_buffers_1 &buffer, boost::function handler) +{ + serial_port_.async_write_some(buffer, handler); +} + +} // namespace mavrosflight diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/mavlink_udp.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/mavlink_udp.cpp new file mode 100644 index 0000000..934cffe --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/mavlink_udp.cpp @@ -0,0 +1,107 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file mavlink_udp.cpp + * \author Daniel Koch + */ + +#include +#include + +using boost::asio::ip::udp; + +namespace mavrosflight +{ + +using boost::asio::serial_port_base; + +MavlinkUDP::MavlinkUDP(std::string bind_host, uint16_t bind_port, std::string remote_host, uint16_t remote_port) : + MavlinkComm(), + socket_(io_service_), + bind_host_(bind_host), + bind_port_(bind_port), + remote_host_(remote_host), + remote_port_(remote_port) +{ +} + +MavlinkUDP::~MavlinkUDP() +{ + do_close(); +} + +bool MavlinkUDP::is_open() +{ + return socket_.is_open(); +} + +void MavlinkUDP::do_open() +{ + try + { + udp::resolver resolver(io_service_); + + bind_endpoint_ = *resolver.resolve({udp::v4(), bind_host_, ""}); + bind_endpoint_.port(bind_port_); + + remote_endpoint_ = *resolver.resolve({udp::v4(), remote_host_, ""}); + remote_endpoint_.port(remote_port_); + + socket_.open(udp::v4()); + socket_.bind(bind_endpoint_); + + socket_.set_option(udp::socket::reuse_address(true)); + socket_.set_option(udp::socket::send_buffer_size(1000*MAVLINK_MAX_PACKET_LEN)); + socket_.set_option(udp::socket::receive_buffer_size(1000*MAVLINK_SERIAL_READ_BUF_SIZE)); + } + catch (boost::system::system_error e) + { + throw SerialException(e); + } +} + +void MavlinkUDP::do_close() +{ + socket_.close(); +} + +void MavlinkUDP::do_async_read(const boost::asio::mutable_buffers_1 &buffer, boost::function handler) +{ + socket_.async_receive_from(buffer, remote_endpoint_, handler); +} + +void MavlinkUDP::do_async_write(const boost::asio::const_buffers_1 &buffer, boost::function handler) +{ + socket_.async_send_to(buffer, remote_endpoint_, handler); +} + +} // namespace mavrosflight diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/mavrosflight.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/mavrosflight.cpp new file mode 100644 index 0000000..2af1918 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/mavrosflight.cpp @@ -0,0 +1,62 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file mavrosflight.cpp + * \author Daniel Koch + */ + +#include + +#include + +namespace mavrosflight +{ + +using boost::asio::serial_port_base; + +MavROSflight::MavROSflight(MavlinkComm &mavlink_comm, uint8_t sysid /* = 1 */, uint8_t compid /* = 50 */) : + comm(mavlink_comm), + param(&comm), + time(&comm), + sysid_(sysid), + compid_(compid) +{ + //! \todo Fix constructors so that we can open the port in here + // comm.open(); +} + +MavROSflight::~MavROSflight() +{ + comm.close(); +} + +} // namespace mavrosflight diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/param.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/param.cpp new file mode 100644 index 0000000..8482c1b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/param.cpp @@ -0,0 +1,224 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file param.cpp + * \author Daniel Koch + */ + +#include + +namespace mavrosflight +{ + +Param::Param() +{ + init("", -1, MAV_PARAM_TYPE_ENUM_END, 0.0f); +} + +Param::Param(mavlink_param_value_t msg) +{ + char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1]; + memcpy(name, msg.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); + name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; + + init(std::string(name), + msg.param_index, + (MAV_PARAM_TYPE) msg.param_type, + msg.param_value); +} + +Param::Param(std::string name, int index, MAV_PARAM_TYPE type, float raw_value) +{ + init(name, index, type, raw_value); +} + +std::string Param::getName() const +{ + return name_; +} + +int Param::getIndex() const +{ + return index_; +} + +MAV_PARAM_TYPE Param::getType() const +{ + return type_; +} + +double Param::getValue() const +{ + return value_; +} + +void Param::requestSet(double value, mavlink_message_t *msg) +{ + if (value != value_) + { + new_value_ = getCastValue(value); + expected_raw_value_ = getRawValue(new_value_); + + mavlink_msg_param_set_pack(1, 50, msg, + 1, MAV_COMP_ID_ALL, name_.c_str(), expected_raw_value_, type_); + + set_in_progress_ = true; + } +} + +bool Param::handleUpdate(const mavlink_param_value_t &msg) +{ + if (msg.param_index != index_) + return false; + + if (msg.param_type != type_) + return false; + + if (set_in_progress_ && msg.param_value == expected_raw_value_) + set_in_progress_ = false; + + if (msg.param_value != getRawValue()) + { + setFromRawValue(msg.param_value); + return true; + } + + return false; +} + +void Param::init(std::string name, int index, MAV_PARAM_TYPE type, float raw_value) +{ + name_ = name; + index_ = index; + type_ = type; + setFromRawValue(raw_value); + set_in_progress_ = false; +} + +void Param::setFromRawValue(float raw_value) +{ + switch (type_) + { + case MAV_PARAM_TYPE_INT8: + value_ = fromRawValue(raw_value); + break; + case MAV_PARAM_TYPE_INT16: + value_ = fromRawValue(raw_value); + break; + case MAV_PARAM_TYPE_INT32: + value_ = fromRawValue(raw_value); + break; + case MAV_PARAM_TYPE_UINT8: + value_ = fromRawValue(raw_value); + break; + case MAV_PARAM_TYPE_UINT16: + value_ = fromRawValue(raw_value); + break; + case MAV_PARAM_TYPE_UINT32: + value_ = fromRawValue(raw_value); + break; + case MAV_PARAM_TYPE_REAL32: + value_ = fromRawValue(raw_value); + break; + } +} + +float Param::getRawValue() +{ + return getRawValue(value_); +} + +float Param::getRawValue(double value) +{ + float raw_value; + + switch (type_) + { + case MAV_PARAM_TYPE_INT8: + raw_value = toRawValue(value); + break; + case MAV_PARAM_TYPE_INT16: + raw_value = toRawValue(value); + break; + case MAV_PARAM_TYPE_INT32: + raw_value = toRawValue(value); + break; + case MAV_PARAM_TYPE_UINT8: + raw_value = toRawValue(value); + break; + case MAV_PARAM_TYPE_UINT16: + raw_value = toRawValue(value); + break; + case MAV_PARAM_TYPE_UINT32: + raw_value = toRawValue(value); + break; + case MAV_PARAM_TYPE_REAL32: + raw_value = toRawValue(value); + break; + } + + return raw_value; +} + +double Param::getCastValue(double value) +{ + double cast_value; + + switch (type_) + { + case MAV_PARAM_TYPE_INT8: + cast_value = toCastValue(value); + break; + case MAV_PARAM_TYPE_INT16: + cast_value = toCastValue(value); + break; + case MAV_PARAM_TYPE_INT32: + cast_value = toCastValue(value); + break; + case MAV_PARAM_TYPE_UINT8: + cast_value = toCastValue(value); + break; + case MAV_PARAM_TYPE_UINT16: + cast_value = toCastValue(value); + break; + case MAV_PARAM_TYPE_UINT32: + cast_value = toCastValue(value); + break; + case MAV_PARAM_TYPE_REAL32: + cast_value = toCastValue(value); + break; + } + + return cast_value; +} + +} // namespace mavrosflight diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/param_manager.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/param_manager.cpp new file mode 100644 index 0000000..40d50e4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/param_manager.cpp @@ -0,0 +1,369 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file param_manager.h + * \author Daniel Koch + */ + +#include +#include +#include + +#include + +namespace mavrosflight +{ + +ParamManager::ParamManager(MavlinkComm * const comm) : + comm_(comm), + unsaved_changes_(false), + write_request_in_progress_(false), + first_param_received_(false), + received_count_(0), + got_all_params_(false) +{ + comm_->register_mavlink_listener(this); +} + +ParamManager::~ParamManager() +{ + if (first_param_received_) + { + delete[] received_; + } +} + +void ParamManager::handle_mavlink_message(const mavlink_message_t &msg) +{ + switch (msg.msgid) + { + case MAVLINK_MSG_ID_PARAM_VALUE: + handle_param_value_msg(msg); + break; + case MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK: + handle_command_ack_msg(msg); + break; + } +} + +bool ParamManager::unsaved_changes() +{ + return unsaved_changes_; +} + +bool ParamManager::get_param_value(std::string name, double *value) +{ + if (is_param_id(name)) + { + *value = params_[name].getValue(); + return true; + } + else + { + *value = 0.0; + return false; + } +} + +bool ParamManager::set_param_value(std::string name, double value) +{ + if (is_param_id(name)) + { + mavlink_message_t msg; + params_[name].requestSet(value, &msg); + comm_->send_message(msg); + + return true; + } + else + { + return false; + } +} + +bool ParamManager::write_params() +{ + if (!write_request_in_progress_) + { + mavlink_message_t msg; + uint8_t sysid = 1; + uint8_t compid = 1; + mavlink_msg_rosflight_cmd_pack(sysid, compid, &msg, ROSFLIGHT_CMD_WRITE_PARAMS); + comm_->send_message(msg); + + write_request_in_progress_ = true; + return true; + } + else + { + return false; + } +} + +void ParamManager::register_param_listener(ParamListenerInterface *listener) +{ + if (listener == NULL) + return; + + bool already_registered = false; + for (int i = 0; i < listeners_.size(); i++) + { + if (listener == listeners_[i]) + { + already_registered = true; + break; + } + } + + if (!already_registered) + listeners_.push_back(listener); +} + +void ParamManager::unregister_param_listener(ParamListenerInterface *listener) +{ + if (listener == NULL) + return; + + for (int i = 0; i < listeners_.size(); i++) + { + if (listener == listeners_[i]) + { + listeners_.erase(listeners_.begin() + i); + i--; + } + } +} + +bool ParamManager::save_to_file(std::string filename) +{ + // build YAML document + YAML::Emitter yaml; + yaml << YAML::BeginSeq; + std::map::iterator it; + for (it = params_.begin(); it != params_.end(); it++) + { + yaml << YAML::Flow; + yaml << YAML::BeginMap; + yaml << YAML::Key << "name" << YAML::Value << it->second.getName(); + yaml << YAML::Key << "type" << YAML::Value << (int) it->second.getType(); + yaml << YAML::Key << "value" << YAML::Value << it->second.getValue(); + yaml << YAML::EndMap; + } + yaml << YAML::EndSeq; + + // write to file + try + { + std::ofstream fout; + fout.open(filename.c_str()); + fout << yaml.c_str(); + fout.close(); + } + catch (...) + { + return false; + } + + return true; +} + +bool ParamManager::load_from_file(std::string filename) +{ + try + { + YAML::Node root = YAML::LoadFile(filename); + assert(root.IsSequence()); + + for (int i = 0; i < root.size(); i++) + { + if (root[i].IsMap() && root[i]["name"] && root[i]["type"] && root[i]["value"]) + { + if (is_param_id(root[i]["name"].as())) + { + Param param = params_.find(root[i]["name"].as())->second; + if ((MAV_PARAM_TYPE) root[i]["type"].as() == param.getType()) + { + set_param_value(root[i]["name"].as(), root[i]["value"].as()); + } + } + } + } + + return true; + } + catch (...) + { + return false; + } +} + +void ParamManager::request_params() +{ + if (!first_param_received_) + { + request_param_list(); + } + else + { + for (size_t i = 0; i < num_params_; i++) + { + if (!received_[i]) + { + request_param(i); + } + } + } +} + +void ParamManager::request_param_list() +{ + mavlink_message_t param_list_msg; + mavlink_msg_param_request_list_pack(1, 50, ¶m_list_msg, 1, MAV_COMP_ID_ALL); + comm_->send_message(param_list_msg); +} + +void ParamManager::request_param(int index) +{ + mavlink_message_t param_request_msg; + char empty[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN]; + mavlink_msg_param_request_read_pack(1, 50, ¶m_request_msg, 1, MAV_COMP_ID_ALL, empty, (int16_t) index); + comm_->send_message(param_request_msg); +} + +void ParamManager::handle_param_value_msg(const mavlink_message_t &msg) +{ + mavlink_param_value_t param; + mavlink_msg_param_value_decode(&msg, ¶m); + + if (!first_param_received_) + { + first_param_received_ = true; + num_params_ = param.param_count; + received_ = new bool[num_params_]; + for (int i = 0; i < num_params_; i++) + { + received_[i] = false; + } + } + + // ensure null termination of name + char c_name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1]; + memcpy(c_name, param.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); + c_name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; + + std::string name(c_name); + + if (!is_param_id(name)) // if we haven't received this param before, add it + { + params_[name] = Param(param); + received_[param.param_index] = true; + + // increase the param count + received_count_++; + if(received_count_ == num_params_) + { + got_all_params_ = true; + } + + for (int i = 0; i < listeners_.size(); i++) + listeners_[i]->on_new_param_received(name, params_[name].getValue()); + } + else // otherwise check if we have new unsaved changes as a result of a param set request + { + if (params_[name].handleUpdate(param)) + { + unsaved_changes_ = true; + for (int i = 0; i < listeners_.size(); i++) + { + listeners_[i]->on_param_value_updated(name, params_[name].getValue()); + listeners_[i]->on_params_saved_change(unsaved_changes_); + } + } + } +} + +void ParamManager::handle_command_ack_msg(const mavlink_message_t &msg) +{ + if (write_request_in_progress_) + { + mavlink_rosflight_cmd_ack_t ack; + mavlink_msg_rosflight_cmd_ack_decode(&msg, &ack); + + if (ack.command == ROSFLIGHT_CMD_WRITE_PARAMS) + { + write_request_in_progress_ = false; + if(ack.success == ROSFLIGHT_CMD_SUCCESS) + { + ROS_INFO("Param write succeeded"); + unsaved_changes_ = false; + + for (int i = 0; i < listeners_.size(); i++) + listeners_[i]->on_params_saved_change(unsaved_changes_); + } + else + { + ROS_INFO("Param write failed - maybe disarm the aricraft and try again?"); + write_request_in_progress_ = false; + unsaved_changes_ = true; + } + } + } +} + +bool ParamManager::is_param_id(std::string name) +{ + return (params_.find(name) != params_.end()); +} + +int ParamManager::get_num_params() +{ + if (first_param_received_) + { + return num_params_; + } + else + { + return 0; + } +} + +int ParamManager::get_params_received() +{ + return received_count_; +} + +bool ParamManager::got_all_params() +{ + return got_all_params_; +} + +} // namespace mavrosflight diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/time_manager.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/time_manager.cpp new file mode 100644 index 0000000..5230b5f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/mavrosflight/time_manager.cpp @@ -0,0 +1,122 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file time_manager.cpp + * \author Daniel Koch + */ + +#include + +namespace mavrosflight +{ + +TimeManager::TimeManager(MavlinkComm *comm) : + comm_(comm), + offset_alpha_(0.6), + offset_ns_(0), + offset_(0.0), + initialized_(false) +{ + comm_->register_mavlink_listener(this); + + ros::NodeHandle nh; + time_sync_timer_ = nh.createTimer(ros::Duration(0.01), &TimeManager::timer_callback, this, true); + // time_sync_timer_ = nh.createTimer(ros::Duration(ros::Rate(1)), &TimeManager::timer_callback, this); +} + +void TimeManager::handle_mavlink_message(const mavlink_message_t &msg) +{ + int64_t now_ns = ros::Time::now().toNSec(); + + if (msg.msgid == MAVLINK_MSG_ID_TIMESYNC) + { + mavlink_timesync_t tsync; + mavlink_msg_timesync_decode(&msg, &tsync); + + if (tsync.tc1 > 0) // check that this is a response, not a request + { + int64_t offset_ns = (tsync.ts1 + now_ns - 2*tsync.tc1) / 2; + + if (!initialized_ || std::abs(offset_ns_ - offset_ns) > 1e7) // if difference > 10ms, use it directly + { + offset_ns_ = offset_ns; + ROS_INFO("Detected time offset of %0.9f s. FCU time: %0.9f, System time: %0.9f", \ + offset_ns/1e9, tsync.ts1*1e-9, tsync.tc1*1e-9); + initialized_ = true; + time_sync_timer_.stop(); + } + else // otherwise low-pass filter the offset + { +// offset_ns_ = offset_alpha_*offset_ns + (1.0 - offset_alpha_)*offset_ns_; + } + } + } +} + +ros::Time TimeManager::get_ros_time_ms(uint32_t boot_ms) +{ + if (!initialized_) + return ros::Time::now(); + + int64_t ns = (uint64_t)boot_ms*1000000 + offset_ns_; + if (ns < 0) + { + return ros::Time::now(); + } + ros::Time now; + now.fromNSec(ns); + return now; +} + +ros::Time TimeManager::get_ros_time_us(uint32_t boot_us) +{ + if (!initialized_) + return ros::Time::now(); + + int64_t ns = (uint64_t)boot_us * 1000 + offset_ns_; + if (ns < 0) + { + return ros::Time::now(); + } + ros::Time now; + now.fromNSec(ns); + return now; +} + +void TimeManager::timer_callback(const ros::TimerEvent &event) +{ + mavlink_message_t msg; + mavlink_msg_timesync_pack(1, 50, &msg, 0, ros::Time::now().toNSec()); + comm_->send_message(msg); +} + +} // namespace mavrosflight diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/rosflight_io.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/rosflight_io.cpp new file mode 100644 index 0000000..50df347 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/rosflight_io.cpp @@ -0,0 +1,846 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file rosflight_io.cpp + * \author Daniel Koch + */ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +namespace rosflight_io +{ +rosflightIO::rosflightIO() +{ + command_sub_ = nh_.subscribe("command", 1, &rosflightIO::commandCallback, this); + + unsaved_params_pub_ = nh_.advertise("unsaved_params", 1, true); + + param_get_srv_ = nh_.advertiseService("param_get", &rosflightIO::paramGetSrvCallback, this); + param_set_srv_ = nh_.advertiseService("param_set", &rosflightIO::paramSetSrvCallback, this); + param_write_srv_ = nh_.advertiseService("param_write", &rosflightIO::paramWriteSrvCallback, this); + param_save_to_file_srv_ = nh_.advertiseService("param_save_to_file", &rosflightIO::paramSaveToFileCallback, this); + param_load_from_file_srv_ = nh_.advertiseService("param_load_from_file", &rosflightIO::paramLoadFromFileCallback, this); + imu_calibrate_bias_srv_ = nh_.advertiseService("calibrate_imu", &rosflightIO::calibrateImuBiasSrvCallback, this); + calibrate_rc_srv_ = nh_.advertiseService("calibrate_rc_trim", &rosflightIO::calibrateRCTrimSrvCallback, this); + reboot_srv_ = nh_.advertiseService("reboot", &rosflightIO::rebootSrvCallback, this); + reboot_bootloader_srv_ = nh_.advertiseService("reboot_to_bootloader", &rosflightIO::rebootToBootloaderSrvCallback, this); + + ros::NodeHandle nh_private("~"); + + if (nh_private.param("udp", false)) + { + std::string bind_host = nh_private.param("bind_host", "localhost"); + uint16_t bind_port = (uint16_t) nh_private.param("bind_port", 14520); + std::string remote_host = nh_private.param("remote_host", bind_host); + uint16_t remote_port = (uint16_t) nh_private.param("remote_port", 14525); + + ROS_INFO("Connecting over UDP to \"%s:%d\", from \"%s:%d\"", remote_host.c_str(), remote_port, bind_host.c_str(), bind_port); + + mavlink_comm_ = new mavrosflight::MavlinkUDP(bind_host, bind_port, remote_host, remote_port); + } + else + { + std::string port = nh_private.param("port", "/dev/ttyUSB0"); + int baud_rate = nh_private.param("baud_rate", 921600); + + ROS_INFO("Connecting to serial port \"%s\", at %d baud", port.c_str(), baud_rate); + + mavlink_comm_ = new mavrosflight::MavlinkSerial(port, baud_rate); + } + + try + { + mavlink_comm_->open(); //! \todo move this into the MavROSflight constructor + mavrosflight_ = new mavrosflight::MavROSflight(*mavlink_comm_); + } + catch (mavrosflight::SerialException e) + { + ROS_FATAL("%s", e.what()); + ros::shutdown(); + } + + mavrosflight_->comm.register_mavlink_listener(this); + mavrosflight_->param.register_param_listener(this); + + // request the param list + mavrosflight_->param.request_params(); + param_timer_ = nh_.createTimer(ros::Duration(1.0), &rosflightIO::paramTimerCallback, this); + + // request version information + request_version(); + version_timer_ = nh_.createTimer(ros::Duration(1.0), &rosflightIO::versionTimerCallback, this); + + // initialize latched "unsaved parameters" message value + std_msgs::Bool unsaved_msg; + unsaved_msg.data = false; + unsaved_params_pub_.publish(unsaved_msg); + + // Set up a few other random things + frame_id_ = nh_private.param("frame_id", "world"); + + prev_status_.armed = false; + prev_status_.failsafe = false; + prev_status_.rc_override = false; + prev_status_.offboard = false; + prev_status_.control_mode = OFFBOARD_CONTROL_MODE_ENUM_END; + prev_status_.error_code = ROSFLIGHT_ERROR_NONE; +} + +rosflightIO::~rosflightIO() +{ + delete mavrosflight_; + delete mavlink_comm_; +} + +void rosflightIO::handle_mavlink_message(const mavlink_message_t &msg) +{ + switch (msg.msgid) + { + case MAVLINK_MSG_ID_HEARTBEAT: + handle_heartbeat_msg(msg); + break; + case MAVLINK_MSG_ID_ROSFLIGHT_STATUS: + handle_status_msg(msg); + break; + case MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK: + handle_command_ack_msg(msg); + break; + case MAVLINK_MSG_ID_STATUSTEXT: + handle_statustext_msg(msg); + break; + case MAVLINK_MSG_ID_ATTITUDE_QUATERNION: + handle_attitude_quaternion_msg(msg); + break; + case MAVLINK_MSG_ID_SMALL_IMU: + handle_small_imu_msg(msg); + break; + case MAVLINK_MSG_ID_SMALL_MAG: + handle_small_mag_msg(msg); + break; + case MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW: + handle_rosflight_output_raw_msg(msg); + break; + case MAVLINK_MSG_ID_RC_CHANNELS: + handle_rc_channels_raw_msg(msg); + break; + case MAVLINK_MSG_ID_DIFF_PRESSURE: + handle_diff_pressure_msg(msg); + break; + case MAVLINK_MSG_ID_NAMED_VALUE_INT: + handle_named_value_int_msg(msg); + break; + case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT: + handle_named_value_float_msg(msg); + break; + case MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT: + handle_named_command_struct_msg(msg); + break; + case MAVLINK_MSG_ID_SMALL_BARO: + handle_small_baro_msg(msg); + break; + case MAVLINK_MSG_ID_SMALL_RANGE: + handle_small_range_msg(msg); + break; + case MAVLINK_MSG_ID_ROSFLIGHT_VERSION: + handle_version_msg(msg); + break; + case MAVLINK_MSG_ID_PARAM_VALUE: + case MAVLINK_MSG_ID_TIMESYNC: + // silently ignore (handled elsewhere) + break; + default: + ROS_DEBUG("rosflight_io: Got unhandled mavlink message ID %d", msg.msgid); + break; + } +} + +void rosflightIO::on_new_param_received(std::string name, double value) +{ + ROS_DEBUG("Got parameter %s with value %g", name.c_str(), value); +} + +void rosflightIO::on_param_value_updated(std::string name, double value) +{ + ROS_INFO("Parameter %s has new value %g", name.c_str(), value); +} + +void rosflightIO::on_params_saved_change(bool unsaved_changes) +{ + std_msgs::Bool msg; + msg.data = unsaved_changes; + unsaved_params_pub_.publish(msg); + + if (unsaved_changes) + { + ROS_WARN_THROTTLE(1,"There are unsaved changes to onboard parameters"); + } + else + { + ROS_INFO("Onboard parameters have been saved"); + } +} + +void rosflightIO::handle_heartbeat_msg(const mavlink_message_t &msg) +{ + ROS_INFO_ONCE("Got HEARTBEAT, connected."); +} + +void rosflightIO::handle_status_msg(const mavlink_message_t &msg) +{ + mavlink_rosflight_status_t status_msg; + mavlink_msg_rosflight_status_decode(&msg, &status_msg); + + // armed state check + if (prev_status_.armed != status_msg.armed) + { + if (status_msg.armed) + ROS_WARN("Autopilot ARMED"); + else + ROS_WARN("Autopilot DISARMED"); + } + + // failsafe check + if (prev_status_.failsafe != status_msg.failsafe) + { + if (status_msg.failsafe) + ROS_ERROR("Autopilot FAILSAFE"); + else + ROS_INFO("Autopilot FAILSAFE RECOVERED"); + } + + // rc override check + if (prev_status_.rc_override != status_msg.rc_override) + { + if (status_msg.rc_override) + ROS_WARN("RC override active"); + else + ROS_WARN("Returned to computer control"); + } + + // offboard control check + if (prev_status_.offboard != status_msg.offboard) + { + if (status_msg.offboard) + ROS_WARN("Computer control active"); + else + ROS_WARN("Computer control lost"); + } + + // Print if got error code + if (prev_status_.error_code != status_msg.error_code) + { + check_error_code(status_msg.error_code, prev_status_.error_code, ROSFLIGHT_ERROR_INVALID_MIXER, "Invalid mixer"); + check_error_code(status_msg.error_code, prev_status_.error_code, ROSFLIGHT_ERROR_IMU_NOT_RESPONDING, "IMU not responding"); + check_error_code(status_msg.error_code, prev_status_.error_code, ROSFLIGHT_ERROR_RC_LOST, "RC lost"); + check_error_code(status_msg.error_code, prev_status_.error_code, ROSFLIGHT_ERROR_UNHEALTHY_ESTIMATOR, "Unhealthy estimator"); + check_error_code(status_msg.error_code, prev_status_.error_code, ROSFLIGHT_ERROR_TIME_GOING_BACKWARDS, "Time going backwards"); + check_error_code(status_msg.error_code, prev_status_.error_code, ROSFLIGHT_ERROR_UNCALIBRATED_IMU, "Uncalibrated IMU"); + + ROS_DEBUG("Autopilot ERROR 0x%02x", status_msg.error_code); + } + + // Print if change in control mode + if (prev_status_.control_mode != status_msg.control_mode) + { + std::string mode_string; + switch (status_msg.control_mode) + { + case MODE_PASS_THROUGH: + mode_string = "PASS_THROUGH"; + break; + case MODE_ROLLRATE_PITCHRATE_YAWRATE_THROTTLE: + mode_string = "RATE"; + break; + case MODE_ROLL_PITCH_YAWRATE_THROTTLE: + mode_string = "ANGLE"; + break; + default: + mode_string = "UNKNOWN"; + } + ROS_WARN_STREAM("Autopilot now in " << mode_string << " mode"); + } + + prev_status_ = status_msg; + + // Build the status message and send it + rosflight_msgs::Status out_status; + out_status.header.stamp = ros::Time::now(); + out_status.armed = status_msg.armed; + out_status.failsafe = status_msg.failsafe; + out_status.rc_override = status_msg.rc_override; + out_status.offboard = status_msg.offboard; + out_status.control_mode = status_msg.control_mode; + out_status.error_code = status_msg.error_code; + out_status.num_errors = status_msg.num_errors; + out_status.loop_time_us = status_msg.loop_time_us; + if (status_pub_.getTopic().empty()) + { + status_pub_ = nh_.advertise("status", 1); + } + status_pub_.publish(out_status); +} + +void rosflightIO::handle_command_ack_msg(const mavlink_message_t &msg) +{ + mavlink_rosflight_cmd_ack_t ack; + mavlink_msg_rosflight_cmd_ack_decode(&msg, &ack); + + if (ack.success == ROSFLIGHT_CMD_SUCCESS) + { + ROS_DEBUG("MAVLink command %d Acknowledged", ack.command); + } + else + { + ROS_ERROR("MAVLink command %d Failed", ack.command); + } +} + +void rosflightIO::handle_statustext_msg(const mavlink_message_t &msg) +{ + mavlink_statustext_t status; + mavlink_msg_statustext_decode(&msg, &status); + + // ensure null termination + char c_str[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN + 1]; + memcpy(c_str, status.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN); + c_str[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = '\0'; + + switch (status.severity) + { + case MAV_SEVERITY_EMERGENCY: + case MAV_SEVERITY_ALERT: + case MAV_SEVERITY_CRITICAL: + case MAV_SEVERITY_ERROR: + ROS_ERROR("[Autopilot]: %s", c_str); + break; + case MAV_SEVERITY_WARNING: + ROS_WARN("[Autopilot]: %s", c_str); + break; + case MAV_SEVERITY_NOTICE: + case MAV_SEVERITY_INFO: + ROS_INFO("[Autopilot]: %s", c_str); + break; + case MAV_SEVERITY_DEBUG: + ROS_DEBUG("[Autopilot]: %s", c_str); + break; + } +} + +void rosflightIO::handle_attitude_quaternion_msg(const mavlink_message_t &msg) +{ + mavlink_attitude_quaternion_t attitude; + mavlink_msg_attitude_quaternion_decode(&msg, &attitude); + + rosflight_msgs::Attitude attitude_msg; + attitude_msg.header.stamp = mavrosflight_->time.get_ros_time_ms(attitude.time_boot_ms); + attitude_msg.attitude.w = attitude.q1; + attitude_msg.attitude.x = attitude.q2; + attitude_msg.attitude.y = attitude.q3; + attitude_msg.attitude.z = attitude.q4; + attitude_msg.angular_velocity.x = attitude.rollspeed; + attitude_msg.angular_velocity.y = attitude.pitchspeed; + attitude_msg.angular_velocity.z = attitude.yawspeed; + + geometry_msgs::Vector3Stamped euler_msg; + euler_msg.header.stamp = attitude_msg.header.stamp; + + tf::Quaternion quat(attitude.q2, attitude.q3, attitude.q4, attitude.q1); + tf::Matrix3x3(quat).getEulerYPR(euler_msg.vector.z, euler_msg.vector.y, euler_msg.vector.x); + + // save off the quaternion for use with the IMU callback + tf::quaternionTFToMsg(quat, attitude_quat_); + + if (attitude_pub_.getTopic().empty()) + { + attitude_pub_ = nh_.advertise("attitude", 1); + } + if (euler_pub_.getTopic().empty()) + { + euler_pub_ = nh_.advertise("attitude/euler", 1); + } + attitude_pub_.publish(attitude_msg); + euler_pub_.publish(euler_msg); +} + +void rosflightIO::handle_small_imu_msg(const mavlink_message_t &msg) +{ + mavlink_small_imu_t imu; + mavlink_msg_small_imu_decode(&msg, &imu); + + sensor_msgs::Imu imu_msg; + imu_msg.header.stamp = mavrosflight_->time.get_ros_time_us(imu.time_boot_us); + imu_msg.header.frame_id = frame_id_; + imu_msg.linear_acceleration.x = imu.xacc; + imu_msg.linear_acceleration.y = imu.yacc; + imu_msg.linear_acceleration.z = imu.zacc; + imu_msg.angular_velocity.x = imu.xgyro; + imu_msg.angular_velocity.y = imu.ygyro; + imu_msg.angular_velocity.z = imu.zgyro; + imu_msg.orientation = attitude_quat_; + + sensor_msgs::Temperature temp_msg; + temp_msg.header.stamp = imu_msg.header.stamp; + temp_msg.header.frame_id = frame_id_; + temp_msg.temperature = imu.temperature; + + if (imu_pub_.getTopic().empty()) + { + imu_pub_ = nh_.advertise("imu/data", 1); + } + imu_pub_.publish(imu_msg); + + if (imu_temp_pub_.getTopic().empty()) + { + imu_temp_pub_ = nh_.advertise("imu/temperature", 1); + } + imu_temp_pub_.publish(temp_msg); +} + +void rosflightIO::handle_rosflight_output_raw_msg(const mavlink_message_t &msg) +{ + mavlink_rosflight_output_raw_t servo; + mavlink_msg_rosflight_output_raw_decode(&msg, &servo); + + rosflight_msgs::OutputRaw out_msg; + out_msg.header.stamp = mavrosflight_->time.get_ros_time_us(servo.stamp); + for (int i = 0; i < 8; i++) + { + out_msg.values[i] = servo.values[i]; + } + + if (output_raw_pub_.getTopic().empty()) + { + output_raw_pub_ = nh_.advertise("output_raw", 1); + } + output_raw_pub_.publish(out_msg); +} + +void rosflightIO::handle_rc_channels_raw_msg(const mavlink_message_t &msg) +{ + mavlink_rc_channels_raw_t rc; + mavlink_msg_rc_channels_raw_decode(&msg, &rc); + + rosflight_msgs::RCRaw out_msg; + out_msg.header.stamp = mavrosflight_->time.get_ros_time_ms(rc.time_boot_ms); + + out_msg.values[0] = rc.chan1_raw; + out_msg.values[1] = rc.chan2_raw; + out_msg.values[2] = rc.chan3_raw; + out_msg.values[3] = rc.chan4_raw; + out_msg.values[4] = rc.chan5_raw; + out_msg.values[5] = rc.chan6_raw; + out_msg.values[6] = rc.chan7_raw; + out_msg.values[7] = rc.chan8_raw; + + if (rc_raw_pub_.getTopic().empty()) + { + rc_raw_pub_ = nh_.advertise("rc_raw", 1); + } + rc_raw_pub_.publish(out_msg); +} + +void rosflightIO::handle_diff_pressure_msg(const mavlink_message_t &msg) +{ + mavlink_diff_pressure_t diff; + mavlink_msg_diff_pressure_decode(&msg, &diff); + + rosflight_msgs::Airspeed airspeed_msg; + airspeed_msg.header.stamp = ros::Time::now(); + airspeed_msg.velocity = diff.velocity; + airspeed_msg.differential_pressure = diff.diff_pressure; + airspeed_msg.temperature = diff.temperature; + + if(calibrate_airspeed_srv_.getService().empty()) + { + calibrate_airspeed_srv_ = nh_.advertiseService("calibrate_airspeed", &rosflightIO::calibrateAirspeedSrvCallback, this); + } + + if (diff_pressure_pub_.getTopic().empty()) + { + diff_pressure_pub_ = nh_.advertise("airspeed", 1); + } + diff_pressure_pub_.publish(airspeed_msg); +} + +void rosflightIO::handle_named_value_int_msg(const mavlink_message_t &msg) +{ + mavlink_named_value_int_t val; + mavlink_msg_named_value_int_decode(&msg, &val); + + // ensure null termination of name + char c_name[MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN + 1]; + memcpy(c_name, val.name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN); + c_name[MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN] = '\0'; + std::string name(c_name); + + if (named_value_int_pubs_.find(name) == named_value_int_pubs_.end()) + { + ros::NodeHandle nh; + named_value_int_pubs_[name] = nh.advertise("named_value/int/" + name, 1); + } + + std_msgs::Int32 out_msg; + out_msg.data = val.value; + + named_value_int_pubs_[name].publish(out_msg); +} + +void rosflightIO::handle_named_value_float_msg(const mavlink_message_t &msg) +{ + mavlink_named_value_float_t val; + mavlink_msg_named_value_float_decode(&msg, &val); + + // ensure null termination of name + char c_name[MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN + 1]; + memcpy(c_name, val.name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN); + c_name[MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN] = '\0'; + std::string name(c_name); + + if (named_value_float_pubs_.find(name) == named_value_float_pubs_.end()) + { + ros::NodeHandle nh; + named_value_float_pubs_[name] = nh.advertise("named_value/float/" + name, 1); + } + + std_msgs::Float32 out_msg; + out_msg.data = val.value; + + named_value_float_pubs_[name].publish(out_msg); +} + +void rosflightIO::handle_named_command_struct_msg(const mavlink_message_t &msg) +{ + mavlink_named_command_struct_t command; + mavlink_msg_named_command_struct_decode(&msg, &command); + + // ensure null termination of name + char c_name[MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN + 1]; + memcpy(c_name, command.name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN); + c_name[MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN] = '\0'; + std::string name(c_name); + + if (named_command_struct_pubs_.find(name) == named_command_struct_pubs_.end()) + { + ros::NodeHandle nh; + named_command_struct_pubs_[name] = nh.advertise("named_value/command_struct/" + name, 1); + } + + rosflight_msgs::Command command_msg; + if (command.type == MODE_PASS_THROUGH) + command_msg.mode = rosflight_msgs::Command::MODE_PASS_THROUGH; + else if (command.type == MODE_ROLLRATE_PITCHRATE_YAWRATE_THROTTLE) + command_msg.mode = rosflight_msgs::Command::MODE_ROLLRATE_PITCHRATE_YAWRATE_THROTTLE; + else if (command.type == MODE_ROLL_PITCH_YAWRATE_THROTTLE) + command_msg.mode = rosflight_msgs::Command::MODE_ROLL_PITCH_YAWRATE_THROTTLE; + else if (command.type == MODE_ROLL_PITCH_YAWRATE_ALTITUDE) + command_msg.mode = rosflight_msgs::Command::MODE_ROLL_PITCH_YAWRATE_ALTITUDE; + + command_msg.ignore = command.ignore; + command_msg.x = command.x; + command_msg.y = command.y; + command_msg.z = command.z; + command_msg.F = command.F; + named_command_struct_pubs_[name].publish(command_msg); +} + +void rosflightIO::handle_small_baro_msg(const mavlink_message_t &msg) +{ + mavlink_small_baro_t baro; + mavlink_msg_small_baro_decode(&msg, &baro); + + rosflight_msgs::Barometer baro_msg; + baro_msg.header.stamp = ros::Time::now(); + baro_msg.altitude = baro.altitude; + baro_msg.pressure = baro.pressure; + baro_msg.temperature = baro.temperature; + + // If we are getting barometer messages, then we should publish the barometer calibration service + if(calibrate_baro_srv_.getService().empty()) + { + calibrate_baro_srv_ = nh_.advertiseService("calibrate_baro", &rosflightIO::calibrateBaroSrvCallback, this); + } + + if (baro_pub_.getTopic().empty()) + { + baro_pub_ = nh_.advertise("baro", 1); + } + baro_pub_.publish(baro_msg); +} + +void rosflightIO::handle_small_mag_msg(const mavlink_message_t &msg) +{ + mavlink_small_mag_t mag; + mavlink_msg_small_mag_decode(&msg, &mag); + + //! \todo calibration, correct units, floating point message type + sensor_msgs::MagneticField mag_msg; + mag_msg.header.stamp = ros::Time::now();//mavrosflight_->time.get_ros_time_us(mag.time_boot_us); + mag_msg.header.frame_id = frame_id_; + + mag_msg.magnetic_field.x = mag.xmag; + mag_msg.magnetic_field.y = mag.ymag; + mag_msg.magnetic_field.z = mag.zmag; + + if (mag_pub_.getTopic().empty()) + { + mag_pub_ = nh_.advertise("magnetometer", 1); + } + mag_pub_.publish(mag_msg); +} + +void rosflightIO::handle_small_range_msg(const mavlink_message_t &msg) +{ + mavlink_small_range_t range; + mavlink_msg_small_range_decode(&msg, &range); + + sensor_msgs::Range alt_msg; + alt_msg.header.stamp = ros::Time::now(); + alt_msg.max_range = range.max_range; + alt_msg.min_range = range.min_range; + alt_msg.range = range.range; + + switch(range.type) { + case ROSFLIGHT_RANGE_SONAR: + alt_msg.radiation_type = sensor_msgs::Range::ULTRASOUND; + alt_msg.field_of_view = 1.0472; // approx 60 deg + + if (sonar_pub_.getTopic().empty()) + { + sonar_pub_ = nh_.advertise("sonar", 1); + } + sonar_pub_.publish(alt_msg); + break; + case ROSFLIGHT_RANGE_LIDAR: + alt_msg.radiation_type = sensor_msgs::Range::INFRARED; + alt_msg.field_of_view = .0349066; //approx 2 deg + + if (lidar_pub_.getTopic().empty()) + { + lidar_pub_ = nh_.advertise("lidar", 1); + } + lidar_pub_.publish(alt_msg); + break; + default: + break; + } + +} + +void rosflightIO::handle_version_msg(const mavlink_message_t &msg) +{ + version_timer_.stop(); + + mavlink_rosflight_version_t version; + mavlink_msg_rosflight_version_decode(&msg, &version); + + std_msgs::String version_msg; + version_msg.data = version.version; + + if (version_pub_.getTopic().empty()) + { + version_pub_ = nh_.advertise("version", 1, true); + } + version_pub_.publish(version_msg); + + ROS_INFO("Firmware version: %s", version.version); +} + +void rosflightIO::commandCallback(rosflight_msgs::Command::ConstPtr msg) +{ + //! \todo these are hard-coded to match right now; may want to replace with something more robust + OFFBOARD_CONTROL_MODE mode = (OFFBOARD_CONTROL_MODE)msg->mode; + OFFBOARD_CONTROL_IGNORE ignore = (OFFBOARD_CONTROL_IGNORE)msg->ignore; + + float x = msg->x; + float y = msg->y; + float z = msg->z; + float F = msg->F; + + switch (mode) + { + case MODE_PASS_THROUGH: + x = saturate(x, -1.0f, 1.0f); + y = saturate(y, -1.0f, 1.0f); + z = saturate(z, -1.0f, 1.0f); + F = saturate(F, 0.0f, 1.0f); + break; + case MODE_ROLLRATE_PITCHRATE_YAWRATE_THROTTLE: + case MODE_ROLL_PITCH_YAWRATE_THROTTLE: + F = saturate(F, 0.0f, 1.0f); + break; + case MODE_ROLL_PITCH_YAWRATE_ALTITUDE: + break; + } + + mavlink_message_t mavlink_msg; + mavlink_msg_offboard_control_pack(1, 50, &mavlink_msg, mode, ignore, x, y, z, F); + mavrosflight_->comm.send_message(mavlink_msg); +} + +bool rosflightIO::paramGetSrvCallback(rosflight_msgs::ParamGet::Request &req, rosflight_msgs::ParamGet::Response &res) +{ + res.exists = mavrosflight_->param.get_param_value(req.name, &res.value); + return true; +} + +bool rosflightIO::paramSetSrvCallback(rosflight_msgs::ParamSet::Request &req, rosflight_msgs::ParamSet::Response &res) +{ + res.exists = mavrosflight_->param.set_param_value(req.name, req.value); + return true; +} + +bool rosflightIO::paramWriteSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) +{ + res.success = mavrosflight_->param.write_params(); + if (!res.success) + { + res.message = "Request rejected: write already in progress"; + } + + return true; +} + +bool rosflightIO::paramSaveToFileCallback(rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res) +{ + res.success = mavrosflight_->param.save_to_file(req.filename); + return true; +} + +bool rosflightIO::paramLoadFromFileCallback(rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res) +{ + res.success = mavrosflight_->param.load_from_file(req.filename); + return true; +} + +bool rosflightIO::calibrateImuBiasSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) +{ + mavlink_message_t msg; + mavlink_msg_rosflight_cmd_pack(1, 50, &msg, ROSFLIGHT_CMD_ACCEL_CALIBRATION); + mavrosflight_->comm.send_message(msg); + + res.success = true; + return true; +} + +bool rosflightIO::calibrateRCTrimSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) +{ + mavlink_message_t msg; + mavlink_msg_rosflight_cmd_pack(1, 50, &msg, ROSFLIGHT_CMD_RC_CALIBRATION); + mavrosflight_->comm.send_message(msg); + res.success = true; + return true; +} + +void rosflightIO::paramTimerCallback(const ros::TimerEvent &e) +{ + if (mavrosflight_->param.got_all_params()) + { + param_timer_.stop(); + ROS_INFO("Received all parameters"); + } + else + { + mavrosflight_->param.request_params(); + ROS_ERROR("Received %d of %d parameters. Requesting missing parameters...", + mavrosflight_->param.get_params_received(), mavrosflight_->param.get_num_params()); + } +} + +void rosflightIO::versionTimerCallback(const ros::TimerEvent &e) +{ + request_version(); +} + +void rosflightIO::request_version() +{ + mavlink_message_t msg; + mavlink_msg_rosflight_cmd_pack(1, 50, &msg, ROSFLIGHT_CMD_SEND_VERSION); + mavrosflight_->comm.send_message(msg); +} + +void rosflightIO::check_error_code(uint8_t current, uint8_t previous, ROSFLIGHT_ERROR_CODE code, std::string name) +{ + if ((current & code) != (previous & code)) + { + if (current & code) + ROS_ERROR("Autopilot ERROR: %s", name.c_str()); + else + ROS_INFO("Autopilot RECOVERED ERROR: %s", name.c_str()); + } +} + +bool rosflightIO::calibrateAirspeedSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) +{ + mavlink_message_t msg; + mavlink_msg_rosflight_cmd_pack(1, 50, &msg, ROSFLIGHT_CMD_AIRSPEED_CALIBRATION); + mavrosflight_->comm.send_message(msg); + res.success = true; + return true; +} + +bool rosflightIO::calibrateBaroSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) +{ + mavlink_message_t msg; + mavlink_msg_rosflight_cmd_pack(1, 50, &msg, ROSFLIGHT_CMD_BARO_CALIBRATION); + mavrosflight_->comm.send_message(msg); + res.success = true; + return true; +} + +bool rosflightIO::rebootSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) +{ + mavlink_message_t msg; + mavlink_msg_rosflight_cmd_pack(1, 50, &msg, ROSFLIGHT_CMD_REBOOT); + mavrosflight_->comm.send_message(msg); + res.success = true; + return true; +} + +bool rosflightIO::rebootToBootloaderSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) +{ + mavlink_message_t msg; + mavlink_msg_rosflight_cmd_pack(1, 50, &msg, ROSFLIGHT_CMD_REBOOT_TO_BOOTLOADER); + mavrosflight_->comm.send_message(msg); + res.success = true; + return true; +} + +} // namespace rosflight_io diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/rosflight_io_node.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/rosflight_io_node.cpp new file mode 100644 index 0000000..c7c0610 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight/src/rosflight_io_node.cpp @@ -0,0 +1,47 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file rosflight_io_node.cpp + * \author Daniel Koch + * + * Entry point for the mavrosflight_node executable + */ + +#include +#include + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "rosflight_io"); + rosflight_io::rosflightIO rosflight_io; + ros::spin(); +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/CMakeLists.txt new file mode 100644 index 0000000..76ea894 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/CMakeLists.txt @@ -0,0 +1,60 @@ +cmake_minimum_required(VERSION 2.8.3) +project(rosflight_firmware) + +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") + +find_package(catkin REQUIRED COMPONENTS roscpp) +find_package(Boost REQUIRED COMPONENTS system thread) + +set(FIRMWARE_INCLUDE_DIRS + firmware/include/ + firmware/lib/ +) + +catkin_package( + INCLUDE_DIRS include ${FIRMWARE_INCLUDE_DIRS} + LIBRARIES rosflight_firmware rosflight_udp_board + CATKIN_DEPENDS roscpp +) + +include_directories(include) +include_directories(${FIRMWARE_INCLUDE_DIRS}) +include_directories(${Boost_INCLUDE_DIRS}) + +add_library(rosflight_firmware + firmware/src/rosflight.cpp + firmware/src/nanoprintf.cpp + firmware/src/estimator.cpp + firmware/src/mixer.cpp + firmware/src/controller.cpp + firmware/src/param.cpp + firmware/src/state_manager.cpp + firmware/src/rc.cpp + firmware/src/command_manager.cpp + firmware/src/sensors.cpp + firmware/src/mavlink.cpp + + firmware/lib/turbotrig/turbotrig.cpp + firmware/lib/turbotrig/turbovec.cpp +) + +add_library(rosflight_udp_board + src/udp_board.cpp +) +target_link_libraries(rosflight_udp_board + rosflight_firmware + ${catkin_LIBRARIES} + ${Boost_LIBRARIES} +) + +install( + TARGETS rosflight_firmware rosflight_udp_board + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +) + +install( + DIRECTORY include/${PROJECT_NAME}/ ${FIRMWARE_INCLUDE_DIRS} + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" +) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/LICENSE.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/LICENSE.md new file mode 100644 index 0000000..bedaae7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/LICENSE.md @@ -0,0 +1,29 @@ +BSD 3-Clause License + +Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab, Provo UT +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/Makefile b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/Makefile new file mode 100644 index 0000000..5aaef99 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/Makefile @@ -0,0 +1,60 @@ +################################################################################ +# +# Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab +# +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright notice, this +# list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright notice, +# this list of conditions and the following disclaimer in the documentation +# and/or other materials provided with the distribution. +# +# * Neither the name of the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +# DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +# FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +# DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +# SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +# OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +# You probably shouldn't modify anything below here! + +TARGET = rosflight + +# Compile-time options +BOARD ?= naze + +# Debugger options, must be empty or GDB +DEBUG ?= + +# Serial port/device for flashing +SERIAL_DEVICE ?= /dev/ttyUSB0 + +PARALLEL_JOBS ?= 4 + +# Build configuration +BOARD_DIR = boards/$(BOARD) + +.PHONY: all flash clean + + +all: + cd $(BOARD_DIR) && make -j$(PARALLEL_JOBS) DEBUG=$(DEBUG) SERIAL_DEVICE=$(SERIAL_DEVICE) + +clean: + cd $(BOARD_DIR) && make clean + +flash: + cd $(BOARD_DIR) && make flash diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/README.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/README.md new file mode 100644 index 0000000..1f88d2b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/README.md @@ -0,0 +1,59 @@ +# ROSflight +[![Build Status](https://travis-ci.org/rosflight/firmware.svg?branch=master)](https://travis-ci.org/rosflight/firmware) +[![Documentation Status](https://readthedocs.org/projects/rosflight/badge/?version=latest)](http://docs.rosflight.org/en/latest/?badge=latest) + + +This is the firmware required for STM32F10x-based flight controllers (naze32, flip32 etc...) to run ROSflight. ROSflight is a software architecture which uses a simple, inexpensive flight controller in tandem with a much more capable onboard computer running ROS. The onboard computer is given a high-bandwidth connection to the flight controller to access sensor information and perform actuator commands at high rates. This architectures provides direct control of lower-level functions via the embedded processor while also enabling more complicated functionality such as vision processing and optimization via the ROS middleware. + +ROSflight is designed to accomplish the following objectives: + +1. Provide simpler and easier methods to develop and run advanced autopilot code on both multirotor and fixed-wing UAVs without extensive embedded programming. +2. Robust software-in-the-loop (SIL) simulation tools for rapid testing and development of UAV code. +3. The extensive use of peer-reviewed sources for all critical control and estimation algorithms complete with official documentation explaining all critical code. +4. Prioritize high-bandwidth, low-latency communication with an onboard computer running ROS. + +These objectives will allow researchers to more easily develop, test and field UAV code by prioritizing offboard control, good documentation and robust development tools. + +## How to Use ## + +Documentation is located at http://docs.rosflight.org. + +## Implementation Details ## + +#### Communication +ROSflight uses MAVlink to communicate over a USB cable. MAVlink has primarily been used in both the Ardupilot and PX4 versions of the PixHawk. More information on MAVlink can be found [here](http://qgroundcontrol.org/mavlink/start "QgroundControl/mavlink"). + +#### Sensors +ROSflight provides access to the onboard 6-axis gyroscope and accelerometer at up to 1000Hz. IMU measurements are very carefully time-stamped and these stamps are accurate to within a microsecond. Using MAVlink time synchronization, this stamp is relayed to ROS, and is also accurate to within a microsecond. However, depending on the order in which measurements are sent over the serial line, IMU messages may not be relayed at a constant rate, which means the inter-arrival time between messages may vary over time on the onboard computer. However, the time stamps in the IMU message header are accurate and should be trusted more than the inter-arrival time. + +The MB1242 I2C sonar and MS4252 I2C differential pressure sensor are also currently supported, as wel as the onboard magnetometer and barometer. These additional sensors have been tested at rates up to 50 Hz without any performance degredation. GPS is currently not supported on the flight control board, and should instead be connected to the onboard computer directly using an FTDI cable. Other sensors have not been directly implemented, but could be given a little effort. Contact us via an issue if the sensor you need is not available. + +#### Estimation +Onboard estimation is performed using a quaternion-based Mahoney Filter, with the addition of a quadratic approximation of angular rates, and the use of a matrix exponential during the propagation step. Details can be found in the documentation (reports/estimator.tex) + +#### Control +Control is performed using a standard PID control scheme with default gains found in param.c. Control is performed in three modes: + +1. Pass-Through - The pass-through mode is meant primarily for operating fixed-wing UAVs, and maps the four input channels directly to actuator outputs. + +2. Rate - Rate mode controls the angular rate of the 3 body-fixed axes, and overall throttle response. This is much like "Acro" mode of other multirotor autopilots. This mode is primarily meant for multirotor UAVs. + +3. Angle - Angle mode is another multirotor UAV control scheme in which the angle of the body-fixed x and y axes are controlled, while the z axis is controlled to a specific angular rate, and overall throttle is directly passed through. This is nearly identical to other "Angle" modes of other multirotor autopilots. + +#### Process Priority +Tasks are prioritized according to the following scheme: + +1. Real-time hardware-specific tasks (PWM, serial read/write, I2C communication). +2. Time-Stamping of sensor measurements and commands, time synchronization with onboard computer. +3. Estimation. +4. Control. +5. Safety Pilot Intervention and control. +6. Communication of sensor information with onboard computer. +7. Registering commands from onboard computer. + +Control and estimation are performed on the heartbeat of an IMU update (1000Hz), and it takes approximately 840us from this update to when control is written to motors. Most of this (590us) is taken up in I2C communication, while the rest is actual estimation and control. Serial write and read tasks are performed asynchronously by hardware units and consist of less than 1% of total CPU time. A detailed analysis of timing has been performed, and a summary of each function can be found in main.c. + +## FAQ + +##### 1. My flight controller doesn't seem to be responding - I don't get any IMU messages +This is likely to be because the BOARD_REV parameter is incorrect. The estimation and control is run on the heartbeat of the accelerometer interrupt, which is attached to different pins on different revisions of the naze32. diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/Makefile b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/Makefile new file mode 100644 index 0000000..a9a70f7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/Makefile @@ -0,0 +1,231 @@ +############################################################################### +# Generic Makefile Template for C/C++ for use with STM32 Microcontrollers +# +# Copyright (c) 2016 - James Jackson +# All rights reserved. + +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# * Neither the name of the nor the +# names of its contributors may be used to endorse or promote products +# derived from this software without specific prior written permission. + +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +# ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +# WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +# DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +# DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +# (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +# ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +# SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +TARGET ?= rosflight + +DEBUG ?= GDB + +SERIAL_DEVICE ?= /dev/ttyUSB0 + +################################# +# GNU ARM Embedded Toolchain +################################# +CC=arm-none-eabi-gcc +CXX=arm-none-eabi-g++ +LD=arm-none-eabi-ld +AR=arm-none-eabi-ar +AS=arm-none-eabi-as +CP=arm-none-eabi-objcopy +OD=arm-none-eabi-objdump +NM=arm-none-eabi-nm +SIZE=arm-none-eabi-size +A2L=arm-none-eabi-addr2line + +################################# +# Working directories +################################# +ROOT = $(dir $(lastword $(MAKEFILE_LIST))) +BOARD_DIR = . +ROSFLIGHT_DIR = ../.. +TURBOTRIG_DIR = $(ROSFLIGHT_DIR)/lib/turbotrig +BREEZY_DIR = lib/breezystm32 +CMSIS_DIR = $(BREEZY_DIR)/lib/CMSIS +STDPERIPH_DIR = $(BREEZY_DIR)/lib/STM32F10x_StdPeriph_Driver +OBJECT_DIR = $(ROOT)/build +BIN_DIR = $(ROOT)/build + + +################################# +# Source Files +################################# + +# board-specific source files +VPATH := $(BOARD_DIR) +BOARD_C_SRC = flash.c +BOARD_CXX_SRC = naze32.cpp \ + main.cpp + +# ROSflight source files +VPATH := $(VPATH):$(ROSFLIGHT_DIR) +ROSFLIGHT_SRC = rosflight.cpp \ + param.cpp \ + sensors.cpp \ + state_manager.cpp \ + estimator.cpp \ + mavlink.cpp \ + controller.cpp \ + command_manager.cpp \ + rc.cpp \ + mixer.cpp + +# Math Source Files +VPATH := $(VPATH):$(TURBOTRIG_DIR) +MATH_SRC = turbotrig.cpp \ + turbovec.cpp + + +# Hardware Driver Source Files +VPATH := $(VPATH):$(BREEZY_DIR) +BREEZY_SRC = drv_gpio.c \ + drv_i2c.c \ + drv_adc.c \ + drv_spi.c \ + drv_pwm.c \ + drv_system.c \ + drv_serial.c \ + drv_uart.c \ + drv_timer.c \ + drv_mpu6050.c \ + drv_ms4525.c \ + drv_mb1242.c \ + drv_ms5611.c \ + drv_hmc5883l.c \ + startup_stm32f10x_md_gcc.S + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + + +# Compile a list of C source files +CSOURCES = $(CMSIS_SRC) \ + $(STDPERIPH_SRC) \ + $(addprefix $(BREEZY_DIR)/, $(BREEZY_SRC)) \ + $(addprefix $(BOARD_DIR)/, $(BOARD_C_SRC)) \ + $(ROSFLIGHT_DIR)/src/nanoprintf.c + +# Compile a list of C++ Source Files +CXXSOURCES = $(addprefix $(ROSFLIGHT_DIR)/src/, $(ROSFLIGHT_SRC)) \ + $(addprefix $(MAVLINK_DIR)/, $(MAVLINK_SRC)) \ + $(addprefix $(BOARD_DIR)/, $(BOARD_CXX_SRC)) \ + $(addprefix $(TURBOTRIG_DIR)/, $(MATH_SRC)) \ + + +# Set up Include Directoreis +INCLUDE_DIRS = $(BREEZY_DIR) \ + $(ROSFLIGHT_DIR)/include \ + $(ROSFLIGHT_DIR)/lib \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x + +################################# +# VERSION CONTROL +################################# +GIT_VERSION_HASH := $(shell git rev-parse --short=8 HEAD) +GIT_VERSION_STRING := $(shell git describe --tags --abbrev=8 --always --dirty --long) +GIT_VARS := -DGIT_VERSION_HASH=0x$(GIT_VERSION_HASH) -DGIT_VERSION_STRING=\"$(GIT_VERSION_STRING)\" + + +################################# +# Object List +################################# +OBJECTS=$(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(ASOURCES)))) +OBJECTS+=$(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(CSOURCES)))) +OBJECTS+=$(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(CXXSOURCES)))) +LDSCRIPT=$(BREEZY_DIR)/stm32_flash.ld + +#$(info $$OBJECTS is [${OBJECTS}]) + +################################# +# Target Output Files +################################# +TARGET_ELF=$(BIN_DIR)/$(TARGET).elf +TARGET_HEX=$(BIN_DIR)/$(TARGET).hex + +################################# +# Debug Config +################################# +ifeq ($(DEBUG), GDB) +DEBUG_FLAGS = -ggdb +OPTIMIZE = -Og +$(info ***** Building with Debug Symbols *****) +else +OPTIMIZE = -Os +COMPILE_FLAGS = -flto +LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) +endif + +################################# +# VERSION CONTROL +################################# +GIT_VERSION_HASH := $(shell git rev-parse --short=8 HEAD) +GIT_VERSION_STRING := $(shell git describe --tags --abbrev=8 --always --dirty --long) +GIT_VARS := -DGIT_VERSION_HASH=0x$(GIT_VERSION_HASH) -DGIT_VERSION_STRING=\"$(GIT_VERSION_STRING)\" + +################################# +# Flags +################################# +COMPILE_FLAGS+=-ffunction-sections -fdata-sections -fno-exceptions +MCFLAGS=-mcpu=cortex-m3 -mthumb +DEFS=-DTARGET_STM32F10X_MD -D__CORTEX_M4 -D__FPU_PRESENT -DWORDS_STACK_SIZE=200 -DSTM32F10X_MD -DUSE_STDPERIPH_DRIVER $(GIT_VARS) +CFLAGS=-c $(MCFLAGS) $(DEFS) $(OPTIMIZE) $(DEBUG_FLAGS) $(COMPILE_FLAGS) $(addprefix -I,$(INCLUDE_DIRS)) -std=c99 +CXXFLAGS=-c $(MCFLAGS) $(DEFS) $(OPTIMIZE) $(DEBUG_FLAGS) $(COMPILE_FLAGS) $(addprefix -I,$(INCLUDE_DIRS)) -std=c++11 -U__STRICT_ANSI__ -fno-rtti +LDFLAGS =-T $(LDSCRIPT) $(MCFLAGS) -lm -lc --specs=nano.specs --specs=rdimon.specs $(ARCH_FLAGS) $(LTO_FLAGS) $(DEBUG_FLAGS) -static -Wl,-gc-sections + +################################# +# Build +################################# +$(TARGET_HEX): $(TARGET_ELF) + $(CP) -O ihex --set-start 0x8000000 $< $@ + +$(TARGET_ELF): $(OBJECTS) + $(CXX) -o $@ $^ $(LDFLAGS) + $(SIZE) $(TARGET_ELF) + +$(OBJECT_DIR)/$(TARGET)/%.o: %.cpp + @mkdir -p $(dir $@) + @echo %% $(notdir $<) + @$(CXX) -c -o $@ $(CXXFLAGS) $< + +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + @mkdir -p $(dir $@) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + +$(OBJECT_DIR)/$(TARGET)/%.o: %.s + @mkdir -p $(dir $@) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + + +################################# +# Recipes +################################# +.PHONY: all flash clean + +clean: + rm -f $(OBJECTS) $(TARGET_ELF) $(TARGET_HEX) $(BIN_DIR)/output.map + +flash: $(TARGET_HEX) + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 921600 $(SERIAL_DEVICE) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/flash.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/flash.c new file mode 100644 index 0000000..1bf4565 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/flash.c @@ -0,0 +1,86 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ +#include + +#include + +#include "flash.h" + +void initEEPROM(void) +{ + // make sure (at compile time) that config struct doesn't overflow allocated flash pages + // ct_assert(sizeof(_params) < CONFIG_SIZE); +} + +static uint8_t compute_checksum(const void * addr, size_t len) +{ + const uint8_t *p; + uint8_t chk = 0; + + for (p = (const uint8_t *)addr; p < ((const uint8_t *)addr + len); p++) + chk ^= *p; + + return chk; +} + +bool readEEPROM(void * dest, size_t len) +{ + memcpy(dest, (char *)FLASH_WRITE_ADDR, len); + return true; +} + +bool writeEEPROM(const void * src, size_t len) +{ + FLASH_Status status; + + // write it + FLASH_Unlock(); + for (unsigned int tries = 3; tries; tries--) + { + FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR); + + for(int i = 0; i < NUM_PAGES; i++) + status = FLASH_ErasePage(FLASH_WRITE_ADDR + i * FLASH_PAGE_SIZE); + + for (unsigned int i = 0; i < len && status == FLASH_COMPLETE; i += 4) + status = FLASH_ProgramWord(FLASH_WRITE_ADDR + i, *(uint32_t *)((char *)src + i)); + + if(status == FLASH_COMPLETE) + break; + } + FLASH_Lock(); + + // Flash write failed - just die now + if (status != FLASH_COMPLETE || compute_checksum(src, len) != compute_checksum((uint32_t*)FLASH_WRITE_ADDR, len)) + return false; + + return true; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/flash.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/flash.h new file mode 100644 index 0000000..84ce771 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/flash.h @@ -0,0 +1,79 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ +#pragma once + +#include +#include +#include + +#include + +// #define ASSERT_CONCAT_(a, b) a##b +// #define ASSERT_CONCAT(a, b) ASSERT_CONCAT_(a, b) +// #define ct_assert(e) enum { ASSERT_CONCAT(assert_line_, __LINE__) = 1/(!!(e)) } + +// define this symbol to increase or decrease flash size. not rely on flash_size_register. +#ifndef FLASH_PAGE_COUNT +#define FLASH_PAGE_COUNT 128 +#endif + +#define FLASH_PAGE_SIZE ((uint16_t)0x400) +#define NUM_PAGES 3 +// if sizeof(_params) is over this number, compile-time error will occur. so, need to add another page to config data. +// TODO compile time check is currently disabled +#define CONFIG_SIZE (FLASH_PAGE_SIZE * NUM_PAGES) + +// static const uint8_t EEPROM_CONF_VERSION = 76; +//static uint32_t enabledSensors = 0; +//static void resetConf(void); +static const uint32_t FLASH_WRITE_ADDR = 0x08000000 + (FLASH_PAGE_SIZE * (FLASH_PAGE_COUNT - (CONFIG_SIZE / 1024))); + + +/** + * @brief Initialize Flash + */ +void initEEPROM(void); + +/** + * @brief Read data from Flash + * @param dest The memory address to copy the data to + * @param len The number of bytes to copy + * @returns true if the read was successful, false otherwise + */ +bool readEEPROM(void * dest, size_t len); + +/** + * @brief Write data to Flash + * @param src The memory address to copy data from + * @param len The number of bytes to copy + * @returns true if the write was successful, false otherwise + */ +bool writeEEPROM(const void * src, size_t len); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/LICENSE.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/LICENSE.md new file mode 100644 index 0000000..94a9ed0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/LICENSE.md @@ -0,0 +1,674 @@ + GNU GENERAL PUBLIC LICENSE + Version 3, 29 June 2007 + + Copyright (C) 2007 Free Software Foundation, Inc. + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + Preamble + + The GNU General Public License is a free, copyleft license for +software and other kinds of works. + + The licenses for most software and other practical works are designed +to take away your freedom to share and change the works. By contrast, +the GNU General Public License is intended to guarantee your freedom to +share and change all versions of a program--to make sure it remains free +software for all its users. We, the Free Software Foundation, use the +GNU General Public License for most of our software; it applies also to +any other work released this way by its authors. You can apply it to +your programs, too. + + When we speak of free software, we are referring to freedom, not +price. Our General Public Licenses are designed to make sure that you +have the freedom to distribute copies of free software (and charge for +them if you wish), that you receive source code or can get it if you +want it, that you can change the software or use pieces of it in new +free programs, and that you know you can do these things. + + To protect your rights, we need to prevent others from denying you +these rights or asking you to surrender the rights. Therefore, you have +certain responsibilities if you distribute copies of the software, or if +you modify it: responsibilities to respect the freedom of others. + + For example, if you distribute copies of such a program, whether +gratis or for a fee, you must pass on to the recipients the same +freedoms that you received. You must make sure that they, too, receive +or can get the source code. And you must show them these terms so they +know their rights. + + Developers that use the GNU GPL protect your rights with two steps: +(1) assert copyright on the software, and (2) offer you this License +giving you legal permission to copy, distribute and/or modify it. + + For the developers' and authors' protection, the GPL clearly explains +that there is no warranty for this free software. For both users' and +authors' sake, the GPL requires that modified versions be marked as +changed, so that their problems will not be attributed erroneously to +authors of previous versions. + + Some devices are designed to deny users access to install or run +modified versions of the software inside them, although the manufacturer +can do so. This is fundamentally incompatible with the aim of +protecting users' freedom to change the software. The systematic +pattern of such abuse occurs in the area of products for individuals to +use, which is precisely where it is most unacceptable. Therefore, we +have designed this version of the GPL to prohibit the practice for those +products. If such problems arise substantially in other domains, we +stand ready to extend this provision to those domains in future versions +of the GPL, as needed to protect the freedom of users. + + Finally, every program is threatened constantly by software patents. +States should not allow patents to restrict development and use of +software on general-purpose computers, but in those that do, we wish to +avoid the special danger that patents applied to a free program could +make it effectively proprietary. To prevent this, the GPL assures that +patents cannot be used to render the program non-free. + + The precise terms and conditions for copying, distribution and +modification follow. + + TERMS AND CONDITIONS + + 0. Definitions. + + "This License" refers to version 3 of the GNU General Public License. + + "Copyright" also means copyright-like laws that apply to other kinds of +works, such as semiconductor masks. + + "The Program" refers to any copyrightable work licensed under this +License. Each licensee is addressed as "you". "Licensees" and +"recipients" may be individuals or organizations. + + To "modify" a work means to copy from or adapt all or part of the work +in a fashion requiring copyright permission, other than the making of an +exact copy. The resulting work is called a "modified version" of the +earlier work or a work "based on" the earlier work. + + A "covered work" means either the unmodified Program or a work based +on the Program. + + To "propagate" a work means to do anything with it that, without +permission, would make you directly or secondarily liable for +infringement under applicable copyright law, except executing it on a +computer or modifying a private copy. Propagation includes copying, +distribution (with or without modification), making available to the +public, and in some countries other activities as well. + + To "convey" a work means any kind of propagation that enables other +parties to make or receive copies. Mere interaction with a user through +a computer network, with no transfer of a copy, is not conveying. + + An interactive user interface displays "Appropriate Legal Notices" +to the extent that it includes a convenient and prominently visible +feature that (1) displays an appropriate copyright notice, and (2) +tells the user that there is no warranty for the work (except to the +extent that warranties are provided), that licensees may convey the +work under this License, and how to view a copy of this License. If +the interface presents a list of user commands or options, such as a +menu, a prominent item in the list meets this criterion. + + 1. Source Code. + + The "source code" for a work means the preferred form of the work +for making modifications to it. "Object code" means any non-source +form of a work. + + A "Standard Interface" means an interface that either is an official +standard defined by a recognized standards body, or, in the case of +interfaces specified for a particular programming language, one that +is widely used among developers working in that language. + + The "System Libraries" of an executable work include anything, other +than the work as a whole, that (a) is included in the normal form of +packaging a Major Component, but which is not part of that Major +Component, and (b) serves only to enable use of the work with that +Major Component, or to implement a Standard Interface for which an +implementation is available to the public in source code form. A +"Major Component", in this context, means a major essential component +(kernel, window system, and so on) of the specific operating system +(if any) on which the executable work runs, or a compiler used to +produce the work, or an object code interpreter used to run it. + + The "Corresponding Source" for a work in object code form means all +the source code needed to generate, install, and (for an executable +work) run the object code and to modify the work, including scripts to +control those activities. However, it does not include the work's +System Libraries, or general-purpose tools or generally available free +programs which are used unmodified in performing those activities but +which are not part of the work. For example, Corresponding Source +includes interface definition files associated with source files for +the work, and the source code for shared libraries and dynamically +linked subprograms that the work is specifically designed to require, +such as by intimate data communication or control flow between those +subprograms and other parts of the work. + + The Corresponding Source need not include anything that users +can regenerate automatically from other parts of the Corresponding +Source. + + The Corresponding Source for a work in source code form is that +same work. + + 2. Basic Permissions. + + All rights granted under this License are granted for the term of +copyright on the Program, and are irrevocable provided the stated +conditions are met. This License explicitly affirms your unlimited +permission to run the unmodified Program. The output from running a +covered work is covered by this License only if the output, given its +content, constitutes a covered work. This License acknowledges your +rights of fair use or other equivalent, as provided by copyright law. + + You may make, run and propagate covered works that you do not +convey, without conditions so long as your license otherwise remains +in force. You may convey covered works to others for the sole purpose +of having them make modifications exclusively for you, or provide you +with facilities for running those works, provided that you comply with +the terms of this License in conveying all material for which you do +not control copyright. Those thus making or running the covered works +for you must do so exclusively on your behalf, under your direction +and control, on terms that prohibit them from making any copies of +your copyrighted material outside their relationship with you. + + Conveying under any other circumstances is permitted solely under +the conditions stated below. Sublicensing is not allowed; section 10 +makes it unnecessary. + + 3. Protecting Users' Legal Rights From Anti-Circumvention Law. + + No covered work shall be deemed part of an effective technological +measure under any applicable law fulfilling obligations under article +11 of the WIPO copyright treaty adopted on 20 December 1996, or +similar laws prohibiting or restricting circumvention of such +measures. + + When you convey a covered work, you waive any legal power to forbid +circumvention of technological measures to the extent such circumvention +is effected by exercising rights under this License with respect to +the covered work, and you disclaim any intention to limit operation or +modification of the work as a means of enforcing, against the work's +users, your or third parties' legal rights to forbid circumvention of +technological measures. + + 4. Conveying Verbatim Copies. + + You may convey verbatim copies of the Program's source code as you +receive it, in any medium, provided that you conspicuously and +appropriately publish on each copy an appropriate copyright notice; +keep intact all notices stating that this License and any +non-permissive terms added in accord with section 7 apply to the code; +keep intact all notices of the absence of any warranty; and give all +recipients a copy of this License along with the Program. + + You may charge any price or no price for each copy that you convey, +and you may offer support or warranty protection for a fee. + + 5. Conveying Modified Source Versions. + + You may convey a work based on the Program, or the modifications to +produce it from the Program, in the form of source code under the +terms of section 4, provided that you also meet all of these conditions: + + a) The work must carry prominent notices stating that you modified + it, and giving a relevant date. + + b) The work must carry prominent notices stating that it is + released under this License and any conditions added under section + 7. This requirement modifies the requirement in section 4 to + "keep intact all notices". + + c) You must license the entire work, as a whole, under this + License to anyone who comes into possession of a copy. This + License will therefore apply, along with any applicable section 7 + additional terms, to the whole of the work, and all its parts, + regardless of how they are packaged. This License gives no + permission to license the work in any other way, but it does not + invalidate such permission if you have separately received it. + + d) If the work has interactive user interfaces, each must display + Appropriate Legal Notices; however, if the Program has interactive + interfaces that do not display Appropriate Legal Notices, your + work need not make them do so. + + A compilation of a covered work with other separate and independent +works, which are not by their nature extensions of the covered work, +and which are not combined with it such as to form a larger program, +in or on a volume of a storage or distribution medium, is called an +"aggregate" if the compilation and its resulting copyright are not +used to limit the access or legal rights of the compilation's users +beyond what the individual works permit. Inclusion of a covered work +in an aggregate does not cause this License to apply to the other +parts of the aggregate. + + 6. Conveying Non-Source Forms. + + You may convey a covered work in object code form under the terms +of sections 4 and 5, provided that you also convey the +machine-readable Corresponding Source under the terms of this License, +in one of these ways: + + a) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by the + Corresponding Source fixed on a durable physical medium + customarily used for software interchange. + + b) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by a + written offer, valid for at least three years and valid for as + long as you offer spare parts or customer support for that product + model, to give anyone who possesses the object code either (1) a + copy of the Corresponding Source for all the software in the + product that is covered by this License, on a durable physical + medium customarily used for software interchange, for a price no + more than your reasonable cost of physically performing this + conveying of source, or (2) access to copy the + Corresponding Source from a network server at no charge. + + c) Convey individual copies of the object code with a copy of the + written offer to provide the Corresponding Source. This + alternative is allowed only occasionally and noncommercially, and + only if you received the object code with such an offer, in accord + with subsection 6b. + + d) Convey the object code by offering access from a designated + place (gratis or for a charge), and offer equivalent access to the + Corresponding Source in the same way through the same place at no + further charge. You need not require recipients to copy the + Corresponding Source along with the object code. If the place to + copy the object code is a network server, the Corresponding Source + may be on a different server (operated by you or a third party) + that supports equivalent copying facilities, provided you maintain + clear directions next to the object code saying where to find the + Corresponding Source. Regardless of what server hosts the + Corresponding Source, you remain obligated to ensure that it is + available for as long as needed to satisfy these requirements. + + e) Convey the object code using peer-to-peer transmission, provided + you inform other peers where the object code and Corresponding + Source of the work are being offered to the general public at no + charge under subsection 6d. + + A separable portion of the object code, whose source code is excluded +from the Corresponding Source as a System Library, need not be +included in conveying the object code work. + + A "User Product" is either (1) a "consumer product", which means any +tangible personal property which is normally used for personal, family, +or household purposes, or (2) anything designed or sold for incorporation +into a dwelling. In determining whether a product is a consumer product, +doubtful cases shall be resolved in favor of coverage. For a particular +product received by a particular user, "normally used" refers to a +typical or common use of that class of product, regardless of the status +of the particular user or of the way in which the particular user +actually uses, or expects or is expected to use, the product. A product +is a consumer product regardless of whether the product has substantial +commercial, industrial or non-consumer uses, unless such uses represent +the only significant mode of use of the product. + + "Installation Information" for a User Product means any methods, +procedures, authorization keys, or other information required to install +and execute modified versions of a covered work in that User Product from +a modified version of its Corresponding Source. The information must +suffice to ensure that the continued functioning of the modified object +code is in no case prevented or interfered with solely because +modification has been made. + + If you convey an object code work under this section in, or with, or +specifically for use in, a User Product, and the conveying occurs as +part of a transaction in which the right of possession and use of the +User Product is transferred to the recipient in perpetuity or for a +fixed term (regardless of how the transaction is characterized), the +Corresponding Source conveyed under this section must be accompanied +by the Installation Information. But this requirement does not apply +if neither you nor any third party retains the ability to install +modified object code on the User Product (for example, the work has +been installed in ROM). + + The requirement to provide Installation Information does not include a +requirement to continue to provide support service, warranty, or updates +for a work that has been modified or installed by the recipient, or for +the User Product in which it has been modified or installed. Access to a +network may be denied when the modification itself materially and +adversely affects the operation of the network or violates the rules and +protocols for communication across the network. + + Corresponding Source conveyed, and Installation Information provided, +in accord with this section must be in a format that is publicly +documented (and with an implementation available to the public in +source code form), and must require no special password or key for +unpacking, reading or copying. + + 7. Additional Terms. + + "Additional permissions" are terms that supplement the terms of this +License by making exceptions from one or more of its conditions. +Additional permissions that are applicable to the entire Program shall +be treated as though they were included in this License, to the extent +that they are valid under applicable law. If additional permissions +apply only to part of the Program, that part may be used separately +under those permissions, but the entire Program remains governed by +this License without regard to the additional permissions. + + When you convey a copy of a covered work, you may at your option +remove any additional permissions from that copy, or from any part of +it. (Additional permissions may be written to require their own +removal in certain cases when you modify the work.) You may place +additional permissions on material, added by you to a covered work, +for which you have or can give appropriate copyright permission. + + Notwithstanding any other provision of this License, for material you +add to a covered work, you may (if authorized by the copyright holders of +that material) supplement the terms of this License with terms: + + a) Disclaiming warranty or limiting liability differently from the + terms of sections 15 and 16 of this License; or + + b) Requiring preservation of specified reasonable legal notices or + author attributions in that material or in the Appropriate Legal + Notices displayed by works containing it; or + + c) Prohibiting misrepresentation of the origin of that material, or + requiring that modified versions of such material be marked in + reasonable ways as different from the original version; or + + d) Limiting the use for publicity purposes of names of licensors or + authors of the material; or + + e) Declining to grant rights under trademark law for use of some + trade names, trademarks, or service marks; or + + f) Requiring indemnification of licensors and authors of that + material by anyone who conveys the material (or modified versions of + it) with contractual assumptions of liability to the recipient, for + any liability that these contractual assumptions directly impose on + those licensors and authors. + + All other non-permissive additional terms are considered "further +restrictions" within the meaning of section 10. If the Program as you +received it, or any part of it, contains a notice stating that it is +governed by this License along with a term that is a further +restriction, you may remove that term. If a license document contains +a further restriction but permits relicensing or conveying under this +License, you may add to a covered work material governed by the terms +of that license document, provided that the further restriction does +not survive such relicensing or conveying. + + If you add terms to a covered work in accord with this section, you +must place, in the relevant source files, a statement of the +additional terms that apply to those files, or a notice indicating +where to find the applicable terms. + + Additional terms, permissive or non-permissive, may be stated in the +form of a separately written license, or stated as exceptions; +the above requirements apply either way. + + 8. Termination. + + You may not propagate or modify a covered work except as expressly +provided under this License. Any attempt otherwise to propagate or +modify it is void, and will automatically terminate your rights under +this License (including any patent licenses granted under the third +paragraph of section 11). + + However, if you cease all violation of this License, then your +license from a particular copyright holder is reinstated (a) +provisionally, unless and until the copyright holder explicitly and +finally terminates your license, and (b) permanently, if the copyright +holder fails to notify you of the violation by some reasonable means +prior to 60 days after the cessation. + + Moreover, your license from a particular copyright holder is +reinstated permanently if the copyright holder notifies you of the +violation by some reasonable means, this is the first time you have +received notice of violation of this License (for any work) from that +copyright holder, and you cure the violation prior to 30 days after +your receipt of the notice. + + Termination of your rights under this section does not terminate the +licenses of parties who have received copies or rights from you under +this License. If your rights have been terminated and not permanently +reinstated, you do not qualify to receive new licenses for the same +material under section 10. + + 9. Acceptance Not Required for Having Copies. + + You are not required to accept this License in order to receive or +run a copy of the Program. Ancillary propagation of a covered work +occurring solely as a consequence of using peer-to-peer transmission +to receive a copy likewise does not require acceptance. However, +nothing other than this License grants you permission to propagate or +modify any covered work. These actions infringe copyright if you do +not accept this License. Therefore, by modifying or propagating a +covered work, you indicate your acceptance of this License to do so. + + 10. Automatic Licensing of Downstream Recipients. + + Each time you convey a covered work, the recipient automatically +receives a license from the original licensors, to run, modify and +propagate that work, subject to this License. You are not responsible +for enforcing compliance by third parties with this License. + + An "entity transaction" is a transaction transferring control of an +organization, or substantially all assets of one, or subdividing an +organization, or merging organizations. If propagation of a covered +work results from an entity transaction, each party to that +transaction who receives a copy of the work also receives whatever +licenses to the work the party's predecessor in interest had or could +give under the previous paragraph, plus a right to possession of the +Corresponding Source of the work from the predecessor in interest, if +the predecessor has it or can get it with reasonable efforts. + + You may not impose any further restrictions on the exercise of the +rights granted or affirmed under this License. For example, you may +not impose a license fee, royalty, or other charge for exercise of +rights granted under this License, and you may not initiate litigation +(including a cross-claim or counterclaim in a lawsuit) alleging that +any patent claim is infringed by making, using, selling, offering for +sale, or importing the Program or any portion of it. + + 11. Patents. + + A "contributor" is a copyright holder who authorizes use under this +License of the Program or a work on which the Program is based. The +work thus licensed is called the contributor's "contributor version". + + A contributor's "essential patent claims" are all patent claims +owned or controlled by the contributor, whether already acquired or +hereafter acquired, that would be infringed by some manner, permitted +by this License, of making, using, or selling its contributor version, +but do not include claims that would be infringed only as a +consequence of further modification of the contributor version. For +purposes of this definition, "control" includes the right to grant +patent sublicenses in a manner consistent with the requirements of +this License. + + Each contributor grants you a non-exclusive, worldwide, royalty-free +patent license under the contributor's essential patent claims, to +make, use, sell, offer for sale, import and otherwise run, modify and +propagate the contents of its contributor version. + + In the following three paragraphs, a "patent license" is any express +agreement or commitment, however denominated, not to enforce a patent +(such as an express permission to practice a patent or covenant not to +sue for patent infringement). To "grant" such a patent license to a +party means to make such an agreement or commitment not to enforce a +patent against the party. + + If you convey a covered work, knowingly relying on a patent license, +and the Corresponding Source of the work is not available for anyone +to copy, free of charge and under the terms of this License, through a +publicly available network server or other readily accessible means, +then you must either (1) cause the Corresponding Source to be so +available, or (2) arrange to deprive yourself of the benefit of the +patent license for this particular work, or (3) arrange, in a manner +consistent with the requirements of this License, to extend the patent +license to downstream recipients. "Knowingly relying" means you have +actual knowledge that, but for the patent license, your conveying the +covered work in a country, or your recipient's use of the covered work +in a country, would infringe one or more identifiable patents in that +country that you have reason to believe are valid. + + If, pursuant to or in connection with a single transaction or +arrangement, you convey, or propagate by procuring conveyance of, a +covered work, and grant a patent license to some of the parties +receiving the covered work authorizing them to use, propagate, modify +or convey a specific copy of the covered work, then the patent license +you grant is automatically extended to all recipients of the covered +work and works based on it. + + A patent license is "discriminatory" if it does not include within +the scope of its coverage, prohibits the exercise of, or is +conditioned on the non-exercise of one or more of the rights that are +specifically granted under this License. You may not convey a covered +work if you are a party to an arrangement with a third party that is +in the business of distributing software, under which you make payment +to the third party based on the extent of your activity of conveying +the work, and under which the third party grants, to any of the +parties who would receive the covered work from you, a discriminatory +patent license (a) in connection with copies of the covered work +conveyed by you (or copies made from those copies), or (b) primarily +for and in connection with specific products or compilations that +contain the covered work, unless you entered into that arrangement, +or that patent license was granted, prior to 28 March 2007. + + Nothing in this License shall be construed as excluding or limiting +any implied license or other defenses to infringement that may +otherwise be available to you under applicable patent law. + + 12. No Surrender of Others' Freedom. + + If conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot convey a +covered work so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you may +not convey it at all. For example, if you agree to terms that obligate you +to collect a royalty for further conveying from those to whom you convey +the Program, the only way you could satisfy both those terms and this +License would be to refrain entirely from conveying the Program. + + 13. Use with the GNU Affero General Public License. + + Notwithstanding any other provision of this License, you have +permission to link or combine any covered work with a work licensed +under version 3 of the GNU Affero General Public License into a single +combined work, and to convey the resulting work. The terms of this +License will continue to apply to the part which is the covered work, +but the special requirements of the GNU Affero General Public License, +section 13, concerning interaction through a network will apply to the +combination as such. + + 14. Revised Versions of this License. + + The Free Software Foundation may publish revised and/or new versions of +the GNU General Public License from time to time. Such new versions will +be similar in spirit to the present version, but may differ in detail to +address new problems or concerns. + + Each version is given a distinguishing version number. If the +Program specifies that a certain numbered version of the GNU General +Public License "or any later version" applies to it, you have the +option of following the terms and conditions either of that numbered +version or of any later version published by the Free Software +Foundation. If the Program does not specify a version number of the +GNU General Public License, you may choose any version ever published +by the Free Software Foundation. + + If the Program specifies that a proxy can decide which future +versions of the GNU General Public License can be used, that proxy's +public statement of acceptance of a version permanently authorizes you +to choose that version for the Program. + + Later license versions may give you additional or different +permissions. However, no additional obligations are imposed on any +author or copyright holder as a result of your choosing to follow a +later version. + + 15. Disclaimer of Warranty. + + THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY +APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT +HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY +OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, +THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM +IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF +ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. Limitation of Liability. + + IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING +WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS +THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY +GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE +USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF +DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD +PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), +EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF +SUCH DAMAGES. + + 17. Interpretation of Sections 15 and 16. + + If the disclaimer of warranty and limitation of liability provided +above cannot be given local legal effect according to their terms, +reviewing courts shall apply local law that most closely approximates +an absolute waiver of all civil liability in connection with the +Program, unless a warranty or assumption of liability accompanies a +copy of the Program in return for a fee. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Programs + + If you develop a new program, and you want it to be of the greatest +possible use to the public, the best way to achieve this is to make it +free software which everyone can redistribute and change under these terms. + + To do so, attach the following notices to the program. It is safest +to attach them to the start of each source file to most effectively +state the exclusion of warranty; and each file should have at least +the "copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + +Also add information on how to contact you by electronic and paper mail. + + If the program does terminal interaction, make it output a short +notice like this when it starts in an interactive mode: + + Copyright (C) + This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. + This is free software, and you are welcome to redistribute it + under certain conditions; type `show c' for details. + +The hypothetical commands `show w' and `show c' should show the appropriate +parts of the General Public License. Of course, your program's commands +might be different; for a GUI interface, you would use an "about box". + + You should also get your employer (if you work as a programmer) or school, +if any, to sign a "copyright disclaimer" for the program, if necessary. +For more information on this, and how to apply and follow the GNU GPL, see +. + + The GNU General Public License does not permit incorporating your program +into proprietary programs. If your program is a subroutine library, you +may consider it more useful to permit linking proprietary applications with +the library. If this is what you want to do, use the GNU Lesser General +Public License instead of this License. But first, please read +. diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/README.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/README.md new file mode 100644 index 0000000..033a3b9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/README.md @@ -0,0 +1,52 @@ +# BreezySTM32: A simple Arduino-like API for developing firmware on STM32-based flight controllers + +BreezySTM32 aims to provide a simple ("breezy") Application Programming Interface (API) for writing +firmware on the ARM STM32F103 controller boards popular on toady's flight controllers +(Naze32, Flip32, CC3D). +As with the Arduino, you write a setup() function and a loop() function, and BreezySTM32 takes care of +the rest, providing you with a C-like printf() statement, a SerialPort1 that you can read/write, and +libraries for standard signals like analog voltage, PWM, UART, and I^2C. (If you want +to use the Arduino IDE with your STM32 board, there are other +[tools](https://github.com/rogerclarkmelbourne/Arduino_STM32) +to do this; my goal with BreezySTM32 was to provide a bare-bones C API for my favorite flight controllers.) + +To use BreezySTM32, you'll at minimum need to install the [GNU ARM toolchain](https://launchpad.net/gcc-arm-embedded). +After that you can use whatever development tools you like to build your firmware. I have found it easiest to avoid +IDE / debugging tools like Eclipse, sticking with simple +makefiles for building / flashing, vim for editing, and printf() for debugging. + +To load new firmware, you should first disconnect the board from your computer, short the BOOT pins together, +and reconnect to your computer. The Flip32 features through-hole soldering pads for the BOOT +pins, so that is the board I've been using for development. By pushing a two-pin jumper onto the pins, +I avoid having to place a paper clip or tweezers across the pins while flashing. (The Baseflight firmware +that I adapted to write BeezySTM32 uses the clever trick of +[listening] (https://github.com/multiwii/baseflight/blob/master/src/serial.c#L878-L879) +for a special reboot message, which you +[send](https://github.com/multiwii/baseflight/blob/master/Makefile#L230) +from your compute right before flashing. So if you've got a long-term project to work on, you might consider +implementing something like that to avoid having to short the pins every time.) + +The BreezySTM32 examples directory includes the following use cases: +
    +
  • a simple LED blinker +
  • a program that searches the board for I2C devices, reporting the addresses of any such devices found +
  • a program that reads from the MaxBotix MB1242 I2C ultrasonic rangefinder and reports distances +in centimeters +
  • a program that reads from the onboard MPU6050 Inertial Measurement Unit and reports acceleration in mm/s2, angular velocity in mrad/s and the time delay between measurements and the time to print to the screen in us. +
  • a program that tests the SPI-based flash memory +
  • a C++ program for blinking one of the LEDs +
+ +A makefile is included with each example, +to show you how to start your own projects. Type make flash to flash the example to your board. + +Projects known to be using BreezySTM32 include: + + +If you find BreezySTM32 helpful, please consider donating +to the [Baseflight](https://goo.gl/3tyFhz) or +[Cleanflight](https://www.paypal.com/cgi-bin/webscr?cmd=_s-xclick&hosted_button_id=TSQKVT6UYKGL6) +projects from which it is derived. diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/breezyprintf.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/breezyprintf.c new file mode 100644 index 0000000..b9f85fc --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/breezyprintf.c @@ -0,0 +1,245 @@ +/* + * Copyright (c) 2004,2012 Kustaa Nyholm / SpareTimeLabs + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or other + * materials provided with the distribution. + * + * Neither the name of the Kustaa Nyholm or SpareTimeLabs nor the names of its + * contributors may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. + * IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, + * INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, + * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY + * OF SUCH DAMAGE. + */ + +#include "breezyprintf.h" + +typedef void (*putcf) (void*,char); +static putcf stdout_putf; +static void* stdout_putp; + + +#ifdef PRINTF_LONG_SUPPORT + +static void uli2a(unsigned long int num, unsigned int base, int uc,char * bf) + { + int n=0; + unsigned int d=1; + while (num/d >= base) + d*=base; + while (d!=0) { + int dgt = num / d; + num%=d; + d/=base; + if (n || dgt>0|| d==0) { + *bf++ = dgt+(dgt<10 ? '0' : (uc ? 'A' : 'a')-10); + ++n; + } + } + *bf=0; + } + +static void li2a (long num, char * bf) + { + if (num<0) { + num=-num; + *bf++ = '-'; + } + uli2a(num,10,0,bf); + } + +#endif + +static void ui2a(unsigned int num, unsigned int base, int uc,char * bf) + { + int n=0; + unsigned int d=1; + while (num/d >= base) + d*=base; + while (d!=0) { + int dgt = num / d; + num%= d; + d/=base; + if (n || dgt>0 || d==0) { + *bf++ = dgt+(dgt<10 ? '0' : (uc ? 'A' : 'a')-10); + ++n; + } + } + *bf=0; + } + +static void i2a (int num, char * bf) + { + if (num<0) { + num=-num; + *bf++ = '-'; + } + ui2a(num,10,0,bf); + } + +static int a2d(char ch) + { + if (ch>='0' && ch<='9') + return ch-'0'; + else if (ch>='a' && ch<='f') + return ch-'a'+10; + else if (ch>='A' && ch<='F') + return ch-'A'+10; + else return -1; + } + +static char a2i(char ch, char** src,int base,int* nump) + { + char* p= *src; + int num=0; + int digit; + while ((digit=a2d(ch))>=0) { + if (digit>base) break; + num=num*base+digit; + ch=*p++; + } + *src=p; + *nump=num; + return ch; + } + +static void putchw(void* putp,putcf putf,int n, char z, char* bf) + { + char fc=z? '0' : ' '; + char ch; + char* p=bf; + while (*p++ && n > 0) + n--; + while (n-- > 0) + putf(putp,fc); + while ((ch= *bf++)) + putf(putp,ch); + } + +void tfp_format(void* putp, putcf putf, const char *fmt, va_list va) + { + char bf[12]; + + char ch; + + + while ((ch=*(fmt++))) { + if (ch!='%') + putf(putp,ch); + else { + char lz=0; +#ifdef PRINTF_LONG_SUPPORT + char lng=0; +#endif + int w=0; + ch=*(fmt++); + if (ch=='0') { + ch=*(fmt++); + lz=1; + } + if (ch>='0' && ch<='9') { + ch=a2i(ch, (char **)&fmt, 10, &w); + } +#ifdef PRINTF_LONG_SUPPORT + if (ch=='l') { + ch=*(fmt++); + lng=1; + } +#endif + switch (ch) { + case 0: + goto abort; + case 'u' : { +#ifdef PRINTF_LONG_SUPPORT + if (lng) + uli2a(va_arg(va, unsigned long int),10,0,bf); + else +#endif + ui2a(va_arg(va, unsigned int),10,0,bf); + putchw(putp,putf,w,lz,bf); + break; + } + case 'd' : { +#ifdef PRINTF_LONG_SUPPORT + if (lng) + li2a(va_arg(va, unsigned long int),bf); + else +#endif + i2a(va_arg(va, int),bf); + putchw(putp,putf,w,lz,bf); + break; + } + case 'x': case 'X' : +#ifdef PRINTF_LONG_SUPPORT + if (lng) + uli2a(va_arg(va, unsigned long int),16,(ch=='X'),bf); + else +#endif + ui2a(va_arg(va, unsigned int),16,(ch=='X'),bf); + putchw(putp,putf,w,lz,bf); + break; + case 'c' : + putf(putp,(char)(va_arg(va, int))); + break; + case 's' : + putchw(putp,putf,w,0,va_arg(va, char*)); + break; + case '%' : + putf(putp,ch); + default: + break; + } + } + } + abort:; + } + + +void init_printf(void* putp, void (*putf) (void*, char)) + { + stdout_putf=putf; + stdout_putp=putp; + } + +void tfp_printf(const char *fmt, ...) + { + va_list va; + va_start(va,fmt); + tfp_format(stdout_putp,stdout_putf,fmt,va); + va_end(va); + } + +static void putcp(void* p,char c) + { + *(*((char**)p))++ = c; + } + + + +void tfp_sprintf(char* s, const char *fmt, ...) + { + va_list va; + va_start(va,fmt); + tfp_format(&s,putcp,fmt,va); + putcp(&s,0); + va_end(va); + } + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/breezyprintf.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/breezyprintf.h new file mode 100644 index 0000000..23a8856 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/breezyprintf.h @@ -0,0 +1,124 @@ +/* +File: printf.h + +Copyright (c) 2004,2012 Kustaa Nyholm / SpareTimeLabs + +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list +of conditions and the following disclaimer. + +Redistributions in binary form must reproduce the above copyright notice, this +list of conditions and the following disclaimer in the documentation and/or other +materials provided with the distribution. + +Neither the name of the Kustaa Nyholm or SpareTimeLabs nor the names of its +contributors may be used to endorse or promote products derived from this software +without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. +IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, +INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT +NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, +OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY +OF SUCH DAMAGE. + +---------------------------------------------------------------------- + +This library is realy just two files: 'printf.h' and 'printf.c'. + +They provide a simple and small (+200 loc) printf functionality to +be used in embedded systems. + +I've found them so usefull in debugging that I do not bother with a +debugger at all. + +They are distributed in source form, so to use them, just compile them +into your project. + +Two printf variants are provided: printf and sprintf. + +The formats supported by this implementation are: 'd' 'u' 'c' 's' 'x' 'X'. + +Zero padding and field width are also supported. + +If the library is compiled with 'PRINTF_SUPPORT_LONG' defined then the +long specifier is also +supported. Note that this will pull in some long math routines (pun intended!) +and thus make your executable noticably longer. + +The memory foot print of course depends on the target cpu, compiler and +compiler options, but a rough guestimate (based on a H8S target) is about +1.4 kB for code and some twenty 'int's and 'char's, say 60 bytes of stack space. +Not too bad. Your milage may vary. By hacking the source code you can +get rid of some hunred bytes, I'm sure, but personally I feel the balance of +functionality and flexibility versus code size is close to optimal for +many embedded systems. + +To use the printf you need to supply your own character output function, +something like : + +void putc ( void* p, char c) + { + while (!SERIAL_PORT_EMPTY) ; + SERIAL_PORT_TX_REGISTER = c; + } + +Before you can call printf you need to initialize it to use your +character output function with something like: + +init_printf(NULL,putc); + +Notice the 'NULL' in 'init_printf' and the parameter 'void* p' in 'putc', +the NULL (or any pointer) you pass into the 'init_printf' will eventually be +passed to your 'putc' routine. This allows you to pass some storage space (or +anything realy) to the character output function, if necessary. +This is not often needed but it was implemented like that because it made +implementing the sprintf function so neat (look at the source code). + +The code is re-entrant, except for the 'init_printf' function, so it +is safe to call it from interupts too, although this may result in mixed output. +If you rely on re-entrancy, take care that your 'putc' function is re-entrant! + +The printf and sprintf functions are actually macros that translate to +'tfp_printf' and 'tfp_sprintf'. This makes it possible +to use them along with 'stdio.h' printf's in a single source file. +You just need to undef the names before you include the 'stdio.h'. +Note that these are not function like macros, so if you have variables +or struct members with these names, things will explode in your face. +Without variadic macros this is the best we can do to wrap these +fucnction. If it is a problem just give up the macros and use the +functions directly or rename them. + +For further details see source code. + +regs Kusti, 23.10.2004 +*/ + + +#ifndef __TFP_PRINTF__ +#define __TFP_PRINTF__ + +#include + +void init_printf(void* putp,void (*putf) (void*,char)); + +void tfp_printf(const char *fmt, ...); +void tfp_sprintf(char* s, const char *fmt, ...); + +void tfp_format(void* putp, void (*putf) (void*,char), const char *fmt, va_list va); + +#define printf tfp_printf +#define sprintf tfp_sprintf + +#endif + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/breezystm32.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/breezystm32.h new file mode 100644 index 0000000..9911a52 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/breezystm32.h @@ -0,0 +1,52 @@ +/* +breezystm32.h : general header for BreezySTM32 library + +Copyright (C) 2016 Simon D. Levy + +This file is part of BreezySTM32. + +BreezySTM32 is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +BreezySTM32 is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with BreezySTM32. If not, see . +*/ + +#pragma once + +#include +#include + +#include "stm32f10x_conf.h" + +#include "drv_adc.h" +#include "drv_i2c.h" +#include "drv_serial.h" +#include "drv_gpio.h" +#include "drv_system.h" +#include "drv_pwm.h" +#include "drv_uart.h" +#include "drv_mpu6050.h" +#include "drv_ms5611.h" +#include "drv_mb1242.h" +#include "drv_sen13680.h" +#include "drv_spi.h" +#include "drv_gpio.h" +#include "drv_m25p16.h" +#include "drv_flashfs.h" +#include "drv_ms4525.h" +#include "drv_hmc5883l.h" +#include "breezyprintf.h" + +extern serialPort_t * Serial1; + +void setup(void); + +void loop(void); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_adc.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_adc.c new file mode 100644 index 0000000..e796b91 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_adc.c @@ -0,0 +1,100 @@ +/* + drv_adc.c : Driver for STM32F103CB onboard ADC + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_adc.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include + +#include "stm32f10x_conf.h" + +#include "drv_system.h" +#include "drv_adc.h" + + +typedef struct adc_config_t { + uint8_t adcChannel; // ADC1_INxx channel number + uint8_t dmaIndex; // index into DMA buffer in case of sparse channels +} adc_config_t; + +static adc_config_t adcConfig[ADC_CHANNEL_MAX]; +static volatile uint16_t adcValues[ADC_CHANNEL_MAX]; + +void adcInit(bool haveADC5) +{ + ADC_InitTypeDef adc; + DMA_InitTypeDef dma; + int numChannels = 1, i, rank = 1; + + // configure always-present battery index (ADC4) + adcConfig[ADC_BATTERY].adcChannel = ADC_Channel_4; + adcConfig[ADC_BATTERY].dmaIndex = numChannels - 1; + + // optional ADC5 input + if (haveADC5) { + numChannels++; + adcConfig[ADC_EXTERNAL_PAD].adcChannel = ADC_Channel_5; + adcConfig[ADC_EXTERNAL_PAD].dmaIndex = numChannels - 1; + } + + // ADC driver assumes all the GPIO was already placed in 'AIN' mode + DMA_DeInit(DMA1_Channel1); + dma.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR; + dma.DMA_MemoryBaseAddr = (uint32_t)adcValues; + dma.DMA_DIR = DMA_DIR_PeripheralSRC; + dma.DMA_BufferSize = numChannels; + dma.DMA_PeripheralInc = DMA_PeripheralInc_Disable; + dma.DMA_MemoryInc = numChannels > 1 ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable; + dma.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord; + dma.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord; + dma.DMA_Mode = DMA_Mode_Circular; + dma.DMA_Priority = DMA_Priority_High; + dma.DMA_M2M = DMA_M2M_Disable; + DMA_Init(DMA1_Channel1, &dma); + DMA_Cmd(DMA1_Channel1, ENABLE); + + adc.ADC_Mode = ADC_Mode_Independent; + adc.ADC_ScanConvMode = numChannels > 1 ? ENABLE : DISABLE; + adc.ADC_ContinuousConvMode = ENABLE; + adc.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None; + adc.ADC_DataAlign = ADC_DataAlign_Right; + adc.ADC_NbrOfChannel = numChannels; + ADC_Init(ADC1, &adc); + + // Configure ADC channels. Skip if channel is zero, means can't use PA0, but OK for this situation. + for (i = 0; i < ADC_CHANNEL_MAX; i++) + if (adcConfig[i].adcChannel > 0) + ADC_RegularChannelConfig(ADC1, adcConfig[i].adcChannel, rank++, ADC_SampleTime_239Cycles5); + ADC_DMACmd(ADC1, ENABLE); + + ADC_Cmd(ADC1, ENABLE); + + // Calibrate ADC + ADC_ResetCalibration(ADC1); + while (ADC_GetResetCalibrationStatus(ADC1)); + ADC_StartCalibration(ADC1); + while (ADC_GetCalibrationStatus(ADC1)); + + // Fire off ADC + ADC_SoftwareStartConvCmd(ADC1, ENABLE); +} + +uint16_t adcGetChannel(uint8_t channel) +{ + return adcValues[adcConfig[channel].dmaIndex]; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_adc.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_adc.h new file mode 100644 index 0000000..30a81af --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_adc.h @@ -0,0 +1,33 @@ +/* + drv_adc.h : Driver for STM32F103CB onboard ADC + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_adc.h + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#pragma once + +typedef enum { + ADC_BATTERY = 0, + ADC_EXTERNAL_PAD = 1, + ADC_EXTERNAL_CURRENT = 2, + ADC_RSSI = 3, + ADC_CHANNEL_MAX = 4 +} AdcChannel; + +void adcInit(bool haveADC5); +uint16_t adcGetChannel(uint8_t channel); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_flash.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_flash.h new file mode 100644 index 0000000..43a0976 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_flash.h @@ -0,0 +1,35 @@ +/* + drv_flash.c : Flash memory data structure for STM32F103 + + Adapted from https://github.com/cleanflight/cleanflight/blob/master/src/main/drivers/flash.h + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#pragma once + +#include + +typedef struct flashGeometry_s { + uint16_t sectors; // Count of the number of erasable blocks on the device + + uint16_t pagesPerSector; + const uint16_t pageSize; // In bytes + + uint32_t sectorSize; // This is just pagesPerSector * pageSize + + uint32_t totalSize; // This is just sectorSize * sectors +} flashGeometry_t; diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_flashfs.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_flashfs.c new file mode 100644 index 0000000..8e0eaea --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_flashfs.c @@ -0,0 +1,572 @@ +/* + drv_flashfs.c : Flash memory support for STM32F103 + + Adapted from https://github.com/cleanflight/cleanflight/blob/master/src/main/io/flashfs.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +/** + * This provides a stream interface to a flash chip if one is present. + * + * On statup, call flashfsInit() after initialising the flash chip in order to init the filesystem. This will + * result in the file pointer being pointed at the first free block found, or at the end of the device if the + * flash chip is full. + * + * Note that bits can only be set to 0 when writing, not back to 1 from 0. You must erase sectors in order + * to bring bits back to 1 again. + * + * In future, we can add support for multiple different flash chips by adding a flash device driver vtable + * and make calls through that, at the moment flashfs just calls m25p16_* routines explicitly. + */ + +#include +#include +#include + +#include "drv_m25p16.h" +#include "drv_flashfs.h" + +static uint8_t flashWriteBuffer[FLASHFS_WRITE_BUFFER_SIZE]; + +/* The position of our head and tail in the circular flash write buffer. + * + * The head is the index that a byte would be inserted into on writing, while the tail is the index of the + * oldest byte that has yet to be written to flash. + * + * When the circular buffer is empty, head == tail + */ +static uint8_t bufferHead = 0, bufferTail = 0; + +// The position of the buffer's tail in the overall flash address space: +static uint32_t tailAddress = 0; + +static void flashfsClearBuffer() +{ + bufferTail = bufferHead = 0; +} + +static bool flashfsBufferIsEmpty() +{ + return bufferTail == bufferHead; +} + +static void flashfsSetTailAddress(uint32_t address) +{ + tailAddress = address; +} + +void flashfsEraseCompletely() +{ + m25p16_eraseCompletely(); + + flashfsClearBuffer(); + + flashfsSetTailAddress(0); +} + +/** + * Start and end must lie on sector boundaries, or they will be rounded out to sector boundaries such that + * all the bytes in the range [start...end) are erased. + */ +void flashfsEraseRange(uint32_t start, uint32_t end) +{ + const flashGeometry_t *geometry = m25p16_getGeometry(); + + if (geometry->sectorSize <= 0) + return; + + // Round the start down to a sector boundary + int startSector = start / geometry->sectorSize; + + // And the end upward + int endSector = end / geometry->sectorSize; + int endRemainder = end % geometry->sectorSize; + + if (endRemainder > 0) { + endSector++; + } + + for (int i = startSector; i < endSector; i++) { + m25p16_eraseSector(i * geometry->sectorSize); + } +} + +/** + * Return true if the flash is not currently occupied with an operation. + */ +bool flashfsIsReady() +{ + return m25p16_isReady(); +} + +uint32_t flashfsGetSize() +{ + return m25p16_getGeometry()->totalSize; +} + +static uint32_t flashfsTransmitBufferUsed() +{ + if (bufferHead >= bufferTail) + return bufferHead - bufferTail; + + return FLASHFS_WRITE_BUFFER_SIZE - bufferTail + bufferHead; +} + +/** + * Get the size of the largest single write that flashfs could ever accept without blocking or data loss. + */ +uint32_t flashfsGetWriteBufferSize() +{ + return FLASHFS_WRITE_BUFFER_USABLE; +} + +/** + * Get the number of bytes that can currently be written to flashfs without any blocking or data loss. + */ +uint32_t flashfsGetWriteBufferFreeSpace() +{ + return flashfsGetWriteBufferSize() - flashfsTransmitBufferUsed(); +} + +const flashGeometry_t* flashfsGetGeometry() +{ + return m25p16_getGeometry(); +} + +/** + * Write the given buffers to flash sequentially at the current tail address, advancing the tail address after + * each write. + * + * In synchronous mode, waits for the flash to become ready before writing so that every byte requested can be written. + * + * In asynchronous mode, if the flash is busy, then the write is aborted and the routine returns immediately. + * In this case the returned number of bytes written will be less than the total amount requested. + * + * Modifies the supplied buffer pointers and sizes to reflect how many bytes remain in each of them. + * + * bufferCount: the number of buffers provided + * buffers: an array of pointers to the beginning of buffers + * bufferSizes: an array of the sizes of those buffers + * sync: true if we should wait for the device to be idle before writes, otherwise if the device is busy the + * write will be aborted and this routine will return immediately. + * + * Returns the number of bytes written + */ +static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes, int bufferCount, bool sync) +{ + uint32_t bytesTotal = 0; + + int i; + + for (i = 0; i < bufferCount; i++) { + bytesTotal += bufferSizes[i]; + } + + if (!sync && !m25p16_isReady()) { + return 0; + } + + uint32_t bytesTotalRemaining = bytesTotal; + + while (bytesTotalRemaining > 0) { + uint32_t bytesTotalThisIteration; + uint32_t bytesRemainThisIteration; + + /* + * Each page needs to be saved in a separate program operation, so + * if we would cross a page boundary, only write up to the boundary in this iteration: + */ + if (tailAddress % M25P16_PAGESIZE + bytesTotalRemaining > M25P16_PAGESIZE) { + bytesTotalThisIteration = M25P16_PAGESIZE - tailAddress % M25P16_PAGESIZE; + } else { + bytesTotalThisIteration = bytesTotalRemaining; + } + + // Are we at EOF already? Abort. + if (flashfsIsEOF()) { + // May as well throw away any buffered data + flashfsClearBuffer(); + + break; + } + + m25p16_pageProgramBegin(tailAddress); + + bytesRemainThisIteration = bytesTotalThisIteration; + + for (i = 0; i < bufferCount; i++) { + if (bufferSizes[i] > 0) { + // Is buffer larger than our write limit? Write our limit out of it + if (bufferSizes[i] >= bytesRemainThisIteration) { + m25p16_pageProgramContinue(buffers[i], bytesRemainThisIteration); + + buffers[i] += bytesRemainThisIteration; + bufferSizes[i] -= bytesRemainThisIteration; + + bytesRemainThisIteration = 0; + break; + } else { + // We'll still have more to write after finishing this buffer off + m25p16_pageProgramContinue(buffers[i], bufferSizes[i]); + + bytesRemainThisIteration -= bufferSizes[i]; + + buffers[i] += bufferSizes[i]; + bufferSizes[i] = 0; + } + } + } + + m25p16_pageProgramFinish(); + + bytesTotalRemaining -= bytesTotalThisIteration; + + // Advance the cursor in the file system to match the bytes we wrote + flashfsSetTailAddress(tailAddress + bytesTotalThisIteration); + + /* + * We'll have to wait for that write to complete before we can issue the next one, so if + * the user requested asynchronous writes, break now. + */ + if (!sync) + break; + } + + return bytesTotal - bytesTotalRemaining; +} + +/* + * Since the buffered data might wrap around the end of the circular buffer, we can have two segments of data to write, + * an initial portion and a possible wrapped portion. + * + * This routine will fill the details of those buffers into the provided arrays, which must be at least 2 elements long. + */ +static void flashfsGetDirtyDataBuffers(uint8_t const *buffers[], uint32_t bufferSizes[]) +{ + buffers[0] = flashWriteBuffer + bufferTail; + buffers[1] = flashWriteBuffer + 0; + + if (bufferHead >= bufferTail) { + bufferSizes[0] = bufferHead - bufferTail; + bufferSizes[1] = 0; + } else { + bufferSizes[0] = FLASHFS_WRITE_BUFFER_SIZE - bufferTail; + bufferSizes[1] = bufferHead; + } +} + +/** + * Get the current offset of the file pointer within the volume. + */ +uint32_t flashfsGetOffset() +{ + uint8_t const * buffers[2]; + uint32_t bufferSizes[2]; + + // Dirty data in the buffers contributes to the offset + + flashfsGetDirtyDataBuffers(buffers, bufferSizes); + + return tailAddress + bufferSizes[0] + bufferSizes[1]; +} + +/** + * Called after bytes have been written from the buffer to advance the position of the tail by the given amount. + */ +static void flashfsAdvanceTailInBuffer(uint32_t delta) +{ + bufferTail += delta; + + // Wrap tail around the end of the buffer + if (bufferTail >= FLASHFS_WRITE_BUFFER_SIZE) { + bufferTail -= FLASHFS_WRITE_BUFFER_SIZE; + } + + if (flashfsBufferIsEmpty()) { + flashfsClearBuffer(); // Bring buffer pointers back to the start to be tidier + } +} + +/** + * If the flash is ready to accept writes, flush the buffer to it. + * + * Returns true if all data in the buffer has been flushed to the device, or false if + * there is still data to be written (call flush again later). + */ +bool flashfsFlushAsync() +{ + if (flashfsBufferIsEmpty()) { + return true; // Nothing to flush + } + + uint8_t const * buffers[2]; + uint32_t bufferSizes[2]; + uint32_t bytesWritten; + + flashfsGetDirtyDataBuffers(buffers, bufferSizes); + bytesWritten = flashfsWriteBuffers(buffers, bufferSizes, 2, false); + flashfsAdvanceTailInBuffer(bytesWritten); + + return flashfsBufferIsEmpty(); +} + +/** + * Wait for the flash to become ready and begin flushing any buffered data to flash. + * + * The flash will still be busy some time after this sync completes, but space will + * be freed up to accept more writes in the write buffer. + */ +void flashfsFlushSync() +{ + if (flashfsBufferIsEmpty()) { + return; // Nothing to flush + } + + uint8_t const * buffers[2]; + uint32_t bufferSizes[2]; + + flashfsGetDirtyDataBuffers(buffers, bufferSizes); + flashfsWriteBuffers(buffers, bufferSizes, 2, true); + + // We've written our entire buffer now: + flashfsClearBuffer(); +} + +void flashfsSeekAbs(uint32_t offset) +{ + flashfsFlushSync(); + + flashfsSetTailAddress(offset); +} + +void flashfsSeekRel(int32_t offset) +{ + flashfsFlushSync(); + + flashfsSetTailAddress(tailAddress + offset); +} + +/** + * Write the given byte asynchronously to the flash. If the buffer overflows, data is silently discarded. + */ +void flashfsWriteByte(uint8_t byte) +{ + flashWriteBuffer[bufferHead++] = byte; + + if (bufferHead >= FLASHFS_WRITE_BUFFER_SIZE) { + bufferHead = 0; + } + + if (flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN) { + flashfsFlushAsync(); + } +} + +/** + * Write the given buffer to the flash either synchronously or asynchronously depending on the 'sync' parameter. + * + * If writing asynchronously, data will be silently discarded if the buffer overflows. + * If writing synchronously, the routine will block waiting for the flash to become ready so will never drop data. + */ +void flashfsWrite(const uint8_t *data, unsigned int len, bool sync) +{ + uint8_t const * buffers[3]; + uint32_t bufferSizes[3]; + + // There could be two dirty buffers to write out already: + flashfsGetDirtyDataBuffers(buffers, bufferSizes); + + // Plus the buffer the user supplied: + buffers[2] = data; + bufferSizes[2] = len; + + /* + * Would writing this data to our buffer cause our buffer to reach the flush threshold? If so try to write through + * to the flash now + */ + if (bufferSizes[0] + bufferSizes[1] + bufferSizes[2] >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN) { + uint32_t bytesWritten; + + // Attempt to write all three buffers through to the flash asynchronously + bytesWritten = flashfsWriteBuffers(buffers, bufferSizes, 3, false); + + if (bufferSizes[0] == 0 && bufferSizes[1] == 0) { + // We wrote all the data that was previously buffered + flashfsClearBuffer(); + + if (bufferSizes[2] == 0) { + // And we wrote all the data the user supplied! Job done! + return; + } + } else { + // We only wrote a portion of the old data, so advance the tail to remove the bytes we did write from the buffer + flashfsAdvanceTailInBuffer(bytesWritten); + } + + // Is the remainder of the data to be written too big to fit in the buffers? + if (bufferSizes[0] + bufferSizes[1] + bufferSizes[2] > FLASHFS_WRITE_BUFFER_USABLE) { + if (sync) { + // Write it through synchronously + flashfsWriteBuffers(buffers, bufferSizes, 3, true); + flashfsClearBuffer(); + } else { + /* + * Silently drop the data the user asked to write (i.e. no-op) since we can't buffer it and they + * requested async. + */ + } + + return; + } + + // Fall through and add the remainder of the incoming data to our buffer + data = buffers[2]; + len = bufferSizes[2]; + } + + // Buffer up the data the user supplied instead of writing it right away + + // First write the portion before we wrap around the end of the circular buffer + unsigned int bufferBytesBeforeWrap = FLASHFS_WRITE_BUFFER_SIZE - bufferHead; + + unsigned int firstPortion = len < bufferBytesBeforeWrap ? len : bufferBytesBeforeWrap; + + memcpy(flashWriteBuffer + bufferHead, data, firstPortion); + + bufferHead += firstPortion; + + data += firstPortion; + len -= firstPortion; + + // If we wrap the head around, write the remainder to the start of the buffer (if any) + if (bufferHead == FLASHFS_WRITE_BUFFER_SIZE) { + memcpy(flashWriteBuffer + 0, data, len); + + bufferHead = len; + } +} + +/** + * Read `len` bytes from the given address into the supplied buffer. + * + * Returns the number of bytes actually read which may be less than that requested. + */ +int flashfsReadAbs(uint32_t address, uint8_t *buffer, unsigned int len) +{ + int bytesRead; + + // Did caller try to read past the end of the volume? + if (address + len > flashfsGetSize()) { + // Truncate their request + len = flashfsGetSize() - address; + } + + // Since the read could overlap data in our dirty buffers, force a sync to clear those first + flashfsFlushSync(); + + bytesRead = m25p16_readBytes(address, buffer, len); + + return bytesRead; +} + +/** + * Find the offset of the start of the free space on the device (or the size of the device if it is full). + */ +int flashfsIdentifyStartOfFreeSpace() +{ + /* Find the start of the free space on the device by examining the beginning of blocks with a binary search, + * looking for ones that appear to be erased. We can achieve this with good accuracy because an erased block + * is all bits set to 1, which pretty much never appears in reasonable size substrings of blackbox logs. + * + * To do better we might write a volume header instead, which would mark how much free space remains. But keeping + * a header up to date while logging would incur more writes to the flash, which would consume precious write + * bandwidth and block more often. + */ + + enum { + /* We can choose whatever power of 2 size we like, which determines how much wastage of free space we'll have + * at the end of the last written data. But smaller blocksizes will require more searching. + */ + FREE_BLOCK_SIZE = 2048, + + /* We don't expect valid data to ever contain this many consecutive uint32_t's of all 1 bits: */ + FREE_BLOCK_TEST_SIZE_INTS = 4, // i.e. 16 bytes + FREE_BLOCK_TEST_SIZE_BYTES = FREE_BLOCK_TEST_SIZE_INTS * sizeof(uint32_t), + }; + + union { + uint8_t bytes[FREE_BLOCK_TEST_SIZE_BYTES]; + uint32_t ints[FREE_BLOCK_TEST_SIZE_INTS]; + } testBuffer; + + int left = 0; // Smallest block index in the search region + int right = flashfsGetSize() / FREE_BLOCK_SIZE; // One past the largest block index in the search region + int mid; + int result = right; + int i; + bool blockErased; + + while (left < right) { + mid = (left + right) / 2; + + if (m25p16_readBytes(mid * FREE_BLOCK_SIZE, testBuffer.bytes, FREE_BLOCK_TEST_SIZE_BYTES) < FREE_BLOCK_TEST_SIZE_BYTES) { + // Unexpected timeout from flash, so bail early (reporting the device fuller than it really is) + break; + } + + // Checking the buffer 4 bytes at a time like this is probably faster than byte-by-byte, but I didn't benchmark it :) + blockErased = true; + for (i = 0; i < FREE_BLOCK_TEST_SIZE_INTS; i++) { + if (testBuffer.ints[i] != 0xFFFFFFFF) { + blockErased = false; + break; + } + } + + if (blockErased) { + /* This erased block might be the leftmost erased block in the volume, but we'll need to continue the + * search leftwards to find out: + */ + result = mid; + + right = mid; + } else { + left = mid + 1; + } + } + + return result * FREE_BLOCK_SIZE; +} + +/** + * Returns true if the file pointer is at the end of the device. + */ +bool flashfsIsEOF() { + return tailAddress >= flashfsGetSize(); +} + +/** + * Call after initializing the flash chip in order to set up the filesystem. + */ +void flashfsInit() +{ + // If we have a flash chip present at all + if (flashfsGetSize() > 0) { + // Start the file pointer off at the beginning of free space so caller can start writing immediately + flashfsSeekAbs(flashfsIdentifyStartOfFreeSpace()); + } +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_flashfs.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_flashfs.h new file mode 100644 index 0000000..44ffee5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_flashfs.h @@ -0,0 +1,51 @@ +/* + drv_flashfs.h : Flash memory function prototypes for STM32F103 + + Adapted from https://github.com/cleanflight/cleanflight/blob/master/src/main/io/flashfs.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#pragma once + +#include + +#include "drv_flash.h" + +#define FLASHFS_WRITE_BUFFER_SIZE 128 +#define FLASHFS_WRITE_BUFFER_USABLE (FLASHFS_WRITE_BUFFER_SIZE - 1) + +// Automatically trigger a flush when this much data is in the buffer +#define FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN 64 + +void flashfsEraseCompletely(); +void flashfsEraseRange(uint32_t start, uint32_t end); +uint32_t flashfsGetSize(); +uint32_t flashfsGetOffset(); +uint32_t flashfsGetWriteBufferFreeSpace(); +uint32_t flashfsGetWriteBufferSize(); +int flashfsIdentifyStartOfFreeSpace(); +const flashGeometry_t * flashfsGetGeometry(); +void flashfsSeekAbs(uint32_t offset); +void flashfsSeekRel(int32_t offset); +void flashfsWriteByte(uint8_t byte); +void flashfsWrite(const uint8_t * data, unsigned int len, bool sync); +int flashfsReadAbs(uint32_t offset, uint8_t *data, unsigned int len); +bool flashfsFlushAsync(); +void flashfsFlushSync(); +void flashfsInit(); +bool flashfsIsReady(); +bool flashfsIsEOF(); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_gpio.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_gpio.c new file mode 100644 index 0000000..932f4d0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_gpio.c @@ -0,0 +1,133 @@ +/* + drv_gpio.c : GPIO support for STM32F103CB + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_gpio.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "stm32f10x_conf.h" +#include "core_cm3.h" +#include "breezyprintf.h" +#include "drv_system.h" // timers, delays, etc +#include "drv_gpio.h" + +#define I2C_DEVICE (I2CDEV_2) + +#define GYRO +#define ACC +#define BUZZER +#define LED0 +#define LED1 +#define INVERTER + +#define I2C_DEVICE (I2CDEV_2) + +#include "drv_adc.h" +#include "drv_i2c.h" +#include "drv_pwm.h" +#include "drv_spi.h" +#include "drv_timer.h" +#include "drv_serial.h" +#include "drv_uart.h" + +void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config) +{ + uint32_t pinpos; + for (pinpos = 0; pinpos < 16; pinpos++) { + // are we doing this pin? + if (config->pin & (0x1 << pinpos)) { + // reference CRL or CRH, depending whether pin number is 0..7 or 8..15 + __IO uint32_t *cr = &gpio->CRL + (pinpos / 8); + // mask out extra bits from pinmode, leaving just CNF+MODE + uint32_t currentmode = config->mode & 0x0F; + // offset to CNF and MODE portions of CRx register + uint32_t shift = (pinpos % 8) * 4; + // Read out current CRx value + uint32_t tmp = *cr; + // if we're in output mode, add speed too. + if (config->mode & 0x10) + currentmode |= config->speed; + // Mask out 4 bits + tmp &= ~(0xF << shift); + // apply current pinmode + tmp |= currentmode << shift; + *cr = tmp; + // Special handling for IPD/IPU + if (config->mode == Mode_IPD) { + gpio->ODR &= ~(1U << pinpos); + } else if (config->mode == Mode_IPU) { + gpio->ODR |= (1U << pinpos); + } + } + } +} + +void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc) +{ + uint32_t tmp = 0x00; + + tmp = ((uint32_t)0x0F) << (0x04 * (pinsrc & (uint8_t)0x03)); + AFIO->EXTICR[pinsrc >> 0x02] &= ~tmp; + AFIO->EXTICR[pinsrc >> 0x02] |= (((uint32_t)portsrc) << (0x04 * (pinsrc & (uint8_t)0x03))); +} + +#define LSB_MASK ((uint16_t)0xFFFF) +#define DBGAFR_POSITION_MASK ((uint32_t)0x000F0000) +#define DBGAFR_SWJCFG_MASK ((uint32_t)0xF0FFFFFF) +#define DBGAFR_LOCATION_MASK ((uint32_t)0x00200000) +#define DBGAFR_NUMBITS_MASK ((uint32_t)0x00100000) + +void gpioPinRemapConfig(uint32_t remap, bool enable) +{ + uint32_t tmp = 0x00, tmp1 = 0x00, tmpreg = 0x00, tmpmask = 0x00; + if ((remap & 0x80000000) == 0x80000000) + tmpreg = AFIO->MAPR2; + else + tmpreg = AFIO->MAPR; + + tmpmask = (remap & DBGAFR_POSITION_MASK) >> 0x10; + tmp = remap & LSB_MASK; + + if ((remap & (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) == (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) { + tmpreg &= DBGAFR_SWJCFG_MASK; + AFIO->MAPR &= DBGAFR_SWJCFG_MASK; + } else if ((remap & DBGAFR_NUMBITS_MASK) == DBGAFR_NUMBITS_MASK) { + tmp1 = ((uint32_t)0x03) << tmpmask; + tmpreg &= ~tmp1; + tmpreg |= ~DBGAFR_SWJCFG_MASK; + } else { + tmpreg &= ~(tmp << ((remap >> 0x15) * 0x10)); + tmpreg |= ~DBGAFR_SWJCFG_MASK; + } + + if (enable) + tmpreg |= (tmp << ((remap >> 0x15) * 0x10)); + + if ((remap & 0x80000000) == 0x80000000) + AFIO->MAPR2 = tmpreg; + else + AFIO->MAPR = tmpreg; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_gpio.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_gpio.h new file mode 100644 index 0000000..b5643e8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_gpio.h @@ -0,0 +1,74 @@ +/* + drv_gpio.c : GPIO support for STM32F103CB + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_gpio.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#pragma once + +typedef enum { + Mode_AIN = 0x0, + Mode_IN_FLOATING = 0x04, + Mode_IPD = 0x28, + Mode_IPU = 0x48, + Mode_Out_OD = 0x14, + Mode_Out_PP = 0x10, + Mode_AF_OD = 0x1C, + Mode_AF_PP = 0x18 +} GPIO_Mode; + +typedef enum { + Speed_10MHz = 1, + Speed_2MHz, + Speed_50MHz +} GPIO_Speed; + +typedef enum { + Pin_0 = 0x0001, + Pin_1 = 0x0002, + Pin_2 = 0x0004, + Pin_3 = 0x0008, + Pin_4 = 0x0010, + Pin_5 = 0x0020, + Pin_6 = 0x0040, + Pin_7 = 0x0080, + Pin_8 = 0x0100, + Pin_9 = 0x0200, + Pin_10 = 0x0400, + Pin_11 = 0x0800, + Pin_12 = 0x1000, + Pin_13 = 0x2000, + Pin_14 = 0x4000, + Pin_15 = 0x8000, + Pin_All = 0xFFFF +} GPIO_Pin; + +typedef struct { + uint16_t pin; + GPIO_Mode mode; + GPIO_Speed speed; +} gpio_config_t; + +#define digitalHi(p, i) { p->BSRR = i; } +#define digitalLo(p, i) { p->BRR = i; } +#define digitalToggle(p, i) { p->ODR ^= i; } +#define digitalIn(p, i) (p->IDR & i) + +void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config); +void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc); +void gpioPinRemapConfig(uint32_t remap, bool enable); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_hmc5883l.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_hmc5883l.c new file mode 100644 index 0000000..b339b7f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_hmc5883l.c @@ -0,0 +1,289 @@ +/* + drv_hmc5883l.c : Support for HMC5883L Magnetometer + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_hmc5883l.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + + +#include + +#include + +// HMC5883L, default address 0x1E +// PB12 connected to MAG_DRDY on rev4 hardware +// PC14 connected to MAG_DRDY on rev5 hardware + +/* CTRL_REGA: Control Register A + * Read Write + * Default value: 0x10 + * 7:5 0 These bits must be cleared for correct operation. + * 4:2 DO2-DO0: Data Output Rate Bits + * DO2 | DO1 | DO0 | Minimum Data Output Rate (Hz) + * ------------------------------------------------------ + * 0 | 0 | 0 | 0.75 + * 0 | 0 | 1 | 1.5 + * 0 | 1 | 0 | 3 + * 0 | 1 | 1 | 7.5 + * 1 | 0 | 0 | 15 (default) + * 1 | 0 | 1 | 30 + * 1 | 1 | 0 | 75 + * 1 | 1 | 1 | Not Used + * 1:0 MS1-MS0: Measurement Configuration Bits + * MS1 | MS0 | MODE + * ------------------------------ + * 0 | 0 | Normal + * 0 | 1 | Positive Bias + * 1 | 0 | Negative Bias + * 1 | 1 | Not Used + * + * CTRL_REGB: Control RegisterB + * Read Write + * Default value: 0x20 + * 7:5 GN2-GN0: Gain Configuration Bits. + * GN2 | GN1 | GN0 | Mag Input | Gain | Output Range + * | | | Range[Ga] | [LSB/mGa] | + * ------------------------------------------------------ + * 0 | 0 | 0 | �0.88Ga | 1370 | 0xF800?0x07FF (-2048:2047) + * 0 | 0 | 1 | �1.3Ga (def) | 1090 | 0xF800?0x07FF (-2048:2047) + * 0 | 1 | 0 | �1.9Ga | 820 | 0xF800?0x07FF (-2048:2047) + * 0 | 1 | 1 | �2.5Ga | 660 | 0xF800?0x07FF (-2048:2047) + * 1 | 0 | 0 | �4.0Ga | 440 | 0xF800?0x07FF (-2048:2047) + * 1 | 0 | 1 | �4.7Ga | 390 | 0xF800?0x07FF (-2048:2047) + * 1 | 1 | 0 | �5.6Ga | 330 | 0xF800?0x07FF (-2048:2047) + * 1 | 1 | 1 | �8.1Ga | 230 | 0xF800?0x07FF (-2048:2047) + * |Not recommended| + * + * 4:0 CRB4-CRB: 0 This bit must be cleared for correct operation. + * + * _MODE_REG: Mode Register + * Read Write + * Default value: 0x02 + * 7:2 0 These bits must be cleared for correct operation. + * 1:0 MD1-MD0: Mode Select Bits + * MS1 | MS0 | MODE + * ------------------------------ + * 0 | 0 | Continuous-Conversion Mode. + * 0 | 1 | Single-Conversion Mode + * 1 | 0 | Negative Bias + * 1 | 1 | Sleep Mode + */ + +#define MAG_ADDRESS 0x1E +#define MAG_DATA_REGISTER 0x03 + +#define HMC58X3_R_CONFA 0 +#define HMC58X3_R_CONFB 1 +#define HMC58X3_R_MODE 2 +#define HMC58X3_X_SELF_TEST_GAUSS (+1.16f) // X axis level when bias current is applied. +#define HMC58X3_Y_SELF_TEST_GAUSS (+1.16f) // Y axis level when bias current is applied. +#define HMC58X3_Z_SELF_TEST_GAUSS (+1.08f) // Z axis level when bias current is applied. +#define SELF_TEST_LOW_LIMIT (243.0f / 390.0f) // Low limit when gain is 5. +#define SELF_TEST_HIGH_LIMIT (575.0f / 390.0f) // High limit when gain is 5. +#define HMC_POS_BIAS 1 +#define HMC_NEG_BIAS 2 + +bool sensor_present = false; + +typedef enum { + X = 0, + Y, + Z +} sensor_axis_e; + +static float magGain[3] = { 1.0f, 1.0f, 1.0f }; + +/*bool hmc5883lDetect() +{ + bool ack = false; + uint8_t sig = 0; + + hmc5883lInit(); + delay(100); + + ack = i2cRead(MAG_ADDRESS, 0x0A, 1, &sig); + if (!ack || sig != 'H') + return false; + + return true; +}*/ + +bool hmc5883lInit(int boardVersion) +{ + gpio_config_t gpio; + int16_t magADC[3]; + int i; + int32_t xyz_total[3] = { 0, 0, 0 }; // 32 bit totals so they won't overflow. + bool bret = true; // Error indicator + + gpio.speed = Speed_2MHz; + gpio.mode = Mode_IN_FLOATING; + if (boardVersion > 4) { + // PB12 - MAG_DRDY output on rev4 hardware + gpio.pin = Pin_12; + gpioInit(GPIOB, &gpio); + } else { + // PC14 - MAG_DRDY output on rev5 hardware + gpio.pin = Pin_14; + gpioInit(GPIOC, &gpio); + } + + sensor_present = i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias + // Note that the very first measurement after a gain change maintains the same gain as the previous setting. + // The new gain setting is effective from the second measurement and on. + i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011) + hmc5883l_read(magADC); + + for (i = 0; i < 5; i++) { // Collect 5 samples + i2cWrite(MAG_ADDRESS, HMC58X3_R_MODE, 1); + delay(10); + hmc5883l_read(magADC); // Get the raw values in case the scales have already been changed. + + // Since the measurements are noisy, they should be averaged rather than taking the max. + xyz_total[X] += magADC[X]; + xyz_total[Y] += magADC[Y]; + xyz_total[Z] += magADC[Z]; + + // Detect saturation. + if (-4096 >= magADC[X] || -4096 >= magADC[Y] || -4096 >= magADC[Z]) { + bret = false; + break; // Breaks out of the for loop. No sense in continuing if we saturated. + } + } + + // Apply the negative bias. (Same gain) + i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias. + for (i = 0; i < 5; i++) { + i2cWrite(MAG_ADDRESS, HMC58X3_R_MODE, 1); + delay(10); + hmc5883l_read(magADC); // Get the raw values in case the scales have already been changed. + + // Since the measurements are noisy, they should be averaged. + xyz_total[X] -= magADC[X]; + xyz_total[Y] -= magADC[Y]; + xyz_total[Z] -= magADC[Z]; + + // Detect saturation. + if (-4096 >= magADC[X] || -4096 >= magADC[Y] || -4096 >= magADC[Z]) { + bret = false; + break; // Breaks out of the for loop. No sense in continuing if we saturated. + } + } + + magGain[X] = fabsf(660.0f * HMC58X3_X_SELF_TEST_GAUSS * 2.0f * 5.0f / xyz_total[X]); + magGain[Y] = fabsf(660.0f * HMC58X3_Y_SELF_TEST_GAUSS * 2.0f * 5.0f / xyz_total[Y]); + magGain[Z] = fabsf(660.0f * HMC58X3_Z_SELF_TEST_GAUSS * 2.0f * 5.0f / xyz_total[Z]); + + // leave test mode + i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFA, 0x70); // Configuration Register A -- 0 11 100 00 num samples: 8 ; output rate: 15Hz ; normal measurement mode + i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFB, 0x20); // Configuration Register B -- 001 00000 configuration gain 1.3Ga + i2cWrite(MAG_ADDRESS, HMC58X3_R_MODE, 0x00); // Mode register -- 000000 00 continuous Conversion Mode + + if (!bret) { // Something went wrong so get a best guess + magGain[X] = 1.0f; + magGain[Y] = 1.0f; + magGain[Z] = 1.0f; + } + + bool ack = false; + uint8_t sig = 0; + + ack = i2cRead(MAG_ADDRESS, 0x0A, 1, &sig); + if (!ack || sig != 'H') + return false; + + return true; +} + +uint8_t buf[6]; +void hmc5883l_update() +{ + static uint32_t last_update = 0; + uint32_t now = millis(); + if(last_update + 13 < now) + { + last_update = now; + i2cRead(MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf); + } + +} + +void hmc5883l_read(int16_t *magData) +{ + // During calibration, magGain is 1.0, so the read returns normal non-calibrated values. + // After calibration is done, magGain is set to calculated gain values. + magData[X] = (int16_t)(buf[0] << 8 | buf[1]); + magData[Y] = (int16_t)(buf[2] << 8 | buf[3]); + magData[Z] = (int16_t)(buf[4] << 8 | buf[5]); +} + + +/* ================================================================= + * Asynchronous Method + */ +static uint8_t mag_buffer[6]; +static int16_t mag_data[3]; +static volatile uint8_t status; + +void mag_read_CB(void) +{ + mag_data[X] = (mag_buffer[0] << 8 | mag_buffer[1]); + mag_data[Z] = (mag_buffer[2] << 8 | mag_buffer[3]); + mag_data[Y] = (mag_buffer[4] << 8 | mag_buffer[5]); +} + +void mag_init_CB(void) +{ + if (status == I2C_JOB_COMPLETE) + { + sensor_present = true; + } +} + +void hmc5883l_request_async_update() +{ + static uint64_t last_update_ms = 0; + uint64_t now = millis(); + + if(now - last_update_ms > 20) + { + // 100 Hz update rate + i2c_queue_job(READ, + MAG_ADDRESS, + MAG_DATA_REGISTER, + mag_buffer, + 6, + &status, + &mag_read_CB); + + last_update_ms = now; + } + return; +} + +void hmc5883l_async_read(int16_t *magData) +{ + magData[0] = mag_data[X]; + magData[1] = mag_data[Y]; + magData[2] = mag_data[Z]; + return; +} + +bool hmc5883l_present() +{ + return sensor_present; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_hmc5883l.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_hmc5883l.h new file mode 100644 index 0000000..7a66af2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_hmc5883l.h @@ -0,0 +1,35 @@ +/* + drv_hmc5883l.h : Support for HMC5883L Magnetometer + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_hmc5883l.h + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + + +#pragma once + +bool hmc5883lInit(int boardVersion); + +// Blocking I2C Read Method +void hmc5883l_update(); +void hmc5883l_read(int16_t *magData); + +// Asynchronous I2C method +void hmc5883l_request_async_update(); +void hmc5883l_async_read(int16_t *magData); + +bool hmc5883l_present(); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_i2c.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_i2c.c new file mode 100644 index 0000000..09a038f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_i2c.c @@ -0,0 +1,628 @@ +/* + drv_i2c.c : I^2C support for STM32F103 + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_i2c.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#define I2C_DEVICE (I2CDEV_2) + +#include +#include +#include // memset + +#include "stm32f10x_conf.h" +#include "drv_system.h" // timers, delays, etc +#include "drv_gpio.h" + +#include "drv_i2c.h" + +// I2C Interrupt Handlers +static void i2c_er_handler(void); +static void i2c_ev_handler(void); +static void i2cUnstick(void); + +// I2C Circular Buffer Variables +static bool i2c_buffer_lock = false; +static i2cJob_t i2c_buffer[I2C_BUFFER_SIZE + 10]; +static volatile uint8_t i2c_buffer_head; +static volatile uint8_t i2c_buffer_tail; +static volatile uint8_t i2c_buffer_count; +static void i2c_init_buffer(void); +static void i2c_job_handler(void); + +typedef struct i2cDevice_t { + I2C_TypeDef *dev; + GPIO_TypeDef *gpio; + uint16_t scl; + uint16_t sda; + uint8_t ev_irq; + uint8_t er_irq; + uint32_t peripheral; +} i2cDevice_t; + +static const i2cDevice_t i2cHardwareMap[] = { + { I2C1, GPIOB, Pin_6, Pin_7, I2C1_EV_IRQn, I2C1_ER_IRQn, RCC_APB1Periph_I2C1 }, + { I2C2, GPIOB, Pin_10, Pin_11, I2C2_EV_IRQn, I2C2_ER_IRQn, RCC_APB1Periph_I2C2 }, +}; + +// Copy of peripheral address for IRQ routines +static I2C_TypeDef *I2Cx = NULL; +// Copy of device index for reinit, etc purposes +static I2CDevice I2Cx_index; + + +void I2C1_ER_IRQHandler(void) +{ + i2c_er_handler(); +} + +void I2C1_EV_IRQHandler(void) +{ + i2c_ev_handler(); +} + +void I2C2_ER_IRQHandler(void) +{ + i2c_er_handler(); +} + +void I2C2_EV_IRQHandler(void) +{ + i2c_ev_handler(); +} + +#define I2C_DEFAULT_TIMEOUT 30000 +static volatile uint16_t i2cErrorCount = 0; + +static volatile bool error = false; +static volatile bool busy; + +static volatile uint8_t addr; +static volatile uint8_t reg; +static volatile uint8_t bytes; +static volatile uint8_t writing; +static volatile uint8_t reading; +static volatile uint8_t *write_p; +static volatile uint8_t *read_p; +static volatile uint8_t *status; +static void (*complete_CB)(void); + +static bool i2cHandleHardwareFailure(void) +{ + i2cErrorCount++; + // reinit peripheral + clock out garbage + i2cInit(I2Cx_index); + return false; +} + +bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data) +{ + uint32_t timeout = I2C_DEFAULT_TIMEOUT; + + addr = addr_ << 1; + reg = reg_; + writing = 1; + reading = 0; + write_p = data; + read_p = data; + bytes = len_; + busy = 1; + error = false; + + if (!I2Cx) + return false; + + if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver + if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start + while (I2Cx->CR1 & 0x0200 && --timeout > 0) { + ; // wait for any stop to finish sending + } + if (timeout == 0) + return i2cHandleHardwareFailure(); + I2C_GenerateSTART(I2Cx, ENABLE); // send the start for the new job + } + I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); // allow the interrupts to fire off again + } + + timeout = I2C_DEFAULT_TIMEOUT; + while (busy && --timeout > 0) { + ; + } + if (timeout == 0) + return i2cHandleHardwareFailure(); + + return !error; +} + +bool i2cWrite(uint8_t addr_, uint8_t reg_, uint8_t data) +{ + return i2cWriteBuffer(addr_, reg_, 1, &data); +} + +bool i2cRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t *buf) +{ + uint32_t timeout = I2C_DEFAULT_TIMEOUT; + + addr = addr_ << 1; + reg = reg_; + writing = 0; + reading = 1; + read_p = buf; + write_p = buf; + bytes = len; + busy = 1; + error = false; + + if (!I2Cx) + return false; + + if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver + if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start + while (I2Cx->CR1 & 0x0200 && --timeout > 0) { + ; // wait for any stop to finish sending + } + if (timeout == 0) + return i2cHandleHardwareFailure(); + I2C_GenerateSTART(I2Cx, ENABLE); // send the start for the new job + } + I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); // allow the interrupts to fire off again + } + + timeout = I2C_DEFAULT_TIMEOUT; + while (busy && --timeout > 0) { + ; + } + if (timeout == 0) + return i2cHandleHardwareFailure(); + + return !error; +} + +bool i2cReadAsync(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t *buf, volatile uint8_t* status_, void (*CB)(void)) +{ + uint32_t timeout = I2C_DEFAULT_TIMEOUT; + + addr = addr_ << 1; + reg = reg_; + writing = 0; + reading = 1; + read_p = buf; + write_p = buf; + bytes = len; + busy = 1; + error = false; + status = status_; + complete_CB = CB; + + if(!I2Cx) + return false; + + if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver + if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start + while (I2Cx->CR1 & 0x0200 && --timeout > 0) { // This is blocking, but happens only + ; // wait for any stop to finish sending // if we are stomping on the port (try to avoid) + } + if (timeout == 0) + return i2cHandleHardwareFailure(); + I2C_GenerateSTART(I2Cx, ENABLE); // send the start for the new job + } + I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); // allow the interrupts to fire off again + } + return true; +} + +bool i2cWriteAsync(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf_, volatile uint8_t* status_, void (*CB)(void)) +{ + uint32_t timeout = I2C_DEFAULT_TIMEOUT; + + addr = addr_ << 1; + reg = reg_; + writing = 1; + reading = 0; + write_p = buf_; + read_p = buf_; + bytes = len_; + busy = 1; + error = false; + status = status_; + complete_CB = CB; + + if (!I2Cx) + return false; + + if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver + if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start + while (I2Cx->CR1 & 0x0200 && --timeout > 0) { + ; // wait for any stop to finish sending + } + if (timeout == 0) + return i2cHandleHardwareFailure(); + I2C_GenerateSTART(I2Cx, ENABLE); // send the start for the new job + } + I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); // allow the interrupts to fire off again + } + return true; +} + +static void i2c_er_handler(void) +{ + // Read the I2C1 status register + volatile uint32_t SR1Register = I2Cx->SR1; + + if (SR1Register & 0x0F00) // an error + { + i2cErrorCount++; + error = true; + } + + // If AF, BERR or ARLO, abandon the current job and commence new if there are jobs + if (SR1Register & 0x0700) { + (void)I2Cx->SR2; // read second status register to clear ADDR if it is set (note that BTF will not be set after a NACK) + I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable the RXNE/TXE interrupt - prevent the ISR tailchaining onto the ER (hopefully) + if (!(SR1Register & 0x0200) && !(I2Cx->CR1 & 0x0200)) { // if we dont have an ARLO error, ensure sending of a stop + if (I2Cx->CR1 & 0x0100) { // We are currently trying to send a start, this is very bad as start, stop will hang the peripheral + uint32_t timeout = I2C_DEFAULT_TIMEOUT; + while (I2Cx->CR1 & 0x0100 && --timeout > 0) { + ; // wait for any start to finish sending + } + I2C_GenerateSTOP(I2Cx, ENABLE); // send stop to finalise bus transaction + timeout = I2C_DEFAULT_TIMEOUT; + while (I2Cx->CR1 & 0x0200 && --timeout > 0) { + ; // wait for stop to finish sending + } + i2cInit(I2Cx_index); // reset and configure the hardware + } else { + I2C_GenerateSTOP(I2Cx, ENABLE); // stop to free up the bus + I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts while bus inactive + } + } + } + I2Cx->SR1 &= ~0x0F00; // reset all the error bits to clear the interrupt + if (status) + (*status) = I2C_JOB_ERROR; // Update job status + if (complete_CB != NULL) + complete_CB(); + busy = 0; + i2c_job_handler(); +} + +void i2c_ev_handler(void) +{ + static uint8_t subaddress_sent, final_stop; // flag to indicate if subaddess sent, flag to indicate final bus condition + static int8_t index; // index is signed -1 == send the subaddress + uint8_t SReg_1 = I2Cx->SR1; // read the status register here + + if (SReg_1 & 0x0001) { // we just sent a start - EV5 in ref manual + I2Cx->CR1 &= ~0x0800; // reset the POS bit so ACK/NACK applied to the current byte + I2C_AcknowledgeConfig(I2Cx, ENABLE); // make sure ACK is on + index = 0; // reset the index + if (reading && (subaddress_sent || 0xFF == reg)) { // we have sent the subaddr + subaddress_sent = 1; // make sure this is set in case of no subaddress, so following code runs correctly + if (bytes == 2) + I2Cx->CR1 |= 0x0800; // set the POS bit so NACK applied to the final byte in the two byte read + I2C_Send7bitAddress(I2Cx, addr, I2C_Direction_Receiver); // send the address and set hardware mode + } else { // direction is Tx, or we havent sent the sub and rep start + I2C_Send7bitAddress(I2Cx, addr, I2C_Direction_Transmitter); // send the address and set hardware mode + if (reg != 0xFF) // 0xFF as subaddress means it will be ignored, in Tx or Rx mode + index = -1; // send a subaddress + } + + } else if (SReg_1 & 0x0002) { // we just sent the address - EV6 in ref manual + // Read SR1,2 to clear ADDR + __DMB(); // memory fence to control hardware + if (bytes == 1 && reading && subaddress_sent) { // we are receiving 1 byte - EV6_3 + I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK + __DMB(); + (void)I2Cx->SR2; // clear ADDR after ACK is turned off + I2C_GenerateSTOP(I2Cx, ENABLE); // program the stop + final_stop = 1; + I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); // allow us to have an EV7 + } else { // EV6 and EV6_1 + (void)I2Cx->SR2; // clear the ADDR here + __DMB(); + if (bytes == 2 && reading && subaddress_sent) { // rx 2 bytes - EV6_1 + I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK + I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to fill + } else if (bytes == 3 && reading && subaddress_sent) // rx 3 bytes + I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // make sure RXNE disabled so we get a BTF in two bytes time + else // receiving greater than three bytes, sending subaddress, or transmitting + I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); + } + + } else if (SReg_1 & 0x004) { // Byte transfer finished - EV7_2, EV7_3 or EV8_2 + final_stop = 1; + if (reading && subaddress_sent) { // EV7_2, EV7_3 + if (bytes > 2) { // EV7_2 + I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK + read_p[index++] = (uint8_t)I2Cx->DR; // read data N-2 + I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop + final_stop = 1; // required to fix hardware + read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1 + I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); // enable TXE to allow the final EV7 + } else { // EV7_3 + if (final_stop){ + I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop + } + else + I2C_GenerateSTART(I2Cx, ENABLE); // program a rep start + read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1 + read_p[index++] = (uint8_t)I2Cx->DR; // read data N + index++; // to show job completed + } + } else { // EV8_2, which may be due to a subaddress sent or a write completion + if (subaddress_sent || (writing)) { + if (final_stop) + I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop + else + I2C_GenerateSTART(I2Cx, ENABLE); // program a rep start + index++; // to show that the job is complete + } else { // We need to send a subaddress + I2C_GenerateSTART(I2Cx, ENABLE); // program the repeated Start + subaddress_sent = 1; // this is set back to zero upon completion of the current task + } + } + // we must wait for the start to clear, otherwise we get constant BTF + uint32_t timeout = I2C_DEFAULT_TIMEOUT; + while (I2Cx->CR1 & 0x0100 && --timeout > 0) { + ; + } + + } else if (SReg_1 & 0x0040) { // Byte received - EV7 + read_p[index++] = (uint8_t)I2Cx->DR; + if (bytes == (index + 3)) + I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush so we can get an EV7_2 + if (bytes == index) // We have completed a final EV7 + index++; // to show job is complete + } else if (SReg_1 & 0x0080) { // Byte transmitted EV8 / EV8_1 + if (index != -1) { // we dont have a subaddress to send + I2Cx->DR = write_p[index++]; + if (bytes == index) // we have sent all the data + I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush + } else { + index++; + I2Cx->DR = reg; // send the subaddress + if (reading || !bytes) // if receiving or sending 0 bytes, flush now + I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush + } + } + + if (index == bytes + 1) { // we have completed the current job + subaddress_sent = 0; // reset this here + if (final_stop) { // If there is a final stop and no more jobs, bus is inactive, disable interrupts to prevent BTF + I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts while bus inactive + } + if (status){ + (*status) = I2C_JOB_COMPLETE; // Update status + } + if (complete_CB != NULL){ + complete_CB(); // Call the custom callback (we are finished) + } + busy = 0; + i2c_job_handler(); // Start the next job (if there is one on the queue) + } +} + +void i2cInit(I2CDevice index) +{ + NVIC_InitTypeDef nvic; + I2C_InitTypeDef i2c; + + if (index > I2CDEV_MAX) + index = I2CDEV_MAX; + + // Turn on peripheral clock, save device and index + I2Cx = i2cHardwareMap[index].dev; + I2Cx_index = index; + RCC_APB1PeriphClockCmd(i2cHardwareMap[index].peripheral, ENABLE); + + // clock out stuff to make sure slaves arent stuck + // This will also configure GPIO as AF_OD at the end + i2cUnstick(); + + // Init I2C peripheral + I2C_DeInit(I2Cx); + I2C_StructInit(&i2c); + + I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Enable EVT and ERR interrupts - they are enabled by the first request + i2c.I2C_Mode = I2C_Mode_I2C; + i2c.I2C_DutyCycle = I2C_DutyCycle_2; + i2c.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; + i2c.I2C_ClockSpeed = 400000; + I2C_Cmd(I2Cx, ENABLE); + I2C_Init(I2Cx, &i2c); + + // I2C ER Interrupt + nvic.NVIC_IRQChannel = i2cHardwareMap[index].er_irq; + // Set the priority to just below the systick interrupt + nvic.NVIC_IRQChannelPreemptionPriority = 2; + nvic.NVIC_IRQChannelSubPriority = 1; + nvic.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&nvic); + + // I2C EV Interrupt + nvic.NVIC_IRQChannel = i2cHardwareMap[index].ev_irq; + // Set the priority to just below the systick interrupt + nvic.NVIC_IRQChannelPreemptionPriority = 1; + NVIC_Init(&nvic); + + // Initialize buffer + i2c_init_buffer(); +} + +uint16_t i2cGetErrorCounter(void) +{ + return i2cErrorCount; +} + +static void i2cUnstick(void) +{ + GPIO_TypeDef *gpio; + gpio_config_t cfg; + uint16_t scl, sda; + int i; + + // disable any I2C interrupts + I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); + + + // prepare pins + gpio = i2cHardwareMap[I2Cx_index].gpio; + scl = i2cHardwareMap[I2Cx_index].scl; + sda = i2cHardwareMap[I2Cx_index].sda; + + digitalHi(gpio, scl | sda); + + cfg.pin = scl | sda; + cfg.speed = Speed_2MHz; + cfg.mode = Mode_Out_OD; + gpioInit(gpio, &cfg); + + for (i = 0; i < 8; i++) { + // Wait for any clock stretching to finish + while (!digitalIn(gpio, scl)) + delayMicroseconds(10); + + // Pull low + digitalLo(gpio, scl); // Set bus low + delayMicroseconds(10); + // Release high again + digitalHi(gpio, scl); // Set bus high + delayMicroseconds(10); + } + + // Generate a start then stop condition + // SCL PB10 + // SDA PB11 + digitalLo(gpio, sda); // Set bus data low + delayMicroseconds(10); + digitalLo(gpio, scl); // Set bus scl low + delayMicroseconds(10); + digitalHi(gpio, scl); // Set bus scl high + delayMicroseconds(10); + digitalHi(gpio, sda); // Set bus sda high + + // Init pins + cfg.pin = scl | sda; + cfg.speed = Speed_2MHz; + cfg.mode = Mode_AF_OD; + gpioInit(gpio, &cfg); + + // clear the buffer +} + +void i2c_job_handler() +{ + if(i2c_buffer_count == 0) + { + // the queue is empty, stop performing i2c until + // a new job is enqueued + return; + } + + if(busy) + { + // wait for the current job to finish. This function + // will get called again when the job is done + return; + } + + // Perform the job on the front of the queue + i2cJob_t* job = i2c_buffer + i2c_buffer_tail; + + // First, change status to BUSY + if (job->status) + (*job->status) = I2C_JOB_BUSY; + + // perform the appropriate job + if(job->type == READ) + { + i2cReadAsync(job->addr, + job->reg, + job->length, + job->data, + job->status, + job->CB); + } + else + { + i2cWriteAsync(job->addr, + job->reg, + job->length, + job->data, + job->status, + job->CB); + } + + // Increment the tail + i2c_buffer_tail = (i2c_buffer_tail + 1) % I2C_BUFFER_SIZE; + + // Decrement the number of jobs on the buffer + i2c_buffer_count--; + return; +} + +void i2c_queue_job(i2cJobType_t type, uint8_t addr_, uint8_t reg_, uint8_t *data, uint8_t length, volatile uint8_t* status_, void (*CB)(void)) +{ + // If this job were going to overflow the buffer, ignore it. + if (i2c_buffer_count >= I2C_BUFFER_SIZE) + { + if(status_) + *status_ = I2C_JOB_ERROR; + return; + } + + // Get a pointer to the head + volatile i2cJob_t* job = i2c_buffer + i2c_buffer_head; + // Increment the buffer head for next call + i2c_buffer_head = (i2c_buffer_head + 1) % I2C_BUFFER_SIZE; + // Increment the buffer size + i2c_buffer_count++; + + // save the data about the job + job->type = type; + job->data = data; + job->addr = addr_; + job->reg = reg_; + job->length = length; + job->next_job = NULL; + job->status = status_; + job->CB = CB; + + // change job status + if (job->status) + (*job->status) = I2C_JOB_QUEUED; + + if(i2c_buffer_count == 1) + { + // if the buffer queue was empty, restart i2c job handling + i2c_job_handler(); + } + i2c_buffer_lock = false; + + return; +} + +void i2c_init_buffer() +{ + // write zeros to the buffer, and set all the indexes to zero + memset(i2c_buffer, 0, I2C_BUFFER_SIZE*sizeof(i2cJob_t)); + i2c_buffer_count = 0; + i2c_buffer_head = 0; + i2c_buffer_tail = 0; +} + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_i2c.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_i2c.h new file mode 100644 index 0000000..0427924 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_i2c.h @@ -0,0 +1,77 @@ +/* + drv_i2c.h : I^2C support for STM32F103CB + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_i2c.h + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#pragma once + +typedef enum I2CDevice { + I2CDEV_1, + I2CDEV_2, + I2CDEV_MAX = I2CDEV_2 +} I2CDevice; + +typedef enum { + READ, + WRITE +} i2cJobType_t; + +enum { + I2C_JOB_DEFAULT, + I2C_JOB_QUEUED, + I2C_JOB_BUSY, + I2C_JOB_COMPLETE, + I2C_JOB_ERROR +}; + +typedef struct i2cJob{ + i2cJobType_t type; + uint8_t addr; + uint8_t reg; + uint8_t* data; + uint8_t length; + struct i2cJob* next_job; + volatile uint8_t* status; + void (*CB)(void); +} i2cJob_t; + +#define I2C_BUFFER_SIZE 16 + +void i2cInit(I2CDevice index); +uint16_t i2cGetErrorCounter(void); + +// Blocking I2C functions (returns value success or failure) +bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data); +bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data); +bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t *buf); + +// =================================================================== +// Asynchronous I2C handler +// To use this, queue up a job, and create a callback you want called when the job is finished +// You can track progress of the job using the status pointer. Otherwise, functions the same +// as the blocking versions. +// +// This uses a circular buffer to stage jobs for the I2C peripheral. The buffer is, by default, 16 jobs +// long (I2C_BUFFER_SIZE), with a maximum size of 256. I hope you never queue up that many jobs, because +// that will take a long time to process However, if you were to reach the limit, it would then start +// ignoring new jobs until there was space on the buffer. +// +// For an example of how to use, check out mpu6050_request_read_temp - the non-blocking way to read +// the accelerometer +void i2c_queue_job(i2cJobType_t type, uint8_t addr_, uint8_t reg_, uint8_t *data, uint8_t length, volatile uint8_t *status_, void (*CB)(void)); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_m25p16.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_m25p16.c new file mode 100644 index 0000000..bcbbd49 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_m25p16.c @@ -0,0 +1,333 @@ +/* + drv_m25p16.c : driver for Micron Technology MP25P16 flash memory + + Adapted from https://github.com/cleanflight/cleanflight/blob/master/src/main/drivers/flash_m25p16.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include +#include +#include + +#include "stm32f10x_conf.h" +#include "stm32f10x_gpio.h" +#include "core_cm3.h" + +// Chip Unique ID on F103 +#define U_ID_0 (*(uint32_t*)0x1FFFF7E8) +#define U_ID_1 (*(uint32_t*)0x1FFFF7EC) +#define U_ID_2 (*(uint32_t*)0x1FFFF7F0) + +#define NAZE_SPI_INSTANCE SPI2 +#define NAZE_SPI_CS_GPIO GPIOB +#define NAZE_SPI_CS_PIN GPIO_Pin_12 +#define NAZE_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB + +// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision: +#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO +#define M25P16_CS_PIN NAZE_SPI_CS_PIN +#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE + + +#include "drv_m25p16.h" + +#include +#include + +#define M25P16_INSTRUCTION_RDID 0x9F +#define M25P16_INSTRUCTION_READ_BYTES 0x03 +#define M25P16_INSTRUCTION_READ_STATUS_REG 0x05 +#define M25P16_INSTRUCTION_WRITE_STATUS_REG 0x01 +#define M25P16_INSTRUCTION_WRITE_ENABLE 0x06 +#define M25P16_INSTRUCTION_WRITE_DISABLE 0x04 +#define M25P16_INSTRUCTION_PAGE_PROGRAM 0x02 +#define M25P16_INSTRUCTION_SECTOR_ERASE 0xD8 +#define M25P16_INSTRUCTION_BULK_ERASE 0xC7 + +#define M25P16_STATUS_FLAG_WRITE_IN_PROGRESS 0x01 +#define M25P16_STATUS_FLAG_WRITE_ENABLED 0x02 + +// Format is manufacturer, memory type, then capacity +#define JEDEC_ID_MICRON_M25P16 0x202015 +#define JEDEC_ID_MICRON_N25Q064 0x20BA17 +#define JEDEC_ID_WINBOND_W25Q64 0xEF4017 +#define JEDEC_ID_MICRON_N25Q128 0x20ba18 +#define JEDEC_ID_WINBOND_W25Q128 0xEF4018 + +#define DISABLE_M25P16 GPIO_SetBits(M25P16_CS_GPIO, M25P16_CS_PIN) +#define ENABLE_M25P16 GPIO_ResetBits(M25P16_CS_GPIO, M25P16_CS_PIN) + +// The timeout we expect between being able to issue page program instructions +#define DEFAULT_TIMEOUT_MILLIS 6 + +// These take sooooo long: +#define SECTOR_ERASE_TIMEOUT_MILLIS 5000 +#define BULK_ERASE_TIMEOUT_MILLIS 21000 + +static flashGeometry_t geometry = {.pageSize = M25P16_PAGESIZE}; + +/* + * Whether we've performed an action that could have made the device busy for writes. + * + * This allows us to avoid polling for writable status when it is definitely ready already. + */ +static bool couldBeBusy = false; + +/** + * Send the given command byte to the device. + */ +static void m25p16_performOneByteCommand(uint8_t command) +{ + ENABLE_M25P16; + + spiTransferByte(M25P16_SPI_INSTANCE, command); + + DISABLE_M25P16; +} + +/** + * The flash requires this write enable command to be sent before commands that would cause + * a write like program and erase. + */ +static void m25p16_writeEnable() +{ + m25p16_performOneByteCommand(M25P16_INSTRUCTION_WRITE_ENABLE); + + // Assume that we're about to do some writing, so the device is just about to become busy + couldBeBusy = true; +} + +static uint8_t m25p16_readStatus() +{ + uint8_t command[2] = {M25P16_INSTRUCTION_READ_STATUS_REG, 0}; + uint8_t in[2]; + + ENABLE_M25P16; + + spiTransfer(M25P16_SPI_INSTANCE, in, command, sizeof(command)); + + DISABLE_M25P16; + + return in[1]; +} + +bool m25p16_isReady() +{ + // If couldBeBusy is false, don't bother to poll the flash chip for its status + couldBeBusy = couldBeBusy && ((m25p16_readStatus() & M25P16_STATUS_FLAG_WRITE_IN_PROGRESS) != 0); + + return !couldBeBusy; +} + +bool m25p16_waitForReady(uint32_t timeoutMillis) +{ + uint32_t time = millis(); + while (!m25p16_isReady()) { + if (millis() - time > timeoutMillis) { + return false; + } + } + + return true; +} + +/** + * Read chip identification and geometry information (into global `geometry`). + * + * Returns true if we get valid ident, false if something bad happened like there is no M25P16. + */ +static bool m25p16_readIdentification() +{ + uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0}; + uint8_t in[4]; + uint32_t chipID; + + delay(50); // short delay required after initialisation of SPI device instance. + + /* Just in case transfer fails and writes nothing, so we don't try to verify the ID against random garbage + * from the stack: + */ + in[1] = 0; + + ENABLE_M25P16; + + spiTransfer(M25P16_SPI_INSTANCE, in, out, sizeof(out)); + + // Clearing the CS bit terminates the command early so we don't have to read the chip UID: + DISABLE_M25P16; + + // Manufacturer, memory type, and capacity + chipID = (in[1] << 16) | (in[2] << 8) | (in[3]); + + // All supported chips use the same pagesize of 256 bytes + + switch (chipID) { + case JEDEC_ID_MICRON_M25P16: + geometry.sectors = 32; + geometry.pagesPerSector = 256; + break; + case JEDEC_ID_MICRON_N25Q064: + case JEDEC_ID_WINBOND_W25Q64: + geometry.sectors = 128; + geometry.pagesPerSector = 256; + break; + case JEDEC_ID_MICRON_N25Q128: + case JEDEC_ID_WINBOND_W25Q128: + geometry.sectors = 256; + geometry.pagesPerSector = 256; + break; + default: + // Unsupported chip or not an SPI NOR flash + geometry.sectors = 0; + geometry.pagesPerSector = 0; + + geometry.sectorSize = 0; + geometry.totalSize = 0; + return false; + } + + geometry.sectorSize = geometry.pagesPerSector * geometry.pageSize; + geometry.totalSize = geometry.sectorSize * geometry.sectors; + + couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be + + return true; +} + +/** + * Initialize the driver, must be called before any other routines. + * + * Attempts to detect a connected m25p16. If found, true is returned and device capacity can be fetched with + * m25p16_getGeometry(). + */ +bool m25p16_init() +{ + //Maximum speed for standard READ command is 20mHz, other commands tolerate 25mHz + spiSetDivisor(M25P16_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); + + return m25p16_readIdentification(); +} + +/** + * Erase a sector full of bytes to all 1's at the given byte offset in the flash chip. + */ +void m25p16_eraseSector(uint32_t address) +{ + uint8_t out[] = { M25P16_INSTRUCTION_SECTOR_ERASE, (address >> 16) & 0xFF, (address >> 8) & 0xFF, address & 0xFF}; + + m25p16_waitForReady(SECTOR_ERASE_TIMEOUT_MILLIS); + + m25p16_writeEnable(); + + ENABLE_M25P16; + + spiTransfer(M25P16_SPI_INSTANCE, NULL, out, sizeof(out)); + + DISABLE_M25P16; +} + +void m25p16_eraseCompletely() +{ + m25p16_waitForReady(BULK_ERASE_TIMEOUT_MILLIS); + + m25p16_writeEnable(); + + m25p16_performOneByteCommand(M25P16_INSTRUCTION_BULK_ERASE); +} + +void m25p16_pageProgramBegin(uint32_t address) +{ + uint8_t command[] = { M25P16_INSTRUCTION_PAGE_PROGRAM, (address >> 16) & 0xFF, (address >> 8) & 0xFF, address & 0xFF}; + + m25p16_waitForReady(DEFAULT_TIMEOUT_MILLIS); + + m25p16_writeEnable(); + + ENABLE_M25P16; + + spiTransfer(M25P16_SPI_INSTANCE, NULL, command, sizeof(command)); +} + +void m25p16_pageProgramContinue(const uint8_t *data, int length) +{ + spiTransfer(M25P16_SPI_INSTANCE, NULL, data, length); +} + +void m25p16_pageProgramFinish() +{ + DISABLE_M25P16; +} + +/** + * Write bytes to a flash page. Address must not cross a page boundary. + * + * Bits can only be set to zero, not from zero back to one again. In order to set bits to 1, use the erase command. + * + * Length must be smaller than the page size. + * + * This will wait for the flash to become ready before writing begins. + * + * Datasheet indicates typical programming time is 0.8ms for 256 bytes, 0.2ms for 64 bytes, 0.05ms for 16 bytes. + * (Although the maximum possible write time is noted as 5ms). + * + * If you want to write multiple buffers (whose sum of sizes is still not more than the page size) then you can + * break this operation up into one beginProgram call, one or more continueProgram calls, and one finishProgram call. + */ +void m25p16_pageProgram(uint32_t address, const uint8_t *data, int length) +{ + m25p16_pageProgramBegin(address); + + m25p16_pageProgramContinue(data, length); + + m25p16_pageProgramFinish(); +} + +/** + * Read `length` bytes into the provided `buffer` from the flash starting from the given `address` (which need not lie + * on a page boundary). + * + * Waits up to DEFAULT_TIMEOUT_MILLIS milliseconds for the flash to become ready before reading. + * + * The number of bytes actually read is returned, which can be zero if an error or timeout occurred. + */ +int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length) +{ + uint8_t command[] = { M25P16_INSTRUCTION_READ_BYTES, (address >> 16) & 0xFF, (address >> 8) & 0xFF, address & 0xFF}; + + if (!m25p16_waitForReady(DEFAULT_TIMEOUT_MILLIS)) { + return 0; + } + + ENABLE_M25P16; + + spiTransfer(M25P16_SPI_INSTANCE, NULL, command, sizeof(command)); + spiTransfer(M25P16_SPI_INSTANCE, buffer, NULL, length); + + DISABLE_M25P16; + + return length; +} + +/** + * Fetch information about the detected flash chip layout. + * + * Can be called before calling m25p16_init() (the result would have totalSize = 0). + */ +const flashGeometry_t* m25p16_getGeometry() +{ + return &geometry; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_m25p16.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_m25p16.h new file mode 100644 index 0000000..d9708ea --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_m25p16.h @@ -0,0 +1,45 @@ +/* + drv_m25p16.h : function prototypes for Micron Technology MP25P16 flash memory + + Adapted from https://github.com/cleanflight/cleanflight/blob/master/src/main/drivers/flash_m25p16.h + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#pragma once + +#include +#include "drv_flash.h" + +#define M25P16_PAGESIZE 256 + +bool m25p16_init(); + +void m25p16_eraseSector(uint32_t address); +void m25p16_eraseCompletely(); + +void m25p16_pageProgram(uint32_t address, const uint8_t *data, int length); + +void m25p16_pageProgramBegin(uint32_t address); +void m25p16_pageProgramContinue(const uint8_t *data, int length); +void m25p16_pageProgramFinish(); + +int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length); + +bool m25p16_isReady(); +bool m25p16_waitForReady(uint32_t timeoutMillis); + +const flashGeometry_t* m25p16_getGeometry(); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mb1030.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mb1030.c new file mode 100644 index 0000000..5147c5c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mb1030.c @@ -0,0 +1,35 @@ +#include +#include +#include + +#include "stm32f10x_conf.h" +#include "core_cm3.h" + +#include "drv_gpio.h" +#include "drv_timer.h" +#include "drv_pwm.h" + +typedef struct{ + TIM_TypeDef *tim; + GPIO_TypeDef *gpio; + uint32_t pin; + uint8_t channel; + uint8_t irq; +} sonar_t; + +static sonar_t sonar_hardware[6] = { + { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn }, // RC2 + { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn }, // RC3 + { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn }, // RC4 + { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn }, // RC5 + { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn }, // RC6 + { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn }, // RC7 +}; + +void mb1030_init() +{ + for(int i = 0; i < 6; i++) + { + pwmGPIOConfig(sonar_hardware[i].gpio, sonar_hardware[i].pin, Mode_IPD); + pwmICConfig(sonar_hardware[i].tim, sonar_hardware[i].channel, TIM_ICPolarity_Rising); +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mb1030.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mb1030.h new file mode 100644 index 0000000..33fb604 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mb1030.h @@ -0,0 +1,4 @@ +#ifndef DRV_MB1030_H +#define DRV_MB1030_H + +#endif // DRV_MB1030_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mb1242.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mb1242.c new file mode 100644 index 0000000..fb96ee8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mb1242.c @@ -0,0 +1,154 @@ +/* + drv_mb1242.c : driver for MaxBotix MB1242 sonar + + Copyright (C) 2016 Simon D. Levy + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include + +#include +#include + +#include "drv_i2c.h" + +#define MB1242_DEFAULT_ADDRESS 0x70 + +static uint8_t start_measurement_command = 0x51; +static uint8_t read_buffer[2] = {0,0}; +static volatile uint8_t start_measurement_status; +static volatile uint8_t read_measurement_status; +static uint8_t state = 0; +static uint64_t last_update_time_us; +static int32_t distance_cm; + + +bool mb1242_init() +{ + return i2cWrite(MB1242_DEFAULT_ADDRESS, 0xFF, start_measurement_command); +} + + +void start_sonar_measurement_CB(void) +{ + // indicate a completed started measurement + state = 1; +} + + +void mb1242_update() +{ + uint64_t now_us = micros(); + if (now_us > last_update_time_us + 25000) + { + last_update_time_us = now_us; + if (state == 0) + { + // Start a sonar measurement, + i2cWrite(MB1242_DEFAULT_ADDRESS, 0xFF, start_measurement_command); + state = 1; + } + else if (state == 1) { + read_buffer[0] = 0; + read_buffer[1] = 0; + // Read the sonar measurement + i2cRead(MB1242_DEFAULT_ADDRESS, 0xFF, 2, read_buffer); + + // convert to cm + distance_cm = (read_buffer[0] << 8) + read_buffer[1]; + if (distance_cm > 850) + { + distance_cm = 0; + } + state = 0; + } + } +} + +float mb1242_read() +{ + return (1.071 * (float)distance_cm + 3.103)/100.0; // emprically determined +} + + +//============================================= +// Asynchronus data storage +static uint8_t buf[2]; +static volatile uint8_t read_status; +static float distance; +static bool new_data = false; +static bool sensor_present = false; + +void mb1242_start_read_CB(void) +{ + if (read_status != I2C_JOB_ERROR) + { + sensor_present = true; + } +} + +void mb1242_read_CB(void) +{ + if (read_status != I2C_JOB_ERROR) + { + sensor_present = true; + new_data = true; + } +} + + +void mb1242_async_update() +{ + uint64_t now_ms = millis(); + if (now_ms > last_update_time_us + 25) // 40 Hz update rate + { + last_update_time_us = now_ms; + if (state == 0) + { + // Start a sonar measurement, + i2c_queue_job(WRITE, MB1242_DEFAULT_ADDRESS, 0xFF, &start_measurement_command, 1, + &read_status, &mb1242_start_read_CB); + state = 1; + } + else if (state == 1) { + // Read the sonar measurement + i2c_queue_job(READ, MB1242_DEFAULT_ADDRESS, 0xFF, buf, 2, &read_status, &mb1242_read_CB); + state = 0; + } + } +} + +float mb1242_async_read() +{ + if (new_data) + { + // convert to cm + distance_cm = (buf[0] << 8) + buf[1]; + if (distance_cm > 850) + { + distance_cm = 0; + } + distance = (1.071 * (float)distance_cm + 3.103)/100.0; // emprically determined + } + return distance; +} + +bool mb1242_present() +{ + return sensor_present; +} + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mb1242.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mb1242.h new file mode 100644 index 0000000..4f86351 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mb1242.h @@ -0,0 +1,33 @@ +/* + drv_mb1242.h : driver for MaxBotix MB1242 sonar + + Copyright (C) 2016 Simon D. Levy + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#pragma once + +bool mb1242_init(); + +// Blocking Methods +void mb1242_update(); +float mb1242_read(); + +// Asynchronous Methods +void mb1242_async_update(); +float mb1242_async_read(); +bool mb1242_present(); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mpu6050.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mpu6050.c new file mode 100644 index 0000000..23cd6ce --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mpu6050.c @@ -0,0 +1,356 @@ +/* + drv_mpu6050.c : driver for Invensense MPU6050 + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_mpu.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + + +#include + +#include + +#ifndef M_PI +#define M_PI 3.14159 +#endif + +/* Generic driver for invensense gyro/acc devices. + * + * Supported hardware: + * MPU6050 (gyro + acc) + * + * AUX_I2C is enabled on devices which have bypass, to allow forwarding to compass in MPU9150-style devices + */ + +// This is generally where all Invensense devices are at, for default (AD0 down) I2C address +#define MPU_ADDRESS (0x68) + +#define GYRO_INT_PIN (Pin_13) + +#define MPU_RA_WHO_AM_I (0x75) +#define MPU_RA_GYRO_XOUT_H (0x43) +#define MPU_RA_ACCEL_XOUT_H (0x3B) +#define MPU_RA_TEMP_OUT_A (0x41) +// For debugging/identification purposes +#define MPU_RA_XA_OFFS_H (0x06) //[15:0] XA_OFFS +#define MPU_RA_PRODUCT_ID (0x0C) // Product ID Register + +// WHO_AM_I register contents for 6050 +#define MPUx0x0_WHO_AM_I_CONST (0x68) + +enum lpf_e { + INV_FILTER_256HZ_NOLPF2 = 0, + INV_FILTER_188HZ, + INV_FILTER_98HZ, + INV_FILTER_42HZ, + INV_FILTER_20HZ, + INV_FILTER_10HZ, + INV_FILTER_5HZ, + INV_FILTER_2100HZ_NOLPF, + NUM_FILTER +}; + +enum gyro_fsr_e { + INV_FSR_250DPS = 0, + INV_FSR_500DPS, + INV_FSR_1000DPS, + INV_FSR_2000DPS, + NUM_GYRO_FSR +}; + +enum clock_sel_e { + INV_CLK_INTERNAL = 0, + INV_CLK_PLL, + NUM_CLK +}; + +enum accel_fsr_e { + INV_FSR_2G = 0, + INV_FSR_4G, + INV_FSR_8G, + INV_FSR_16G, + NUM_ACCEL_FSR +}; + + +// Lowpass +static uint8_t mpuLowPassFilter = INV_FILTER_20HZ; + +// Timestamp +static uint64_t imu_time_us = 0; +static bool new_imu_data = false; + +// MPU6xxx registers +#define MPU_RA_SMPLRT_DIV 0x19 +#define MPU_RA_CONFIG 0x1A +#define MPU_RA_GYRO_CONFIG 0x1B +#define MPU_RA_ACCEL_CONFIG 0x1C +#define MPU_RA_FIFO_EN 0x23 +#define MPU_RA_I2C_MST_CTRL 0x24 +#define MPU_RA_INT_PIN_CFG 0x37 +#define MPU_RA_INT_ENABLE 0x38 +#define MPU_RA_SIGNAL_PATH_RST 0x68 +#define MPU_RA_USER_CTRL 0x6A +#define MPU_RA_PWR_MGMT_1 0x6B +#define MPU_RA_PWR_MGMT_2 0x6C +#define MPU_RA_FIFO_COUNT_H 0x72 +#define MPU_RA_FIFO_R_W 0x74 + +// MPU6050 bits +#define MPU6050_INV_CLK_GYROZ 0x03 +#define MPU6050_BIT_FIFO_RST 0x04 +#define MPU6050_BIT_DMP_RST 0x08 +#define MPU6050_BIT_FIFO_EN 0x40 + +static bool mpuReadRegisterI2C(uint8_t reg, uint8_t *data, int length) +{ + return i2cRead(MPU_ADDRESS, reg, length, data); +} + +static bool mpuWriteRegisterI2C(uint8_t reg, uint8_t data) +{ + return i2cWrite(MPU_ADDRESS, reg, data); +} + +void mpu6050_exti_init(int boardVersion) +{ + // enable AFIO for EXTI support + RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE); + + // Configure EXTI + EXTI_ClearITPendingBit(EXTI_Line13); + EXTI_InitTypeDef EXTI_InitStructure; + // GPIO Structure Used To initialize external interrupt pin + // This assumes that the interrupt pin is attached to pin 26 (PB13) + // Which is not be the case for all boards. The naze32 rev5+ has it's + // interrupt on PC13, while rev4- and the flip32 devices use PB13. + // see src/main/sensors/initializiation.c:85 in the cleanflight source code + // for their version handling. + if (boardVersion > 4) { + gpioExtiLineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource13); + } else { + gpioExtiLineConfig(GPIO_PortSourceGPIOB, GPIO_PinSource13); + } + + // Configure EXTI Line13 + EXTI_InitStructure.EXTI_Line = EXTI_Line13; + EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; + EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising; + EXTI_InitStructure.EXTI_LineCmd = ENABLE; + EXTI_Init(&EXTI_InitStructure); + + // Disable AFIO Clock - we don't need it anymore + RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, DISABLE); + + // Configure NVIC (Nested Vector Interrupt Controller) + NVIC_InitTypeDef NVIC_InitStructure; + // Select NVIC Channel to configure + NVIC_InitStructure.NVIC_IRQChannel = EXTI15_10_IRQn; + // Set priority to lowest + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 7; + // Set subpriority to lowest + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + // Update NVIC registers + NVIC_Init(&NVIC_InitStructure); + // NVIC_SetPriority(EXTI15_10_IRQn, 1); +} + + +// ====================================================================== +void mpu6050_init(bool enableInterrupt, uint16_t * acc1G, float * gyroScale, int boardVersion) +{ + gpio_config_t gpio; + + // Set acc1G. Modified once by mpu6050CheckRevision for old (hopefully nonexistent outside of clones) parts + *acc1G = 512 * 8; + + // 16.4 dps/lsb scalefactor for all Invensense devices + *gyroScale = (1.0f / 16.4f) * (M_PI / 180.0f); + + // MPU_INT output on rev5+ hardware (PC13) + if (enableInterrupt) { + gpio.pin = Pin_13; + gpio.speed = Speed_2MHz; + gpio.mode = Mode_IN_FLOATING; + if (boardVersion > 4){ + gpioInit(GPIOC, &gpio); + } else { + gpioInit(GPIOB, &gpio); + } + mpu6050_exti_init(boardVersion); + } + + // Device reset + mpuWriteRegisterI2C(MPU_RA_PWR_MGMT_1, 0x80); // Device reset + delay(30); // wait for reboot + + // Gyro config + mpuWriteRegisterI2C(MPU_RA_SMPLRT_DIV, 0x00); // Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV) + mpuWriteRegisterI2C(MPU_RA_PWR_MGMT_1, MPU6050_INV_CLK_GYROZ); // Clock source = 3 (PLL with Z Gyro reference) + mpuWriteRegisterI2C(MPU_RA_CONFIG, mpuLowPassFilter); // set DLPF + mpuWriteRegisterI2C(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3); // full-scale 2kdps gyro range + + // Accel scale 8g (4096 LSB/g) + mpuWriteRegisterI2C(MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3); + + // Data ready interrupt configuration: INT_RD_CLEAR_DIS, I2C_BYPASS_EN + mpuWriteRegisterI2C(MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); + mpuWriteRegisterI2C(MPU_RA_INT_ENABLE, 0x01); // DATA_RDY_EN interrupt enable +} + +void mpu6050_read_all(int16_t *accData, int16_t *gyroData, int16_t* tempData, uint64_t *time_us) +{ + uint8_t buf[14]; + + mpuReadRegisterI2C(MPU_RA_ACCEL_XOUT_H, buf, 14); + + accData[0] = (int16_t)((buf[0] << 8) | buf[1]); + accData[1] = (int16_t)((buf[2] << 8) | buf[3]); + accData[2] = (int16_t)((buf[4] << 8) | buf[5]); + + (*tempData) = (int16_t)((buf[6] << 8) | buf[7]); + + gyroData[0] = (int16_t)((buf[8] << 8) | buf[9]); + gyroData[1] = (int16_t)((buf[10] << 8) | buf[11]); + gyroData[2] = (int16_t)((buf[12] << 8) | buf[13]); + + (*time_us) = imu_time_us; +} + + +void mpu6050_read_accel(int16_t *accData) +{ + uint8_t buf[6]; + + if (mpuReadRegisterI2C(MPU_RA_ACCEL_XOUT_H, buf, 6)) + { + + accData[0] = (int16_t)((buf[0] << 8) | buf[1]); + accData[1] = (int16_t)((buf[2] << 8) | buf[3]); + accData[2] = (int16_t)((buf[4] << 8) | buf[5]); + } +} + + +void mpu6050_read_gyro(int16_t *gyroData) +{ + uint8_t buf[6]; + + mpuReadRegisterI2C(MPU_RA_GYRO_XOUT_H, buf, 6); + + gyroData[0] = (int16_t)((buf[0] << 8) | buf[1]); + gyroData[1] = (int16_t)((buf[2] << 8) | buf[3]); + gyroData[2] = (int16_t)((buf[4] << 8) | buf[5]); +} + +void mpu6050_read_temperature(int16_t *tempData) +{ + uint8_t buf[2]; + + mpuReadRegisterI2C(MPU_RA_TEMP_OUT_A, buf, 2); + + *tempData = (int16_t)((buf[0] << 8) | buf[1]) / 4; +} + + +/*======================================================= + * Asynchronous I2C Read Functions: + * These methods use the asynchronous I2C + * read capability on the naze32. + */ +static volatile int16_t accel[3]; +static volatile int16_t gyro[3]; +static volatile int16_t temp; +static volatile bool need_to_queue_new_i2c_job = false; +uint8_t all_buffer[14]; +uint64_t measurement_time = 0; + +void read_all_CB(void) +{ + accel[0] = (int16_t)((all_buffer[0] << 8) | all_buffer[1]); + accel[1] = (int16_t)((all_buffer[2] << 8) | all_buffer[3]); + accel[2] = (int16_t)((all_buffer[4] << 8) | all_buffer[5]); + + temp = (int16_t)((all_buffer[6] << 8) | all_buffer[7]); + + gyro[0] = (int16_t)((all_buffer[8] << 8) | all_buffer[9]); + gyro[1] = (int16_t)((all_buffer[10] << 8) | all_buffer[11]); + gyro[2] = (int16_t)((all_buffer[12] << 8) | all_buffer[13]); + + new_imu_data = true; + measurement_time = imu_time_us; +} + +void mpu6050_request_async_update_all() +{ + // Adds a new i2c job to the I2C job queue. + // Current status of the job can be read by polling the + // status variable, and the callback will be called when the function + // is finished + i2c_queue_job(READ, + MPU_ADDRESS, + MPU_RA_ACCEL_XOUT_H, + all_buffer, + 14, + NULL, + &read_all_CB); +} + + +void mpu6050_async_read_all(volatile int16_t *accData, volatile int16_t *tempData, volatile int16_t *gyroData, volatile uint64_t* timeData) +{ + accData[0] = accel[0]; + accData[1] = accel[1]; + accData[2] = accel[2]; + (*tempData) = temp; + gyroData[0] = gyro[0]; + gyroData[1] = gyro[1]; + gyroData[2] = gyro[2]; + (*timeData) = measurement_time; +} + +bool mpu6050_new_data() +{ + if (need_to_queue_new_i2c_job) + { + mpu6050_request_async_update_all(); + need_to_queue_new_i2c_job = false; + } + + if (new_imu_data) + { + new_imu_data = false; + return true; + } + return false; +} + +//===================================================================================== + +void EXTI15_10_IRQHandler(void) +{ + if (EXTI_GetITStatus(EXTI_Line13) != RESET) + { + imu_time_us = micros(); + need_to_queue_new_i2c_job = true; + } + EXTI_ClearITPendingBit(EXTI_Line13); +} + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mpu6050.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mpu6050.h new file mode 100644 index 0000000..0245492 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_mpu6050.h @@ -0,0 +1,41 @@ +/* + drv_mpu6050.h : driver for Invensense MPU6050 + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_mpu.h + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include "drv_i2c.h" + +#pragma once + + +void mpu6050_init(bool enableInterrupt, uint16_t * acc1G, float * gyroScale, int boardVersion); +void mpu6050_register_interrupt_cb(void (*functionPtr)(void)); + +// Blocking Read Functions +bool mpu6050_new_data(); +void mpu6050_read_all(int16_t *accData, int16_t *gyroData, int16_t* tempData, uint64_t* time_us); +void mpu6050_read_accel(int16_t *accData); +void mpu6050_read_gyro(int16_t *gyroData); +void mpu6050_read_temperature(int16_t * tempData); + +// Asynchronous Read Functions +void mpu6050_request_async_accel_read(int16_t *accData, volatile uint8_t *status_); +void mpu6050_request_async_gyro_read(int16_t *gyroData, volatile uint8_t *status_); +void mpu6050_request_async_temp_read(volatile int16_t *tempData, volatile uint8_t *status_); +void mpu6050_async_read_all(volatile int16_t *accData, volatile int16_t *tempData, volatile int16_t *gyroData, volatile uint64_t *timeData); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_ms4525.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_ms4525.c new file mode 100644 index 0000000..66dfe08 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_ms4525.c @@ -0,0 +1,168 @@ +/* + drv_ms4525.c : driver for MS4525 differential pressure sensor + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + + +#include + +// MS4525 address 0x28 for most common version +#define MS4525_ADDR 0x28 +#define STATUS_MASK 0x3F + +#define FILTERING4525_ADC_MIN 0.001 // +#define FILTERING4525_ADC_MAX 0.01 // +#define FILTERING4525_ADC_MIN_AT 10 // when abs(delta between ADC and current value) is less than MIN_AT , apply MIN +#define FILTERING4525_ADC_MAX_AT 100 // when abs(delta between ADC and current value) is more than MAX_AT , apply MAX (interpolation in between) + +uint32_t polling_interval_ms = 20; // (ms) +uint32_t last_measurement_time_ms = 0; + +static float temp = 0.0f; +static float raw_diff_pressure_Pa = 0.0f; +static float diff_pressure_abs_Pa = 0.0f; +static float diff_pressure_smooth_Pa = 0.0f; + +static bool calibrated = true; +static volatile float diff_pressure_offset = 0.0f; + +static inline float sign(float x) +{ + return (x > 0) - (x < 0); +} + +bool ms4525_calibrated() +{ + return calibrated; +} + + + +bool ms4525_init(void) +{ + uint8_t buf[1]; + bool airspeed_present = false; + airspeed_present |= i2cRead(MS4525_ADDR, 0xFF, 1, buf); + calibrated = false; + return airspeed_present; +} + + +void ms4525_update() +{ + uint8_t buf[4]; + + uint32_t now_ms = millis(); + if(now_ms > last_measurement_time_ms + polling_interval_ms) + { + last_measurement_time_ms = now_ms; + i2cRead(MS4525_ADDR, 0xFF, 4, buf); + + uint8_t status = (buf[0] & 0xC0) >> 6; + if(status == 0x00) // good data packet + { + int16_t raw_diff_pressure = 0x3FFF & ((buf[0] << 8) + buf[1]); + int16_t raw_temp = ( 0xFFE0 & ((buf[2] << 8) + buf[3])) >> 5; + + // Convert to Pa and K + raw_diff_pressure_Pa = -(((float)raw_diff_pressure - 1638.3f) / 6553.2f - 1.0f) * 6894.757; + temp = (0.097703957f * raw_temp) + 223.0; // K + + // Filter diff pressure measurement + float LPF_alpha = 0.1; + diff_pressure_abs_Pa = raw_diff_pressure_Pa - diff_pressure_offset; + diff_pressure_smooth_Pa += LPF_alpha * (diff_pressure_abs_Pa - diff_pressure_smooth_Pa); + } + else // stale data packet - ignore + { + return; + } + } +} + +void ms4525_read(float *diff_press, float *temperature) +{ + (*temperature) = temp; + (*diff_press) = diff_pressure_smooth_Pa; +} + +//================================================= +// Asynchronus data storage +static uint8_t buf[4] = {0, 0, 0, 0}; +static volatile uint8_t read_status; +static bool new_data = false; +static bool sensor_present = false; + +void ms4525_read_CB(void) +{ + if (read_status != I2C_JOB_ERROR) + { + new_data = true; + sensor_present = true; + } +} + +bool ms4525_present(void) +{ + return sensor_present; +} + +void ms4525_async_read(float* diff_press, float* temperature) +{ + if (new_data) + { + uint8_t status = (buf[0] & 0xC0) >> 6; + if(status == 0x00) // good data packet + { + int16_t raw_diff_pressure = 0x3FFF & ((buf[0] << 8) + buf[1]); + int16_t raw_temp = ( 0xFFE0 & ((buf[2] << 8) + buf[3])) >> 5; + // Convert to Pa and K + raw_diff_pressure_Pa = -(((float)raw_diff_pressure - 1638.3f) / 6553.2f - 1.0f) * 6894.757; + temp = (0.097703957f * raw_temp) + 223.0; // K + + // Filter diff pressure measurement + float LPF_alpha = 0.85; + diff_pressure_abs_Pa = raw_diff_pressure_Pa - diff_pressure_offset; + diff_pressure_smooth_Pa = (1.0-LPF_alpha) * diff_pressure_abs_Pa + LPF_alpha * diff_pressure_smooth_Pa; + } + else // stale data packet - ignore + { + return; + } + } + (*temperature) = temp; + (*diff_press) = diff_pressure_smooth_Pa; +} + + +void ms4525_async_update(void) +{ + static uint64_t next_update_ms = 0; + uint64_t now_ms = millis(); + + // if it's not time to do anything, just return + if (now_ms < next_update_ms) + { + return; + } + else + { + i2c_queue_job(READ, MS4525_ADDR, 0xFF, buf, 4, &read_status, &ms4525_read_CB); + next_update_ms += 1; // Poll at 1000 Hz + } + return; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_ms4525.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_ms4525.h new file mode 100644 index 0000000..39fdd2f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_ms4525.h @@ -0,0 +1,34 @@ +/* + drv_ms4525.h : driver for MS4525 Differential Pressure Sensor + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ +#include + +#pragma once + +bool ms4525_init(void); + +// Blocking I2C function +void ms4525_update(); +void ms4525_read(float *differential_pressure, float *temp); +void ms4525_start_calibration(); +bool ms4525_calibrated(); + +// Asynchronous I2C function +bool ms4525_present(void); +void ms4525_async_update(void); +void ms4525_async_read(float *diff_press, float *temperature); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_ms5611.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_ms5611.c new file mode 100644 index 0000000..e679f6b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_ms5611.c @@ -0,0 +1,360 @@ +/* + drv_ms5611.c : driver for Measurement Specialties MS5611 barometer + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_ms5611.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + + +#include +#include + +// MS5611, Standard address 0x77 +#define MS5611_ADDR 0x77 + +#define CMD_RESET 0x1E // ADC reset command +#define CMD_ADC_READ 0x00 // ADC read command +#define CMD_ADC_CONV 0x40 // ADC conversion command +#define CMD_ADC_D1 0x00 // ADC D1 conversion +#define CMD_ADC_D2 0x10 // ADC D2 conversion +#define CMD_ADC_256 0x00 // ADC OSR=256 +#define CMD_ADC_512 0x02 // ADC OSR=512 +#define CMD_ADC_1024 0x04 // ADC OSR=1024 +#define CMD_ADC_2048 0x06 // ADC OSR=2048 +#define CMD_ADC_4096 0x08 // ADC OSR=4096 +#define CMD_PROM_RD 0xA0 // Prom read command +#define PROM_NB 8 + +static uint32_t ms5611_ut; // static result of temperature measurement +static uint32_t ms5611_up; // static result of pressure measurement +static uint16_t ms5611_c[PROM_NB]; // on-chip ROM +static uint8_t ms5611_osr = CMD_ADC_4096; +float pressure = 0.0; +float temperature = 0.0; +static uint8_t init_state = 0; + +static void ms5611_reset(void) +{ + i2cWrite(MS5611_ADDR, CMD_RESET, 1); + delayMicroseconds(2800); +} + +static uint16_t ms5611_prom(int8_t coef_num) +{ + uint8_t rxbuf[2] = { 0, 0 }; + i2cRead(MS5611_ADDR, CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command + return rxbuf[0] << 8 | rxbuf[1]; +} + +int8_t ms5611_crc(uint16_t *prom) +{ + int32_t i, j; + uint32_t res = 0; + uint8_t crc = prom[7] & 0xF; + prom[7] &= 0xFF00; + + bool blankEeprom = true; + + for (i = 0; i < 16; i++) { + if (prom[i >> 1]) { + blankEeprom = false; + } + if (i & 1) + res ^= ((prom[i >> 1]) & 0x00FF); + else + res ^= (prom[i >> 1] >> 8); + for (j = 8; j > 0; j--) { + if (res & 0x8000) + res ^= 0x1800; + res <<= 1; + } + } + prom[7] |= crc; + if (!blankEeprom && crc == ((res >> 12) & 0xF)) + return 0; + + return -1; +} + +static uint32_t ms5611_read_adc(void) +{ + uint8_t rxbuf[3]; + i2cRead(MS5611_ADDR, CMD_ADC_READ, 3, rxbuf); // read ADC + return (rxbuf[0] << 16) | (rxbuf[1] << 8) | rxbuf[2]; +} + +static void ms5611_start_ut(void) +{ + i2cWrite(MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start! +} + +static void ms5611_get_ut(void) +{ + ms5611_ut = ms5611_read_adc(); +} + +static void ms5611_start_up(void) +{ + i2cWrite(MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D1 + ms5611_osr, 1); // D1 (pressure) conversion start! +} + +static void ms5611_get_up(void) +{ + ms5611_up = ms5611_read_adc(); +} + +static void ms5611_calculate() +{ + int32_t press = 0; + int64_t temp = 0; + int64_t delt = 0; + if(ms5611_up > 9085466 * 2 / 3 && ms5611_ut > 0) + { + int64_t dT = (int64_t)ms5611_ut - ((int64_t)ms5611_c[5] << 8); + int64_t off = ((int64_t)ms5611_c[2] << 16) + (((int64_t)ms5611_c[4] * dT) >> 7); + int64_t sens = ((int64_t)ms5611_c[1] << 15) + (((int64_t)ms5611_c[3] * dT) >> 8); + temp = 2000 + ((dT * (int64_t)ms5611_c[6]) >> 23); + + if (temp < 2000) { // temperature lower than 20degC + delt = temp - 2000; + delt = 5 * delt * delt; + off -= delt >> 1; + sens -= delt >> 2; + if (temp < -1500) { // temperature lower than -15degC + delt = temp + 1500; + delt = delt * delt; + off -= 7 * delt; + sens -= (11 * delt) >> 1; + } + temp -= ((dT * dT) >> 31); + } + press = ((((uint64_t)ms5611_up * sens) >> 21) - off) >> 15; + + pressure = (float)press; // Pa + temperature = (float)temp/ 100.0 + 273.0; // K + +// float pre_adjust_altitude = fast_alt(pressure); + +// altitude = fast_alt(pressure) - offset; + } +} + + +// ======================================================================================= + +bool ms5611_init(void) +{ + bool ack = false; + uint8_t sig; + int i; + + while(millis() < 10); // No idea how long the chip takes to power-up, but let's make it 10ms + + ack = i2cRead(MS5611_ADDR, CMD_PROM_RD, 1, &sig); + if (!ack) + return false; + else + init_state = 1; + + ms5611_reset(); + + init_state = 2; + + // read all coefficients + for (i = 0; i < PROM_NB; i++) + ms5611_c[i] = ms5611_prom(i); + // check crc, bail out if wrong + if (ms5611_crc(ms5611_c) != 0) + return false; + + return true; +} + +void ms5611_update(void) +{ + static uint32_t next_time_ms = 0; + static int state = 0; + + if(millis() > next_time_ms) + { + if (state) + { + ms5611_get_up(); + ms5611_start_ut(); + next_time_ms += 10; + state = 0; + } + else + { + ms5611_get_ut(); + ms5611_start_up(); + state = 1; + next_time_ms += 10; + ms5611_calculate(); + } + } +} + +void ms5611_read(float* press, float* temp) +{ + (*press) = pressure; + (*temp) = temperature; +} + + +//=================================================================== +// ASYNC FUNCTIONS +static uint8_t pressure_buffer[3]; +static uint8_t temp_buffer[3]; + +static uint8_t temp_command = 1; +static uint8_t pressure_command = 1; +static volatile uint8_t temp_start_status = 0; +static volatile uint8_t temp_read_status = 0; +static volatile uint8_t pressure_read_status = 0; +static volatile uint8_t pressure_start_status = 0; +static volatile uint8_t baro_state = 0; +static volatile uint32_t next_update_ms = 0; + +static volatile uint8_t init_status; +static uint8_t init_command; + +void ms5611_init_CB(void) +{ + // we successfully found the sensor + if (init_status == I2C_JOB_COMPLETE) + { + init_state ++; + next_update_ms = millis() + 30; + } +} + +void temp_request_CB(void) +{ + next_update_ms = millis() + 15; +} + +void pressure_request_CB(void) +{ + next_update_ms = millis() + 15; +} + +void pressure_read_CB(void) +{ + ms5611_up = (pressure_buffer[0] << 16) | (pressure_buffer[1] << 8) | pressure_buffer[2]; +} + +static void temp_read_CB(void) +{ + ms5611_ut = (temp_buffer[0] << 16) | (temp_buffer[1] << 8) | temp_buffer[2]; +} + +void ms5611_async_update(void) +{ + uint32_t now_ms = millis(); + // if it's not time to do anything, just return + if (now_ms < next_update_ms) + { + return; + } + else + { + // this may be reduced by an i2c callback, but at the very least, monitor at 10 Hz + next_update_ms += 100; + } + + // Try to initialize the sensor if we haven't already + if (init_state < 2) + { + if (init_state == 0) + { + init_command = 1; + i2c_queue_job(READ, MS5611_ADDR, CMD_PROM_RD, &init_command, 1, &init_status, ms5611_init_CB); + return; + } + else if (init_state == 1) + { + init_command = 1; + i2c_queue_job(READ, MS5611_ADDR, CMD_RESET, &init_command, 1, &init_status, ms5611_init_CB); + return; + } + } + + switch (baro_state) + { + case 0: + // Read the pressure + i2c_queue_job(READ, + MS5611_ADDR, + CMD_ADC_READ, + pressure_buffer, + 3, + &pressure_read_status, + &pressure_read_CB); +// baro_state++; +// break; +// case 1: + // start a temp conversion + i2c_queue_job(WRITE, + MS5611_ADDR, + CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, + &temp_command, + 1, + &temp_start_status, + &temp_request_CB); + baro_state = 1; + break; + case 1: + // Read the temperature + i2c_queue_job(READ, + MS5611_ADDR, + CMD_ADC_READ, + temp_buffer, + 3, + &temp_read_status, + &temp_read_CB); +// baro_state = 0; +// break; +// case 3: + // start a pressure conversion + i2c_queue_job(WRITE, + MS5611_ADDR, + CMD_ADC_CONV + CMD_ADC_D1 + ms5611_osr, + &pressure_command, + 1, + &pressure_start_status, + &pressure_request_CB); + baro_state = 0; + break; + default: + baro_state = 0; + break; + } + + ms5611_calculate(); +} + +bool ms5611_present() +{ + return init_state > 0; +} + +void ms5611_async_read(float* press, float* temp) +{ + (*press) = pressure; + (*temp) = temperature; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_ms5611.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_ms5611.h new file mode 100644 index 0000000..a319177 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_ms5611.h @@ -0,0 +1,33 @@ +/* + drv_ms5611.h : driver for Measurement Specialties MS5611 barometer + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_ms5611.h + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#pragma once + +bool ms5611_init(void); + +// blocking I2C update function +void ms5611_update(void); +void ms5611_read(float* pressure, float* temperature); + +// Asynchronous ms5611 functions +bool ms5611_present(void); +void ms5611_async_update(void); +void ms5611_async_read(float* pressure, float* temperature); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_pwm.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_pwm.c new file mode 100644 index 0000000..a9f7dc6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_pwm.c @@ -0,0 +1,436 @@ +/* + drv_pwm.c : PWM support for STM32F103CB + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_pwm.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + + +/* + Configuration maps: + + 1) multirotor PPM input + PWM1 used for PPM + PWM5..8 used for motors + PWM9..10 used for motors + PWM11..14 used for motors + + 2) multirotor PWM input + PWM1..8 used for input + PWM9..10 used for motors + PWM11..14 used for motors + */ + +#include +#include +#include + +#include "stm32f10x_conf.h" + +#include "drv_gpio.h" +#include "drv_timer.h" +#include "drv_pwm.h" +#include "drv_system.h" + +typedef struct { + volatile uint16_t *ccr; + volatile uint16_t *cr1; + volatile uint16_t *cnt; + uint16_t period; + + // for input only + uint8_t channel; + uint8_t state; + uint16_t rise; + uint16_t fall; + uint16_t capture; +} pwmPortData_t; + +static uint8_t sonar_trigger_port; + +typedef void (*pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function pointer used to write motors + +static pwmPortData_t pwmPorts[MAX_PORTS]; +static uint16_t captures[MAX_INPUTS]; +static uint16_t sonar_reads[MAX_INPUTS]; +static pwmWriteFuncPtr pwmWritePtr = NULL; +static uint8_t pwmFilter = 0; +static uint32_t pwmLastUpdateTime_ms = 0; +static bool new_data = false; +static bool sonar_present = false; + +#define PWM_TIMER_MHZ 1 +#define PWM_TIMER_8_MHZ 8 + +static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value) +{ + uint16_t tim_oc_preload; + TIM_OCInitTypeDef TIM_OCInitStructure; + + TIM_OCStructInit(&TIM_OCInitStructure); + TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2; + TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; + TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable; + TIM_OCInitStructure.TIM_Pulse = value; + TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_Low; + TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set; + + tim_oc_preload = TIM_OCPreload_Enable; + + switch (channel) { + case TIM_Channel_1: + TIM_OC1Init(tim, &TIM_OCInitStructure); + TIM_OC1PreloadConfig(tim, tim_oc_preload); + break; + case TIM_Channel_2: + TIM_OC2Init(tim, &TIM_OCInitStructure); + TIM_OC2PreloadConfig(tim, tim_oc_preload); + break; + case TIM_Channel_3: + TIM_OC3Init(tim, &TIM_OCInitStructure); + TIM_OC3PreloadConfig(tim, tim_oc_preload); + break; + case TIM_Channel_4: + TIM_OC4Init(tim, &TIM_OCInitStructure); + TIM_OC4PreloadConfig(tim, tim_oc_preload); + break; + } +} + +static void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity) +{ + TIM_ICInitTypeDef TIM_ICInitStructure; + + TIM_ICStructInit(&TIM_ICInitStructure); + TIM_ICInitStructure.TIM_Channel = channel; + TIM_ICInitStructure.TIM_ICPolarity = polarity; + TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; + TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; + TIM_ICInitStructure.TIM_ICFilter = pwmFilter; + + TIM_ICInit(tim, &TIM_ICInitStructure); +} + +static void pwmGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, GPIO_Mode mode) +{ + gpio_config_t cfg; + + cfg.pin = pin; + cfg.mode = mode; + cfg.speed = Speed_2MHz; + gpioInit(gpio, &cfg); +} + +static pwmPortData_t *pwmOutConfig(uint8_t port, uint8_t mhz, uint16_t period, uint16_t value) +{ + pwmPortData_t *p = &pwmPorts[port]; + configTimeBase(timerHardware[port].tim, period, mhz); + pwmGPIOConfig(timerHardware[port].gpio, timerHardware[port].pin, Mode_AF_PP); + pwmOCConfig(timerHardware[port].tim, timerHardware[port].channel, value); + // Needed only on TIM1 + if (timerHardware[port].outputEnable) + TIM_CtrlPWMOutputs(timerHardware[port].tim, ENABLE); + TIM_Cmd(timerHardware[port].tim, ENABLE); + + p->cr1 = &timerHardware[port].tim->CR1; + p->cnt = &timerHardware[port].tim->CNT; + + switch (timerHardware[port].channel) { + case TIM_Channel_1: + p->ccr = &timerHardware[port].tim->CCR1; + break; + case TIM_Channel_2: + p->ccr = &timerHardware[port].tim->CCR2; + break; + case TIM_Channel_3: + p->ccr = &timerHardware[port].tim->CCR3; + break; + case TIM_Channel_4: + p->ccr = &timerHardware[port].tim->CCR4; + break; + } + p->period = period; + return p; +} + +static pwmPortData_t *pwmInConfig(uint8_t port, timerCCCallbackPtr callback, uint8_t channel) +{ + pwmPortData_t *p = &pwmPorts[port]; + const timerHardware_t *timerHardwarePtr = &(timerHardware[port]); + + p->channel = channel; + + pwmGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_IPD); + pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); + + timerConfigure(timerHardwarePtr, 0xFFFF, PWM_TIMER_MHZ); + configureTimerCaptureCompareInterrupt(timerHardwarePtr, port, callback); + + return p; +} + +uint32_t pwmLastUpdate() +{ + return pwmLastUpdateTime_ms; +} + +static void ppmCallback(uint8_t port, uint16_t capture) +{ + pwmLastUpdateTime_ms = millis(); + new_data = true; + + (void)port; + uint16_t diff; + static uint16_t now; + static uint16_t last = 0; + static uint8_t chan = 0; + + last = now; + now = capture; + diff = now - last; + + if (diff > 2700) { // Per http://www.rcgroups.com/forums/showpost.php?p=21996147&postcount=3960 "So, if you use 2.5ms or higher as being the reset for the PPM stream start, you will be fine. I use 2.7ms just to be safe." + chan = 0; + } else { + if (diff > PULSE_MIN && diff < PULSE_MAX && chan < MAX_INPUTS) { // 750 to 2250 ms is our 'valid' channel range + captures[chan] = diff; + } + chan++; + } +} + +static void pwmCallback(uint8_t port, uint16_t capture) +{ + pwmLastUpdateTime_ms = millis(); + new_data = true; + + if (pwmPorts[port].state == 0) { + pwmPorts[port].rise = capture; + pwmPorts[port].state = 1; + pwmICConfig(timerHardware[port].tim, timerHardware[port].channel, TIM_ICPolarity_Falling); + } else { + pwmPorts[port].fall = capture; + // compute capture + pwmPorts[port].capture = pwmPorts[port].fall - pwmPorts[port].rise; + if (pwmPorts[port].capture > PULSE_MIN && pwmPorts[port].capture < PULSE_MAX) { // valid pulse width + captures[pwmPorts[port].channel] = pwmPorts[port].capture; + } + // switch state + pwmPorts[port].state = 0; + pwmICConfig(timerHardware[port].tim, timerHardware[port].channel, TIM_ICPolarity_Rising); + } +} + +static void sonarCallback(uint8_t port, uint16_t capture) +{ + if (pwmPorts[port].state == 0) { + // switch state + pwmPorts[port].rise = capture; + pwmPorts[port].state = 1; + pwmICConfig(timerHardware[port].tim, timerHardware[port].channel, TIM_ICPolarity_Falling); + } else { + pwmPorts[port].fall = capture; + // compute capture + pwmPorts[port].capture = pwmPorts[port].fall - pwmPorts[port].rise; +// if (pwmPorts[port].capture > 880 && pwmPorts[port].capture < 65000) { // valid pulse width + sonar_reads[pwmPorts[port].channel - 8] = pwmPorts[port].capture; + sonar_present = true; +// } + // switch state + pwmPorts[port].state = 0; + pwmICConfig(timerHardware[port].tim, timerHardware[port].channel, TIM_ICPolarity_Rising); + } +} + +static void configureSonar(uint8_t port) +{ + // Initialize as a trigger for sonar ring + sonar_trigger_port = port; + + gpio_config_t sonar_trigger_config; + sonar_trigger_config.mode = Mode_Out_PP; + sonar_trigger_config.pin = timerHardware[port].pin; + sonar_trigger_config.speed = Speed_50MHz; + + gpioInit(timerHardware[sonar_trigger_port].gpio, &sonar_trigger_config); +} + +// =========================================================================== + +enum { + TYPE_IP = 0x10, + TYPE_IW = 0x20, + TYPE_M = 0x40, + TYPE_S = 0x80, +}; + +enum { + TYPE_PWM_IN_OUT = 0x000, + TYPE_GPIO_OUTPUT = 0x100, +}; + +static const uint16_t multiPPM[] = { + PWM1 | TYPE_IP, // PPM input + PWM9 | TYPE_M, // Swap to servo if needed + PWM10 | TYPE_M, // Swap to servo if needed + PWM11 | TYPE_M, + PWM12 | TYPE_M, + PWM13 | TYPE_M, + PWM14 | TYPE_M, + PWM5 | TYPE_M, // Swap to servo if needed + PWM6 | TYPE_M, // Swap to servo if needed + PWM7 | TYPE_M, // Swap to servo if needed + PWM8 | TYPE_M, // Swap to servo if needed + 0xFFF +}; + +static const uint16_t multiPPMSONAR[] = { + PWM1 | TYPE_IP, // PPM input + PWM2 | TYPE_S, // Read Sonar Input + PWM3 | TYPE_S, + PWM4 | TYPE_S, + PWM5 | TYPE_S, + PWM6 | TYPE_S, + PWM7 | TYPE_S, + PWM8 | TYPE_S, + + PWM9 | TYPE_M, + PWM10 | TYPE_M, + PWM11 | TYPE_M, + PWM12 | TYPE_M, + PWM13 | TYPE_M, + PWM14 | TYPE_M, + 0xFFF +}; + +static const uint16_t multiPWM[] = { + PWM1 | TYPE_IW, // input #1 + PWM2 | TYPE_IW, + PWM3 | TYPE_IW, + PWM4 | TYPE_IW, + PWM5 | TYPE_IW, + PWM6 | TYPE_IW, + PWM7 | TYPE_IW, + PWM8 | TYPE_IW, // input #8 + PWM9 | TYPE_M, // motor #1 or servo #1 (swap to servo if needed) + PWM10 | TYPE_M, // motor #2 or servo #2 (swap to servo if needed) + PWM11 | TYPE_M, // motor #1 or #3 + PWM12 | TYPE_M, + PWM13 | TYPE_M, + PWM14 | TYPE_M, // motor #4 or #6 + 0xFFF +}; + + +static pwmPortData_t *motors[MAX_PORTS]; +static uint8_t numMotors = 0; +static uint8_t numInputs = 0; + +static void pwmWriteBrushed(uint8_t index, uint16_t value) +{ + *motors[index]->ccr = (value - 1000) * motors[index]->period / 1000; +} + +static void pwmWriteStandard(uint8_t index, uint16_t value) +{ + *motors[index]->ccr = value; +} + +void pwmInit(bool useCPPM, bool usePwmFilter, bool fastPWM, uint32_t motorPwmRate, uint16_t idlePulseUsec) +{ + const uint16_t *setup; + + // pwm filtering on input + pwmFilter = usePwmFilter ? 1 : 0; + + numMotors = 0; + setup = useCPPM ? multiPPMSONAR : multiPWM; + + int i; + for (i = 0; i < MAX_PORTS; i++) { + + uint8_t port = setup[i] & 0x0F; + uint8_t mask = setup[i] & 0xF0; + uint16_t output = setup[i] &0x0F00; + + if (setup[i] == 0x0FFF) // terminator + break; + + if(output & TYPE_GPIO_OUTPUT){ + configureSonar(port); + } + + if (mask & TYPE_IP) { + pwmInConfig(port, ppmCallback, 0); + numInputs = 8; + } else if (mask & TYPE_IW) { + pwmInConfig(port, pwmCallback, numInputs); + numInputs++; + } else if (mask & TYPE_S) { + pwmInConfig(port, sonarCallback, numInputs); + numInputs++; + } else if (mask & TYPE_M) { + uint32_t mhz = (motorPwmRate > 500 || fastPWM) ? PWM_TIMER_8_MHZ : PWM_TIMER_MHZ; + uint32_t hz = mhz * 1000000; + + uint16_t period = hz / (fastPWM ? 4000 : motorPwmRate); + + motors[numMotors++] = pwmOutConfig(port, mhz, period, idlePulseUsec); + } + } + + // determine motor writer function + pwmWritePtr = pwmWriteStandard; + if (motorPwmRate > 500) { + pwmWritePtr = pwmWriteBrushed; + } +} + +void pwmWriteMotor(uint8_t index, uint16_t value) +{ + if (index < numMotors) + pwmWritePtr(index, value); +} + +uint16_t pwmRead(uint8_t channel) +{ + if(millis() > pwmLastUpdateTime_ms + 40) + { + return 0; + } + else + { + new_data = false; + return captures[channel]; + } +} + +bool pwmNewData() +{ + return new_data; +} + +float sonarRead(uint8_t channel) +{ + return (float)sonar_reads[channel] / 5787.405; +} + +bool sonarPresent() +{ + return sonar_present; +} + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_pwm.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_pwm.h new file mode 100644 index 0000000..80d5fc8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_pwm.h @@ -0,0 +1,58 @@ +/* + drv_pwm.h : PWM support for STM32F103CB + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_pwm.h + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#pragma once + +#define MAX_SERVOS 8 +#define MAX_INPUTS 8 +#define PULSE_MIN (750) // minimum PWM pulse width which is considered valid +#define PULSE_MAX (2250) // maximum PWM pulse width which is considered valid + +// This indexes into the read-only hardware definition structure in drv_pwm.c, as well as into pwmPorts[] structure with dynamic data. +enum { + PWM1 = 0, + PWM2, + PWM3, + PWM4, + PWM5, + PWM6, + PWM7, + PWM8, + PWM9, + PWM10, + PWM11, + PWM12, + PWM13, + PWM14, + MAX_PORTS +}; + +void pwmInit(bool useCPPM, bool usePwmFilter, bool fastPWM, uint32_t motorPwmRate, uint16_t idlePulseUsec); +void pwmWriteMotor(uint8_t index, uint16_t value); +uint16_t pwmRead(uint8_t channel); + +uint32_t pwmLastUpdate(); +bool pwmNewData(); + +bool sonarPresent(); +float sonarRead(uint8_t channel); + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_sen13680.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_sen13680.c new file mode 100644 index 0000000..26f537f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_sen13680.c @@ -0,0 +1,97 @@ +/* + drv_sen13680.c : driver for Sparkfun SEN13680 LIDAR-Lite v2 + + Copyright (C) 2016 Simon D. Levy + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +// See https://github.com/PulsedLight3D for Arduino code +// and more documentation on this sensor + +#include + +#include +#include + +#include "drv_i2c.h" + +#define SEN13680_DEFAULT_ADDRESS 0x62 + +static float distance; + + + +bool sen13680_init() +{ + // check for device SEN13680_DEFAULT_ADDRESS and set + // to read fast and noisy if it's there + bool success = true; + if (i2cWrite(SEN13680_DEFAULT_ADDRESS, 0x00, 0x00)) + { + // Set the time between measurements (0x45). 0x04 means 250 Hz + success &= i2cWrite(SEN13680_DEFAULT_ADDRESS, 0x45, 0x04); + delay(10); + // Set the mode pin to default setting + success &= i2cWrite(SEN13680_DEFAULT_ADDRESS, 0x04, 0x21); + delay(10); + // Set the number of measurements to be taken (continuous) + success &= i2cWrite(SEN13680_DEFAULT_ADDRESS, 0x11, 0xFF); + delay(10); + // Initiate Reading + success &= i2cWrite(SEN13680_DEFAULT_ADDRESS, 0x00, 0x04); + delay(10); + } + else + { + success = false; + } + if (!success) + { + distance = -1; + } + return success; +} + + +void sen13680_update() +{ + // get current time + uint64_t now_us = micros(); + static uint64_t last_update_time_us = 0; + + // populate new measurement at 100hz + if (now_us > last_update_time_us + 10000) + { + // save current time + last_update_time_us = now_us; + uint8_t read_buffer[2] = {100,100}; + + // Request and read a lidar measurement + // Lidar Lite is stupid, and needs a stop signal before the second start signal + // in an I2C read. So, I'm writing the address to nowhere, stopping, starting again + // and then reading from nowhere + i2cWrite(SEN13680_DEFAULT_ADDRESS, 0xFF, 0x8F); + i2cRead(SEN13680_DEFAULT_ADDRESS, 0xFF, 2, read_buffer); + + distance = (float)((int16_t)(read_buffer[0] << 8) + read_buffer[1])/100.0; + } +} + +float sen13680_read() +{ + return distance; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_sen13680.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_sen13680.h new file mode 100644 index 0000000..3757251 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_sen13680.h @@ -0,0 +1,27 @@ +/* + drv_sen13680.h : driver for Sparkfun SEN13680 LIDAR-Lite v2 + + Copyright (C) 2016 Simon D. Levy + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#pragma once + +bool sen13680_init(); + +void sen13680_update(); +float sen13680_read(); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_serial.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_serial.c new file mode 100644 index 0000000..a74f273 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_serial.c @@ -0,0 +1,69 @@ +/* + drv_serial.c : serial support for STM32F103CB + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_serial.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include +#include + +#include "drv_serial.h" + +void serialPrint(serialPort_t *instance, const char *str) +{ + uint8_t ch; + while ((ch = *(str++)) != 0) { + serialWrite(instance, ch); + } +} + +uint32_t serialGetBaudRate(serialPort_t *instance) +{ + return instance->baudRate; +} + +void serialWrite(serialPort_t *instance, uint8_t ch) +{ + instance->vTable->serialWrite(instance, ch); +} + +uint8_t serialTotalBytesWaiting(serialPort_t *instance) +{ + return instance->vTable->serialTotalBytesWaiting(instance); +} + +uint8_t serialRead(serialPort_t *instance) +{ + return instance->vTable->serialRead(instance); +} + +void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate) +{ + instance->vTable->serialSetBaudRate(instance, baudRate); +} + +bool isSerialTransmitBufferEmpty(serialPort_t *instance) +{ + return instance->vTable->isSerialTransmitBufferEmpty(instance); +} + +inline void serialSetMode(serialPort_t *instance, portMode_t mode) +{ + instance->vTable->setMode(instance, mode); +} + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_serial.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_serial.h new file mode 100644 index 0000000..6c19bf9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_serial.h @@ -0,0 +1,75 @@ +/* + drv_serial.h : serial support for STM32F103CB + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_serial.h + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#pragma once + +typedef void (*serialReceiveCallbackPtr)(uint16_t data); // used by serial drivers to return frames to app + +typedef enum portMode_t { + MODE_RX = 1 << 0, + MODE_TX = 1 << 1, + MODE_RXTX = MODE_RX | MODE_TX, + MODE_SBUS = 1 << 2 +} portMode_t; + +typedef struct serialPort { + + const struct serialPortVTable *vTable; + + portMode_t mode; + uint32_t baudRate; + + uint32_t rxBufferSize; + uint32_t txBufferSize; + volatile uint8_t *rxBuffer; + volatile uint8_t *txBuffer; + uint32_t rxBufferHead; + uint32_t rxBufferTail; + uint32_t txBufferHead; + uint32_t txBufferTail; + + // FIXME rename member to rxCallback + serialReceiveCallbackPtr callback; +} serialPort_t; + +struct serialPortVTable { + void (*serialWrite)(serialPort_t *instance, uint8_t ch); + + uint8_t (*serialTotalBytesWaiting)(serialPort_t *instance); + + uint8_t (*serialRead)(serialPort_t *instance); + + // Specified baud rate may not be allowed by an implementation, use serialGetBaudRate to determine actual baud rate in use. + void (*serialSetBaudRate)(serialPort_t *instance, uint32_t baudRate); + + bool (*isSerialTransmitBufferEmpty)(serialPort_t *instance); + + void (*setMode)(serialPort_t *instance, portMode_t mode); +}; + +void serialWrite(serialPort_t *instance, uint8_t ch); +uint8_t serialTotalBytesWaiting(serialPort_t *instance); +uint8_t serialRead(serialPort_t *instance); +void serialSetBaudRate(serialPort_t *instance, uint32_t baudRate); +void serialSetMode(serialPort_t *instance, portMode_t mode); +bool isSerialTransmitBufferEmpty(serialPort_t *instance); +void serialPrint(serialPort_t *instance, const char *str); +uint32_t serialGetBaudRate(serialPort_t *instance); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_spi.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_spi.c new file mode 100644 index 0000000..40359b1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_spi.c @@ -0,0 +1,515 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include + +//#include +#include + +#include "drv_gpio.h" + +#include "drv_spi.h" + +#define UNUSED(x) (void)(x) + +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 + +#ifdef USE_SPI_DEVICE_1 + +#ifndef SPI1_GPIO +#define SPI1_GPIO GPIOA +#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOA +#define SPI1_NSS_PIN GPIO_Pin_4 +#define SPI1_NSS_PIN_SOURCE GPIO_PinSource4 +#define SPI1_SCK_PIN GPIO_Pin_5 +#define SPI1_SCK_PIN_SOURCE GPIO_PinSource5 +#define SPI1_MISO_PIN GPIO_Pin_6 +#define SPI1_MISO_PIN_SOURCE GPIO_PinSource6 +#define SPI1_MOSI_PIN GPIO_Pin_7 +#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource7 +#endif + +void initSpi1(void) +{ + // Specific to the STM32F103 + // SPI1 Driver + // PA4 14 SPI1_NSS + // PA5 15 SPI1_SCK + // PA6 16 SPI1_MISO + // PA7 17 SPI1_MOSI + + SPI_InitTypeDef spi; + + // Enable SPI1 clock + RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, ENABLE); + +#ifdef STM32F303xC + GPIO_InitTypeDef GPIO_InitStructure; + + RCC_AHBPeriphClockCmd(SPI1_GPIO_PERIPHERAL, ENABLE); + + GPIO_PinAFConfig(SPI1_GPIO, SPI1_SCK_PIN_SOURCE, GPIO_AF_5); + GPIO_PinAFConfig(SPI1_GPIO, SPI1_MISO_PIN_SOURCE, GPIO_AF_5); + GPIO_PinAFConfig(SPI1_GPIO, SPI1_MOSI_PIN_SOURCE, GPIO_AF_5); + +#ifdef SPI1_NSS_PIN_SOURCE + GPIO_PinAFConfig(SPI1_GPIO, SPI1_NSS_PIN_SOURCE, GPIO_AF_5); +#endif + + // Init pins + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + +#ifdef USE_SDCARD_SPI1 + // Configure pins and pullups for SD-card use + + // No pull-up needed since we drive this pin as an output + GPIO_InitStructure.GPIO_Pin = SPI1_MOSI_PIN; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + GPIO_Init(SPI1_GPIO, &GPIO_InitStructure); + + // Prevent MISO pin from floating when SDCard is deselected (high-Z) or not connected + GPIO_InitStructure.GPIO_Pin = SPI1_MISO_PIN; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; + GPIO_Init(SPI1_GPIO, &GPIO_InitStructure); + + // In clock-low mode, STM32 manual says we should enable a pulldown to match + GPIO_InitStructure.GPIO_Pin = SPI1_SCK_PIN; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN; + GPIO_Init(SPI1_GPIO, &GPIO_InitStructure); +#else + // General-purpose pin config + GPIO_InitStructure.GPIO_Pin = SPI1_SCK_PIN | SPI1_MISO_PIN | SPI1_MOSI_PIN; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + GPIO_Init(SPI1_GPIO, &GPIO_InitStructure); +#endif + +#ifdef SPI1_NSS_PIN + GPIO_InitStructure.GPIO_Pin = SPI1_NSS_PIN; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + + GPIO_Init(SPI1_GPIO, &GPIO_InitStructure); +#endif +#endif + + + + gpio_config_t gpio; + + // MOSI + SCK as output + gpio.mode = Mode_AF_PP; + gpio.pin = SPI1_MOSI_PIN | SPI1_SCK_PIN; + gpio.speed = Speed_50MHz; + gpioInit(SPI1_GPIO, &gpio); + + // MISO as input + gpio.pin = SPI1_MISO_PIN; + gpio.mode = Mode_IN_FLOATING; + gpioInit(SPI1_GPIO, &gpio); + +#ifdef SPI1_NSS_PIN + // NSS as gpio slave select + gpio.pin = SPI1_NSS_PIN; + gpio.mode = Mode_Out_PP; + gpioInit(SPI1_GPIO, &gpio); +#endif + + + // Init SPI1 hardware + SPI_I2S_DeInit(SPI1); + + spi.SPI_Mode = SPI_Mode_Master; + spi.SPI_Direction = SPI_Direction_2Lines_FullDuplex; + spi.SPI_DataSize = SPI_DataSize_8b; + spi.SPI_NSS = SPI_NSS_Soft; + spi.SPI_FirstBit = SPI_FirstBit_MSB; + spi.SPI_CRCPolynomial = 7; + spi.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8; + +#ifdef USE_SDCARD_SPI1 + spi.SPI_CPOL = SPI_CPOL_Low; + spi.SPI_CPHA = SPI_CPHA_1Edge; +#else + spi.SPI_CPOL = SPI_CPOL_High; + spi.SPI_CPHA = SPI_CPHA_2Edge; +#endif + +#ifdef STM32F303xC + // Configure for 8-bit reads. + SPI_RxFIFOThresholdConfig(SPI1, SPI_RxFIFOThreshold_QF); +#endif + + SPI_Init(SPI1, &spi); + SPI_Cmd(SPI1, ENABLE); + +#ifdef SPI1_NSS_PIN + // Drive NSS high to disable connected SPI device. + GPIO_SetBits(SPI1_GPIO, SPI1_NSS_PIN); +#endif +} +#endif + +#ifndef SPI2_GPIO +#define SPI2_GPIO GPIOB +#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB +#define SPI2_NSS_PIN GPIO_Pin_12 +#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12 +#define SPI2_SCK_PIN GPIO_Pin_13 +#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13 +#define SPI2_MISO_PIN GPIO_Pin_14 +#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14 +#define SPI2_MOSI_PIN GPIO_Pin_15 +#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15 + + +void initSpi2(void) +{ + // Specific to the STM32F103 / STM32F303 (AF5) + // SPI2 Driver + // PB12 25 SPI2_NSS + // PB13 26 SPI2_SCK + // PB14 27 SPI2_MISO + // PB15 28 SPI2_MOSI + + SPI_InitTypeDef spi; + + // Enable SPI2 clock + RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE); + + gpio_config_t gpio; + + // MOSI + SCK as output + gpio.mode = Mode_AF_PP; + gpio.pin = SPI2_SCK_PIN | SPI2_MOSI_PIN; + gpio.speed = Speed_50MHz; + gpioInit(SPI2_GPIO, &gpio); + + // MISO as input + gpio.pin = SPI2_MISO_PIN; + gpio.mode = Mode_IN_FLOATING; + gpioInit(SPI2_GPIO, &gpio); + +#ifdef SPI2_NSS_PIN + // NSS as gpio slave select + gpio.pin = SPI2_NSS_PIN; + gpio.mode = Mode_Out_PP; + gpioInit(SPI2_GPIO, &gpio); +#endif + + + // Init SPI2 hardware + SPI_I2S_DeInit(SPI2); + + spi.SPI_Mode = SPI_Mode_Master; + spi.SPI_Direction = SPI_Direction_2Lines_FullDuplex; + spi.SPI_DataSize = SPI_DataSize_8b; + spi.SPI_NSS = SPI_NSS_Soft; + spi.SPI_FirstBit = SPI_FirstBit_MSB; + spi.SPI_CRCPolynomial = 7; + spi.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8; + +#ifdef USE_SDCARD_SPI2 + spi.SPI_CPOL = SPI_CPOL_Low; + spi.SPI_CPHA = SPI_CPHA_1Edge; +#else + spi.SPI_CPOL = SPI_CPOL_High; + spi.SPI_CPHA = SPI_CPHA_2Edge; +#endif + +#ifdef STM32F303xC + // Configure for 8-bit reads. + SPI_RxFIFOThresholdConfig(SPI2, SPI_RxFIFOThreshold_QF); +#endif + + SPI_Init(SPI2, &spi); + SPI_Cmd(SPI2, ENABLE); + +#ifdef SPI2_NSS_PIN + // Drive NSS high to disable connected SPI device. + GPIO_SetBits(SPI2_GPIO, SPI2_NSS_PIN); +#endif +} +#endif + +#if defined(USE_SPI_DEVICE_3) && defined(STM32F303xC) + +#ifndef SPI3_GPIO +#define SPI3_GPIO GPIOB +#define SPI3_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB +#define SPI3_NSS_GPIO GPIOA +#define SPI3_NSS_PERIPHERAL RCC_AHBPeriph_GPIOA +#define SPI3_NSS_PIN GPIO_Pin_15 +#define SPI3_NSS_PIN_SOURCE GPIO_PinSource15 +#define SPI3_SCK_PIN GPIO_Pin_3 +#define SPI3_SCK_PIN_SOURCE GPIO_PinSource3 +#define SPI3_MISO_PIN GPIO_Pin_4 +#define SPI3_MISO_PIN_SOURCE GPIO_PinSource4 +#define SPI3_MOSI_PIN GPIO_Pin_5 +#define SPI3_MOSI_PIN_SOURCE GPIO_PinSource5 +#endif + +void initSpi3(void) +{ + // Specific to the STM32F303 (AF6) + // SPI3 Driver + // PA15 38 SPI3_NSS + // PB3 39 SPI3_SCK + // PB4 40 SPI3_MISO + // PB5 41 SPI3_MOSI + + SPI_InitTypeDef spi; + + // Enable SPI3 clock + RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI3, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE); + + GPIO_InitTypeDef GPIO_InitStructure; + + RCC_AHBPeriphClockCmd(SPI3_GPIO_PERIPHERAL, ENABLE); + + GPIO_PinAFConfig(SPI3_GPIO, SPI3_SCK_PIN_SOURCE, GPIO_AF_6); + GPIO_PinAFConfig(SPI3_GPIO, SPI3_MISO_PIN_SOURCE, GPIO_AF_6); + GPIO_PinAFConfig(SPI3_GPIO, SPI3_MOSI_PIN_SOURCE, GPIO_AF_6); + +#ifdef SPI2_NSS_PIN_SOURCE + RCC_AHBPeriphClockCmd(SPI3_NNS_PERIPHERAL, ENABLE); + GPIO_PinAFConfig(SPI3_NNS_GPIO, SPI3_NSS_PIN_SOURCE, GPIO_AF_6); +#endif + + // Init pins + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + +#ifdef USE_SDCARD_SPI3 + // Configure pins and pullups for SD-card use + + // No pull-up needed since we drive this pin as an output + GPIO_InitStructure.GPIO_Pin = SPI3_MOSI_PIN; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + GPIO_Init(SPI3_GPIO, &GPIO_InitStructure); + + // Prevent MISO pin from floating when SDCard is deselected (high-Z) or not connected + GPIO_InitStructure.GPIO_Pin = SPI3_MISO_PIN; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; + GPIO_Init(SPI3_GPIO, &GPIO_InitStructure); + + // In clock-low mode, STM32 manual says we should enable a pulldown to match + GPIO_InitStructure.GPIO_Pin = SPI3_SCK_PIN; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN; + GPIO_Init(SPI3_GPIO, &GPIO_InitStructure); +#else + // General-purpose pin config + GPIO_InitStructure.GPIO_Pin = SPI3_SCK_PIN | SPI3_MISO_PIN | SPI3_MOSI_PIN; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + GPIO_Init(SPI3_GPIO, &GPIO_InitStructure); +#endif + +#ifdef SPI3_NSS_PIN + GPIO_InitStructure.GPIO_Pin = SPI3_NSS_PIN; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; + + GPIO_Init(SPI3_NSS_GPIO, &GPIO_InitStructure); +#endif + + // Init SPI hardware + SPI_I2S_DeInit(SPI3); + + spi.SPI_Mode = SPI_Mode_Master; + spi.SPI_Direction = SPI_Direction_2Lines_FullDuplex; + spi.SPI_DataSize = SPI_DataSize_8b; + spi.SPI_NSS = SPI_NSS_Soft; + spi.SPI_FirstBit = SPI_FirstBit_MSB; + spi.SPI_CRCPolynomial = 7; + spi.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8; + +#ifdef USE_SDCARD_SPI3 + spi.SPI_CPOL = SPI_CPOL_Low; + spi.SPI_CPHA = SPI_CPHA_1Edge; +#else + spi.SPI_CPOL = SPI_CPOL_High; + spi.SPI_CPHA = SPI_CPHA_2Edge; +#endif + + // Configure for 8-bit reads. + SPI_RxFIFOThresholdConfig(SPI3, SPI_RxFIFOThreshold_QF); + + SPI_Init(SPI3, &spi); + SPI_Cmd(SPI3, ENABLE); + +#ifdef SPI3_NSS_PIN + // Drive NSS high to disable connected SPI device. + GPIO_SetBits(SPI3_NSS_GPIO, SPI3_NSS_PIN); +#endif +} +#endif + +bool spiInit(SPI_TypeDef *instance) +{ +#if (!(defined(USE_SPI_DEVICE_1) && defined(USE_SPI_DEVICE_2) && defined(USE_SPI_DEVICE_3))) + UNUSED(instance); +#endif + +#ifdef USE_SPI_DEVICE_1 + if (instance == SPI1) { + initSpi1(); + return true; + } +#endif +#ifdef USE_SPI_DEVICE_2 + if (instance == SPI2) { + initSpi2(); + return true; + } +#endif +#if defined(USE_SPI_DEVICE_3) && defined(STM32F303xC) + if (instance == SPI3) { + initSpi3(); + return true; + } +#endif + return false; +} + +uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data) +{ + uint16_t spiTimeout = 1000; + + while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) { + if ((spiTimeout--) == 0) + break; + } + + + + SPI_I2S_SendData(instance, data); + + spiTimeout = 1000; + while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET){ + if ((spiTimeout--) == 0) + break; + } + + return ((uint8_t)SPI_I2S_ReceiveData(instance)); + +} + +/** + * Return true if the bus is currently in the middle of a transmission. + */ +bool spiIsBusBusy(SPI_TypeDef *instance) +{ + return SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET; +} + +void spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len) +{ + uint16_t spiTimeout = 1000; + + uint8_t b; + instance->DR; + while (len--) { + b = in ? *(in++) : 0xFF; + while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) { + if ((spiTimeout--) == 0) + break; + } + + + SPI_I2S_SendData(instance, b); + + spiTimeout = 1000; + while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) { + if ((spiTimeout--) == 0) + break; + } + + b = SPI_I2S_ReceiveData(instance); + + if (out) + *(out++) = b; + } +} + + +void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor) +{ +#define BR_CLEAR_MASK 0xFFC7 + + uint16_t tempRegister; + + SPI_Cmd(instance, DISABLE); + + tempRegister = instance->CR1; + + switch (divisor) { + case 2: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_2; + break; + + case 4: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_4; + break; + + case 8: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_8; + break; + + case 16: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_16; + break; + + case 32: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_32; + break; + + case 64: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_64; + break; + + case 128: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_128; + break; + + case 256: + tempRegister &= BR_CLEAR_MASK; + tempRegister |= SPI_BaudRatePrescaler_256; + break; + } + + instance->CR1 = tempRegister; + + SPI_Cmd(instance, ENABLE); +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_spi.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_spi.h new file mode 100644 index 0000000..7c37a68 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_spi.h @@ -0,0 +1,30 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define SPI_0_28125MHZ_CLOCK_DIVIDER 256 +#define SPI_0_5625MHZ_CLOCK_DIVIDER 128 +#define SPI_18MHZ_CLOCK_DIVIDER 2 +#define SPI_9MHZ_CLOCK_DIVIDER 4 + +bool spiInit(SPI_TypeDef *instance); +void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor); +uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t in); +bool spiIsBusBusy(SPI_TypeDef *instance); + +void spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_system.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_system.c new file mode 100644 index 0000000..8192d16 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_system.c @@ -0,0 +1,168 @@ +/* + drv_sytem.c : system utilities (init, reset, delay, etc.) for STM32F103CB + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_system.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + + +#include +#include +#include + +#include "stm32f10x_conf.h" + +#include "drv_gpio.h" +#include "drv_system.h" + +static volatile uint64_t sysTickUptime = 0; + +static void cycleCounterInit(void) +{ + RCC_ClocksTypeDef clocks; + RCC_GetClocksFreq(&clocks); +} + +// SysTick +void SysTick_Handler(void) +{ + sysTickUptime++; +} + +uint64_t micros(void) +{ + return sysTickUptime * 20; +} + +uint32_t millis(void) +{ + return (uint32_t)(sysTickUptime / 50); +} + +void systemInit(void) +{ + struct { + GPIO_TypeDef *gpio; + gpio_config_t cfg; + } gpio_setup[3]; + + gpio_setup[0].gpio = LED0_GPIO; + gpio_setup[0].cfg.pin = LED0_PIN; + gpio_setup[0].cfg.mode = Mode_Out_PP; + gpio_setup[0].cfg.speed = Speed_2MHz; + + gpio_setup[1].gpio = LED1_GPIO; + gpio_setup[1].cfg.pin = LED1_PIN; + gpio_setup[1].cfg.mode = Mode_Out_PP; + gpio_setup[1].cfg.speed = Speed_2MHz; + + gpio_setup[2].gpio = INV_GPIO; + gpio_setup[2].cfg.pin = INV_PIN; + gpio_setup[2].cfg.mode = Mode_Out_PP; + gpio_setup[2].cfg.speed = Speed_2MHz; + + gpio_config_t gpio; + int i, gpio_count = sizeof(gpio_setup) / sizeof(gpio_setup[0]); + + // Configure NVIC preempt/priority groups + // This means we have two bits for the preemption priority, two bits for sub-priority + NVIC_PriorityGroupConfig(NVIC_PriorityGroup_4); + + // Turn on clocks for stuff we use + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4, ENABLE); + RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC | RCC_APB2Periph_TIM1 | RCC_APB2Periph_ADC1 | RCC_APB2Periph_USART1, ENABLE); + RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); + RCC_ClearFlag(); + + // Make all GPIO in by default to save power and reduce noise + gpio.pin = Pin_All; + gpio.mode = Mode_AIN; + gpioInit(GPIOA, &gpio); + gpioInit(GPIOB, &gpio); + gpioInit(GPIOC, &gpio); + + // Turn off JTAG port 'cause we're using the GPIO for leds +#define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24) + AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW; + + LED0_OFF; + LED1_OFF; + + for (i = 0; i < gpio_count; i++) { + gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg); + } + + // Init cycle counter + cycleCounterInit(); + + // SysTick + // Set to fire of at 50,000 Hz (which will give us 0.02 microsecond accuracy) + SysTick_Config(SystemCoreClock / 50000); + + // escalate the priority of the systick IRQn to highest + NVIC_SetPriority(SysTick_IRQn, 0 ); +} + +void delayMicroseconds(uint32_t us) +{ + uint64_t now = micros(); + while(micros() < (now + us)); +} + +void delay(uint32_t ms) +{ + while (ms--) + delayMicroseconds(1000); +} + +void failureMode() +{ + LED1_OFF; + LED0_ON; + systemReset(false); +} + +uint32_t rccReadBkpDr(void) +{ + return *((uint16_t *)BKP_BASE + 0x04) | *((uint16_t *)BKP_BASE + 0x08) << 16; +} + +void rccWriteBkpDr(uint32_t value) +{ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE); + PWR->CR |= PWR_CR_DBP; + + *((uint16_t *)BKP_BASE + 0x04) = value & 0xffff; + *((uint16_t *)BKP_BASE + 0x08) = (value & 0xffff0000) >> 16; +} + +#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) + +void systemReset(bool toBootloader) +{ + if (toBootloader) { + // 1FFFF000 -> 20000200 -> SP + // 1FFFF004 -> 1FFFF021 -> PC + *((uint32_t *)0x20004FF0) = 0xDEADBEEF; // 20KB STM32F103 + } + + // write magic value that we're doing a soft reset + rccWriteBkpDr(BKP_SOFTRESET); + + // Generate system reset + SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_system.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_system.h new file mode 100644 index 0000000..81b4aad --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_system.h @@ -0,0 +1,84 @@ +/* + drv_sytem.h : system utilities (init, reset, delay, etc.) for STM32F103CB + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_system.h + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#pragma once + +#define BKP_SOFTRESET (0x50F7B007) + +//#define GYRO +//#define ACC +//#define BUZZER +#define LED0 +#define LED1 +#define INVERTER + +#define LED0_GPIO GPIOB +#define LED0_PIN Pin_3 // PB3 (LED) +#define LED1_GPIO GPIOB +#define LED1_PIN Pin_4 // PB4 (LED) +#define INV_PIN Pin_2 // PB2 (BOOT1) abused as inverter select GPIO +#define INV_GPIO GPIOB + +#ifdef LED0 +#define LED0_TOGGLE digitalToggle(LED0_GPIO, LED0_PIN); +#define LED0_OFF digitalHi(LED0_GPIO, LED0_PIN); +#define LED0_ON digitalLo(LED0_GPIO, LED0_PIN); +#else +#define LED0_TOGGLE +#define LED0_OFF +#define LED0_ON +#endif + +#ifdef LED1 +#define LED1_TOGGLE digitalToggle(LED1_GPIO, LED1_PIN); +#define LED1_OFF digitalHi(LED1_GPIO, LED1_PIN); +#define LED1_ON digitalLo(LED1_GPIO, LED1_PIN); +#else +#define LED1_TOGGLE +#define LED1_OFF +#define LED1_ON +#endif + +#ifdef INV_GPIO +#define INV_OFF digitalLo(INV_GPIO, INV_PIN); +#define INV_ON digitalHi(INV_GPIO, INV_PIN); +#else +#define INV_OFF ; +#define INV_ON ; +#endif + +void systemInit(void); +void delayMicroseconds(uint32_t us); +void delay(uint32_t ms); + +uint64_t micros(void); +uint32_t millis(void); + +// Backup SRAM R/W +uint32_t rccReadBkpDr(void); +void rccWriteBkpDr(uint32_t value); + +// failure +void failureMode(); + +// bootloader/IAP +void systemReset(bool toBootloader); + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_timer.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_timer.c new file mode 100644 index 0000000..4c6f315 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_timer.c @@ -0,0 +1,271 @@ +/* + drv_timer.c : timer support for STM32F103CB + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_timer.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include + +#include "stm32f10x_conf.h" +#include "core_cm3.h" +#include "drv_timer.h" +#include "drv_gpio.h" + +/* FreeFlight/Naze32 timer layout + TIM2_CH1 RC1 PWM1 + TIM2_CH2 RC2 PWM2 + TIM2_CH3 RC3/UA2_TX PWM3 + TIM2_CH4 RC4/UA2_RX PWM4 + TIM3_CH1 RC5 PWM5 + TIM3_CH2 RC6 PWM6 + TIM3_CH3 RC7 PWM7 + TIM3_CH4 RC8 PWM8 + TIM1_CH1 PWM1 PWM9 + TIM1_CH4 PWM2 PWM10 + TIM4_CH1 PWM3 PWM11 + TIM4_CH2 PWM4 PWM12 + TIM4_CH3 PWM5 PWM13 + TIM4_CH4 PWM6 PWM14 + + RX1 TIM2_CH1 PA0 [also PPM] [also used for throttle calibration] + RX2 TIM2_CH2 PA1 + RX3 TIM2_CH3 PA2 [also UART2_TX] + RX4 TIM2_CH4 PA3 [also UART2_RX] + RX5 TIM3_CH1 PA6 [also ADC_IN6] + RX6 TIM3_CH2 PA7 [also ADC_IN7] + RX7 TIM3_CH3 PB0 [also ADC_IN8] + RX8 TIM3_CH4 PB1 [also ADC_IN9] + + Outputs + PWM1 TIM1_CH1 PA8 + PWM2 TIM1_CH4 PA11 + PWM3 TIM4_CH1 PB6? [also I2C1_SCL] + PWM4 TIM4_CH2 PB7 [also I2C1_SDA] + PWM5 TIM4_CH3 PB8 + PWM6 TIM4_CH4 PB9 + { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, }, // PWM2 + { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, }, // PWM3 + { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, }, // PWM4 + { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, }, // PWM5 + { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 0, }, // PWM6 + { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, }, // PWM7 + Groups that allow running different period (ex 50Hz servos + 400Hz throttle + etc): + TIM2 4 channels + TIM3 4 channels + TIM1 2 channels + TIM4 4 channels +*/ + +const timerHardware_t timerHardware[] = { + { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, }, // PWM1 + { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, }, // PWM2 + { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, }, // PWM3 + { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, }, // PWM4 + { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, }, // PWM5 + { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 0, }, // PWM6 + { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, }, // PWM7 + { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, }, // PWM8 + { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, }, // PWM9 + { TIM1, GPIOA, Pin_11, TIM_Channel_4, TIM1_CC_IRQn, 1, }, // PWM10 + { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, }, // PWM11 + { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, }, // PWM12 + { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, }, // PWM13 + { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, }, // PWM14 +}; + +enum { + TIM1_IDX = 0, + TIM2_IDX, + TIM3_IDX, + TIM4_IDX, + MAX_TIMERS +}; + +#define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4 + +static const TIM_TypeDef *const timers[MAX_TIMERS] = { + [TIM1_IDX] = TIM1, [TIM2_IDX] = TIM2, [TIM3_IDX] = TIM3, [TIM4_IDX] = TIM4 +}; + +typedef struct channelConfig_s { + uint16_t channel; + uint16_t interruptBit; + uint16_t (*TIM_GetCaptureFn)(TIM_TypeDef *TIMx); +} channelConfig_t; + +static const channelConfig_t channels[CC_CHANNELS_PER_TIMER] = { + { TIM_Channel_1, TIM_IT_CC1, TIM_GetCapture1 }, + { TIM_Channel_2, TIM_IT_CC2, TIM_GetCapture2 }, + { TIM_Channel_3, TIM_IT_CC3, TIM_GetCapture3 }, + { TIM_Channel_4, TIM_IT_CC4, TIM_GetCapture4 } +}; + +typedef struct timerConfig_s { + TIM_TypeDef *tim; + uint8_t channel; + timerCCCallbackPtr *callback; + uint8_t reference; +} timerConfig_t; + +timerConfig_t timerConfigs[MAX_TIMERS][CC_CHANNELS_PER_TIMER]; + +static int lookupTimerIndex(const TIM_TypeDef *tim) +{ + int timerIndex; + for (timerIndex = 0; timerIndex < MAX_TIMERS; timerIndex++ ) { + if (timers[timerIndex] == tim) + break; + } + return timerIndex; +} + +static int lookupChannelIndex(const int channel) +{ + int channelIndex; + for (channelIndex = 0; channelIndex < CC_CHANNELS_PER_TIMER; channelIndex++ ) { + if (channels[channelIndex].channel == channel) + break; + } + return channelIndex; +} + +void configureTimerChannelCallback(TIM_TypeDef *tim, uint8_t channel, uint8_t reference, timerCCCallbackPtr *callback) +{ + assert_param(IS_TIM_CHANNEL(channel)); + + int timerIndex = lookupTimerIndex(tim); + int channelIndex = lookupChannelIndex(channel); + + if (timerIndex >= MAX_TIMERS || channelIndex >= CC_CHANNELS_PER_TIMER) { + return; + } + + timerConfigs[timerIndex][channelIndex].callback = callback; + timerConfigs[timerIndex][channelIndex].channel = channel; + timerConfigs[timerIndex][channelIndex].reference = reference; +} + +void configureTimerInputCaptureCompareChannel(TIM_TypeDef *tim, const uint8_t channel) +{ + switch (channel) { + case TIM_Channel_1: + TIM_ITConfig(tim, TIM_IT_CC1, ENABLE); + break; + case TIM_Channel_2: + TIM_ITConfig(tim, TIM_IT_CC2, ENABLE); + break; + case TIM_Channel_3: + TIM_ITConfig(tim, TIM_IT_CC3, ENABLE); + break; + case TIM_Channel_4: + TIM_ITConfig(tim, TIM_IT_CC4, ENABLE); + break; + } +} + +void configureTimerCaptureCompareInterrupt(const timerHardware_t *timerHardwarePtr, uint8_t reference, timerCCCallbackPtr *callback) +{ + configureTimerChannelCallback(timerHardwarePtr->tim, timerHardwarePtr->channel, reference, callback); + configureTimerInputCaptureCompareChannel(timerHardwarePtr->tim, timerHardwarePtr->channel); +} + +void timerNVICConfigure(uint8_t irq) +{ + NVIC_InitTypeDef NVIC_InitStructure; + + NVIC_InitStructure.NVIC_IRQChannel = irq; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 2; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); +} + +void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz) +{ + TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; + + TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); + TIM_TimeBaseStructure.TIM_Period = period - 1; // AKA TIMx_ARR + + // "The counter clock frequency (CK_CNT) is equal to f CK_PSC / (PSC[15:0] + 1)." - STM32F10x Reference Manual 14.4.11 + // Thus for 1Mhz: 72000000 / 1000000 = 72, 72 - 1 = 71 = TIM_Prescaler + TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1; + + + TIM_TimeBaseStructure.TIM_ClockDivision = 0; + TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; + TIM_TimeBaseInit(tim, &TIM_TimeBaseStructure); +} + +void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, uint8_t mhz) +{ + configTimeBase(timerHardwarePtr->tim, period, mhz); + TIM_Cmd(timerHardwarePtr->tim, ENABLE); + timerNVICConfigure(timerHardwarePtr->irq); +} + + +static timerConfig_t *findTimerConfig(unsigned int timerIndex, unsigned int channelIndex) +{ + assert_param(timerIndex < MAX_TIMERS); + assert_param(channelIndex < CC_CHANNELS_PER_TIMER); + + return &(timerConfigs[timerIndex][channelIndex]); +} + +static void timCCxHandler(TIM_TypeDef *const tim, unsigned int timerIndex) +{ + unsigned int channelIndex; + + for (channelIndex = 0; channelIndex < CC_CHANNELS_PER_TIMER; channelIndex++) { + channelConfig_t const *const channel = &channels[channelIndex]; + + if (TIM_GetITStatus(tim, channel->interruptBit) == SET) { + TIM_ClearITPendingBit(tim, channel->interruptBit); + + uint16_t capture; + capture = channel->TIM_GetCaptureFn(tim); + + timerConfig_t *timerConfig; + timerConfig = findTimerConfig(timerIndex, channelIndex); + if (timerConfig->callback) { + timerConfig->callback(timerConfig->reference, capture); + } + } + } +} + +void TIM1_CC_IRQHandler(void) +{ + timCCxHandler(TIM1, TIM1_IDX); +} + +void TIM2_IRQHandler(void) +{ + timCCxHandler(TIM2, TIM2_IDX); +} + +void TIM3_IRQHandler(void) +{ + timCCxHandler(TIM3, TIM3_IDX); +} + +void TIM4_IRQHandler(void) +{ + timCCxHandler(TIM4, TIM4_IDX); +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_timer.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_timer.h new file mode 100644 index 0000000..7c80e30 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_timer.h @@ -0,0 +1,43 @@ +/* + drv_timer.h : timer support for STM32F103CB + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_timer.h + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#pragma once + +typedef void timerCCCallbackPtr(uint8_t port, uint16_t capture); + +typedef struct { + TIM_TypeDef *tim; + GPIO_TypeDef *gpio; + uint32_t pin; + uint8_t channel; + uint8_t irq; + uint8_t outputEnable; +} timerHardware_t; + +extern const timerHardware_t timerHardware[]; + +void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz); +void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, uint8_t mhz); +void timerNVICConfigure(uint8_t irq); + +void configureTimerInputCaptureCompareChannel(TIM_TypeDef *tim, const uint8_t channel); +void configureTimerCaptureCompareInterrupt(const timerHardware_t *timerHardwarePtr, uint8_t reference, timerCCCallbackPtr *callback); +void configureTimerChannelCallback(TIM_TypeDef *tim, uint8_t channel, uint8_t reference, timerCCCallbackPtr *callback); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_uart.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_uart.c new file mode 100644 index 0000000..94575bb --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_uart.c @@ -0,0 +1,300 @@ +/* + drv_uart.c : UART support for STM32F103CB + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_uart.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + + +#include +#include +#include + +#include "stm32f10x_conf.h" + +#include "drv_serial.h" +#include "drv_gpio.h" +#include "drv_uart.h" + +static uartPort_t uartPort1; + +// USART1 - Telemetry (RX/TX by DMA) +uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode) +{ + uartPort_t *s; + static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE]; + static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE]; + gpio_config_t gpio; + NVIC_InitTypeDef NVIC_InitStructure; + + s = &uartPort1; + s->port.vTable = uartVTable; + + s->port.baudRate = baudRate; + + s->port.rxBuffer = rx1Buffer; + s->port.txBuffer = tx1Buffer; + s->port.rxBufferSize = UART1_RX_BUFFER_SIZE; + s->port.txBufferSize = UART1_TX_BUFFER_SIZE; + + s->rxDMAChannel = DMA1_Channel5; + s->txDMAChannel = DMA1_Channel4; + + RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE); + // USART1_TX PA9 + // USART1_RX PA10 + gpio.speed = Speed_2MHz; + gpio.pin = Pin_9; + gpio.mode = Mode_AF_PP; + if (mode & MODE_TX) + gpioInit(GPIOA, &gpio); + gpio.pin = Pin_10; + gpio.mode = Mode_IPU; + if (mode & MODE_RX) + gpioInit(GPIOA, &gpio); + + // DMA TX Interrupt + NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel4_IRQn; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 3; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); + + return s; +} + +serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode) +{ + DMA_InitTypeDef DMA_InitStructure; + USART_InitTypeDef USART_InitStructure; + + uartPort_t *s = NULL; + + if (!USARTx) + return NULL; + + if (USARTx == USART1) + s = serialUSART1(baudRate, mode); + + s->USARTx = USARTx; + + // common serial initialisation code should move to serialPort::init() + s->port.rxBufferHead = s->port.rxBufferTail = 0; + s->port.txBufferHead = s->port.txBufferTail = 0; + // callback for IRQ-based RX ONLY + s->port.callback = callback; + s->port.mode = mode; + s->port.baudRate = baudRate; + + USART_InitStructure.USART_BaudRate = baudRate; + USART_InitStructure.USART_WordLength = USART_WordLength_8b; + if (mode & MODE_SBUS) { + USART_InitStructure.USART_StopBits = USART_StopBits_2; + USART_InitStructure.USART_Parity = USART_Parity_Even; + } else { + USART_InitStructure.USART_StopBits = USART_StopBits_1; + USART_InitStructure.USART_Parity = USART_Parity_No; + } + USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; + USART_InitStructure.USART_Mode = 0; + if (mode & MODE_RX) + USART_InitStructure.USART_Mode |= USART_Mode_Rx; + if (mode & MODE_TX) + USART_InitStructure.USART_Mode |= USART_Mode_Tx; + USART_Init(USARTx, &USART_InitStructure); + USART_Cmd(USARTx, ENABLE); + + DMA_StructInit(&DMA_InitStructure); + DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&USARTx->DR; + DMA_InitStructure.DMA_Priority = DMA_Priority_Medium; + DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; + DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; + DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; + DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; + DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; + + // Receive DMA or IRQ + if (mode & MODE_RX) { + if (s->rxDMAChannel) { + DMA_InitStructure.DMA_BufferSize = s->port.rxBufferSize; + DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; + DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; + DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)s->port.rxBuffer; + DMA_DeInit(s->rxDMAChannel); + DMA_Init(s->rxDMAChannel, &DMA_InitStructure); + DMA_Cmd(s->rxDMAChannel, ENABLE); + USART_DMACmd(USARTx, USART_DMAReq_Rx, ENABLE); + s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAChannel); + } else { + USART_ITConfig(USARTx, USART_IT_RXNE, ENABLE); + } + } + + // Transmit DMA or IRQ + if (mode & MODE_TX) { + if (s->txDMAChannel) { + DMA_InitStructure.DMA_BufferSize = s->port.txBufferSize; + DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; + DMA_InitStructure.DMA_Mode = DMA_Mode_Normal; + DMA_DeInit(s->txDMAChannel); + DMA_Init(s->txDMAChannel, &DMA_InitStructure); + DMA_ITConfig(s->txDMAChannel, DMA_IT_TC, ENABLE); + DMA_SetCurrDataCounter(s->txDMAChannel, 0); + s->txDMAChannel->CNDTR = 0; + USART_DMACmd(USARTx, USART_DMAReq_Tx, ENABLE); + } else { + USART_ITConfig(USARTx, USART_IT_TXE, ENABLE); + } + } + + return (serialPort_t *)s; +} + +void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate) +{ + USART_InitTypeDef USART_InitStructure; + uartPort_t *s = (uartPort_t *)instance; + + USART_InitStructure.USART_BaudRate = baudRate; + USART_InitStructure.USART_WordLength = USART_WordLength_8b; + USART_InitStructure.USART_StopBits = USART_StopBits_1; + USART_InitStructure.USART_Parity = USART_Parity_No; + USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; + USART_InitStructure.USART_Mode = 0; + if (s->port.mode & MODE_RX) + USART_InitStructure.USART_Mode |= USART_Mode_Rx; + if (s->port.mode & MODE_TX) + USART_InitStructure.USART_Mode |= USART_Mode_Tx; + USART_Init(s->USARTx, &USART_InitStructure); + + s->port.baudRate = baudRate; +} + +void uartSetMode(serialPort_t *s, portMode_t mode) +{ + (void)s; + (void)mode; + // not implemented. +} + + +static void uartStartTxDMA(uartPort_t *s) +{ + s->txDMAChannel->CMAR = (uint32_t)&s->port.txBuffer[s->port.txBufferTail]; + if (s->port.txBufferHead > s->port.txBufferTail) { + s->txDMAChannel->CNDTR = s->port.txBufferHead - s->port.txBufferTail; + s->port.txBufferTail = s->port.txBufferHead; + } else { + s->txDMAChannel->CNDTR = s->port.txBufferSize - s->port.txBufferTail; + s->port.txBufferTail = 0; + } + s->txDMAEmpty = false; + DMA_Cmd(s->txDMAChannel, ENABLE); +} + +uint8_t uartTotalBytesWaiting(serialPort_t *instance) +{ + uartPort_t *s = (uartPort_t *)instance; + // FIXME always returns 1 or 0, not the amount of bytes waiting + if (s->rxDMAChannel) + return s->rxDMAChannel->CNDTR != s->rxDMAPos; + else + return s->port.rxBufferTail != s->port.rxBufferHead; +} + +// BUGBUG TODO TODO FIXME - What is the bug? +bool isUartTransmitBufferEmpty(serialPort_t *instance) +{ + uartPort_t *s = (uartPort_t *)instance; + if (s->txDMAChannel) + return s->txDMAEmpty; + else + return s->port.txBufferTail == s->port.txBufferHead; +} + +uint8_t uartRead(serialPort_t *instance) +{ + uint8_t ch; + uartPort_t *s = (uartPort_t *)instance; + + if (s->rxDMAChannel) { + ch = s->port.rxBuffer[s->port.rxBufferSize - s->rxDMAPos]; + if (--s->rxDMAPos == 0) + s->rxDMAPos = s->port.rxBufferSize; + } else { + ch = s->port.rxBuffer[s->port.rxBufferTail]; + s->port.rxBufferTail = (s->port.rxBufferTail + 1) % s->port.rxBufferSize; + } + + return ch; +} + +void uartWrite(serialPort_t *instance, uint8_t ch) +{ + uartPort_t *s = (uartPort_t *)instance; + s->port.txBuffer[s->port.txBufferHead] = ch; + s->port.txBufferHead = (s->port.txBufferHead + 1) % s->port.txBufferSize; + + if (s->txDMAChannel) { + if (!(s->txDMAChannel->CCR & 1)) + uartStartTxDMA(s); + } else { + USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE); + } +} + +const struct serialPortVTable uartVTable[] = { + { + uartWrite, + uartTotalBytesWaiting, + uartRead, + uartSetBaudRate, + isUartTransmitBufferEmpty, + uartSetMode, + } +}; + +// Handlers + +// USART1 Tx DMA Handler +void DMA1_Channel4_IRQHandler(void) +{ + uartPort_t *s = &uartPort1; + DMA_ClearITPendingBit(DMA1_IT_TC4); + DMA_Cmd(s->txDMAChannel, DISABLE); + + if (s->port.txBufferHead != s->port.txBufferTail) + uartStartTxDMA(s); + else + s->txDMAEmpty = true; +} + +// USART1 Tx IRQ Handler +void USART1_IRQHandler(void) +{ + uartPort_t *s = &uartPort1; + uint16_t SR = s->USARTx->SR; + + if (SR & USART_FLAG_TXE) { + if (s->port.txBufferTail != s->port.txBufferHead) { + s->USARTx->DR = s->port.txBuffer[s->port.txBufferTail]; + s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize; + } else { + USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE); + } + } +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_uart.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_uart.h new file mode 100644 index 0000000..529488e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/drv_uart.h @@ -0,0 +1,60 @@ +/* + drv_uart.h : UART support for STM32F103CB + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_uart.h + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#pragma once + +#define UART_BUFFER_SIZE 64 + +#define UART1_RX_BUFFER_SIZE 256 +#define UART1_TX_BUFFER_SIZE 256 +#define UART2_RX_BUFFER_SIZE 128 +#define UART2_TX_BUFFER_SIZE 64 +#define UART3_RX_BUFFER_SIZE 256 +#define UART3_TX_BUFFER_SIZE 256 +#define MAX_SERIAL_PORTS 3 + +// FIXME this is a uart_t really. Move the generic properties into a separate structure (serialPort_t) and update the code to use it +typedef struct { + serialPort_t port; + + // FIXME these are uart specific and do not belong in here + DMA_Channel_TypeDef *rxDMAChannel; + DMA_Channel_TypeDef *txDMAChannel; + + uint32_t rxDMAIrq; + uint32_t txDMAIrq; + + uint32_t rxDMAPos; + bool txDMAEmpty; + + USART_TypeDef *USARTx; +} uartPort_t; + +extern const struct serialPortVTable uartVTable[]; + +serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode); + +// serialPort API +void uartWrite(serialPort_t *instance, uint8_t ch); +uint8_t uartTotalBytesWaiting(serialPort_t *instance); +uint8_t uartRead(serialPort_t *instance); +void uartSetBaudRate(serialPort_t *s, uint32_t baudRate); +bool isUartTransmitBufferEmpty(serialPort_t *s); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/accelgyro/Makefile b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/accelgyro/Makefile new file mode 100644 index 0000000..ec5c8c4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/accelgyro/Makefile @@ -0,0 +1,169 @@ +############################################################################### +# "THE BEER-WARE LICENSE" (Revision 42): +# wrote this file. As long as you retain this notice you +# can do whatever you want with this stuff. If we meet some day, and you think +# this stuff is worth it, you can buy me a beer in return + +############################################################################### + +# Change this to wherever you put BreezySTM32 +BREEZY_DIR = ../../ + +# Fill this out with source files for your specific project +PROJECT_SRC = accelgyro.c + +############################################################################### + +# You probably shouldn't modify anything below here! + +TARGET ?= myproject + +# Compile-time options +OPTIONS ?= + +# Debugger optons, must be empty or GDB +DEBUG ?= + +# Serial port/Device for flashing +SERIAL_DEVICE ?= /dev/ttyUSB0 + +# Working directories +ROOT = $(dir $(lastword $(MAKEFILE_LIST))) +SRC_DIR = $(ROOT) +CMSIS_DIR = $(BREEZY_DIR)/lib/CMSIS +STDPERIPH_DIR = $(BREEZY_DIR)/lib/STM32F10x_StdPeriph_Driver +OBJECT_DIR = $(ROOT)/obj +BIN_DIR = $(ROOT)/obj + +myproject_SRC = $(BREEZY_DIR)/main.c \ + $(BREEZY_DIR)/startup_stm32f10x_md_gcc.S \ + $(BREEZY_DIR)/drv_gpio.c \ + $(BREEZY_DIR)/drv_i2c.c \ + $(BREEZY_DIR)/drv_system.c \ + $(BREEZY_DIR)/drv_serial.c \ + $(BREEZY_DIR)/drv_uart.c \ + $(BREEZY_DIR)/drv_timer.c \ + $(BREEZY_DIR)/breezyprintf.c \ + $(BREEZY_DIR)/drv_mpu6050.c \ + $(PROJECT_SRC) \ + $(CMSIS_SRC) \ + $(STDPERIPH_SRC) + +VPATH := $(SRC_DIR):$(SRC_DIR)/startups + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + +############################################################################### +# Things that might need changing to use different tools +# + +# Tool names +CC = arm-none-eabi-gcc -std=gnu99 +OBJCOPY = arm-none-eabi-objcopy + +# +# Tool options. +# +INCLUDE_DIRS = $(SRC_DIR) \ + $(BREEZY_DIR) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 + +ifeq ($(DEBUG),GDB) +OPTIMIZE = -Og + +else +OPTIMIZE = -Os +LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) +endif + +DEBUG_FLAGS = -ggdb3 + +CFLAGS = $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -Wall -pedantic -Wextra -Wshadow -Wunsafe-loop-optimizations \ + -ffunction-sections \ + -fdata-sections \ + -DSTM32F10X_MD \ + -DUSE_STDPERIPH_DRIVER \ + -D$(TARGET) + +ASFLAGS = $(ARCH_FLAGS) \ + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) + +LD_SCRIPT = $(BREEZY_DIR)/stm32_flash.ld +LDFLAGS = -lm \ + -nostartfiles \ + --specs=nano.specs \ + -lc \ + -lnosys \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_MAP) \ + -T$(LD_SCRIPT) + +# +# Things we will build +# + +TARGET_HEX = $(BIN_DIR)/$(TARGET).hex +TARGET_ELF = $(BIN_DIR)/$(TARGET).elf +TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) +TARGET_MAP = $(OBJECT_DIR)/$(TARGET).map + +# List of buildable ELF files and their object dependencies. +# It would be nice to compute these lists, but that seems to be just beyond make. + +$(TARGET_HEX): $(TARGET_ELF) + $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ + +$(TARGET_ELF): $(TARGET_OBJS) + $(CC) -o $@ $^ $(LDFLAGS) + +MKDIR_OBJDIR = @mkdir -p $(dir $@) + +# Compile +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + +# Assemble +$(OBJECT_DIR)/$(TARGET)/%.o: %.S + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(ASFLAGS) $< + +clean: + rm -rf $(TARGET_HEX) $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) obj + +flash_$(TARGET): $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 921600 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 921600 $(SERIAL_DEVICE) + +flash: flash_$(TARGET) + +unbrick: $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +listen: + miniterm.py $(SERIAL_DEVICE) 115200 + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/accelgyro/accelgyro.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/accelgyro/accelgyro.c new file mode 100644 index 0000000..89e4323 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/accelgyro/accelgyro.c @@ -0,0 +1,71 @@ +/* + accelgyro.c : report accelerometer and gyroscope values + + Copyright (C) 2016 James Jackson + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include + +#define BOARD_REV 2 + +float accel_scale; // converts to units of m/s^2 +float gyro_scale; // converts to units of rad/s + +volatile int16_t accel_data[3]; +volatile int16_t gyro_data[3]; +volatile int16_t temp_data; + +volatile uint8_t accel_status = 0; +volatile uint8_t gyro_status = 0; +volatile uint8_t temp_status = 0; +volatile bool mpu_new_measurement = false; + +uint32_t start_time = 0; + +void setup(void) +{ + delay(500); + i2cInit(I2CDEV_2); + + uint16_t acc1G; + mpu6050_init(true, &acc1G, &gyro_scale, BOARD_REV); + accel_scale = 9.80665f / acc1G; +} + +void loop(void) +{ +// printf("test"); +// delay(100); + if (mpu6050_new_data()) + { + LED0_TOGGLE; + volatile uint64_t time_us; + mpu6050_async_read_all(accel_data, &temp_data, gyro_data, &time_us); + printf("%d\t %d\t %d\t %d\t %d\t %d\t %d\t %d\t \n", + (int32_t)(accel_data[0]*accel_scale*1000.0f), + (int32_t)(accel_data[1]*accel_scale*1000.0f), + (int32_t)(accel_data[2]*accel_scale*1000.0f), + (int32_t)(gyro_data[0]*gyro_scale*1000.0f), + (int32_t)(gyro_data[1]*gyro_scale*1000.0f), + (int32_t)(gyro_data[2]*gyro_scale*1000.0f), + (int32_t)temp_data, + (int32_t)time_us); +// printf("test"); + delay(50); + } +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/blinkplusplus/Makefile b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/blinkplusplus/Makefile new file mode 100644 index 0000000..7c4c2ba --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/blinkplusplus/Makefile @@ -0,0 +1,162 @@ +############################################################################### +# "THE BEER-WARE LICENSE" (Revision 42): +# wrote this file. As long as you retain this notice you +# can do whatever you want with this stuff. If we meet some day, and you think +# this stuff is worth it, you can buy me a beer in return + +############################################################################### + +# Change this to wherever you put BreezySTM32 +BREEZY_DIR = ../../ + +TARGET ?= ledblink + +CPP_OBJS = ledblink.o + +############################################################################### + +# Compile-time options +OPTIONS ?= + +# Debugger optons, must be empty or GDB +DEBUG ?= + +# Serial port/Device for flashing +SERIAL_DEVICE ?= /dev/ttyUSB0 + +# Working directories +ROOT = $(dir $(lastword $(MAKEFILE_LIST))) +SRC_DIR = $(ROOT) +CMSIS_DIR = $(BREEZY_DIR)/lib/CMSIS +STDPERIPH_DIR = $(BREEZY_DIR)/lib/STM32F10x_StdPeriph_Driver +OBJECT_DIR = $(ROOT)/obj +BIN_DIR = $(ROOT)/obj + +$(TARGET)_CSRC = $(BREEZY_DIR)/main.c \ + $(BREEZY_DIR)/startup_stm32f10x_md_gcc.S \ + $(BREEZY_DIR)/drv_gpio.c \ + $(BREEZY_DIR)/drv_i2c.c \ + $(BREEZY_DIR)/drv_adc.c \ + $(BREEZY_DIR)/drv_spi.c \ + $(BREEZY_DIR)/drv_pwm.c \ + $(BREEZY_DIR)/drv_system.c \ + $(BREEZY_DIR)/drv_serial.c \ + $(BREEZY_DIR)/drv_uart.c \ + $(BREEZY_DIR)/drv_timer.c \ + $(BREEZY_DIR)/printf.c \ + $(CMSIS_SRC) \ + $(STDPERIPH_SRC) + +VPATH := $(SRC_DIR):$(SRC_DIR)/startups + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + +############################################################################### +# Things that might need changing to use different tools +# + +# Tool names +CC = arm-none-eabi-gcc +OBJCOPY = arm-none-eabi-objcopy + +# +# Tool options. +# +INCLUDE_DIRS = $(SRC_DIR) \ + $(BREEZY_DIR) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 + +ifeq ($(DEBUG),GDB) +OPTIMIZE = -Og + +else +OPTIMIZE = -Os +LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) +endif + +DEBUG_FLAGS = -ggdb3 + +CFLAGS = $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -Wall -pedantic -Wextra -Wshadow -Wunsafe-loop-optimizations \ + -ffunction-sections \ + -fdata-sections \ + -DSTM32F10X_MD \ + -DUSE_STDPERIPH_DRIVER \ + -D$(TARGET) + +ASFLAGS = $(ARCH_FLAGS) \ + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) + +LD_SCRIPT = $(BREEZY_DIR)/stm32_flash.ld +LDFLAGS = -lm \ + -nostartfiles \ + -lc \ + --specs=rdimon.specs \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_MAP) \ + -T$(LD_SCRIPT) + +# +# Things we will build +# + +TARGET_HEX = $(BIN_DIR)/$(TARGET).hex +TARGET_ELF = $(BIN_DIR)/$(TARGET).elf +TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_CSRC)))) $(CPP_OBJS) +TARGET_MAP = $(OBJECT_DIR)/$(TARGET).map + +# List of buildable ELF files and their object dependencies. +# It would be nice to compute these lists, but that seems to be just beyond make. + +$(TARGET_HEX): $(TARGET_ELF) + $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ + +$(TARGET_ELF): $(TARGET_OBJS) + $(CC) -o $@ $^ $(LDFLAGS) + +MKDIR_OBJDIR = @mkdir -p $(dir $@) + +# Compile +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + +# Assemble +$(OBJECT_DIR)/$(TARGET)/%.o: %.S + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(ASFLAGS) $< + +# C++ support +%.o: %.cpp + $(CC) -c $(CFLAGS) -o $@ $^ + +clean: + rm -rf $(TARGET_HEX) $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) *.o obj + +flash_$(TARGET): $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +flash: flash_$(TARGET) + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/blinkplusplus/ledblink.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/blinkplusplus/ledblink.cpp new file mode 100644 index 0000000..f51e1fb --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/blinkplusplus/ledblink.cpp @@ -0,0 +1,68 @@ +/* + ledblink.cpp : blink the LED using C++ + + Copyright (C) 2016 Simon D. Levy + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +extern "C" { // allows us to compile C++ with arm-none-eabi-gcc + +#include + +class Blinker { + + private: + + int ledid; + + public: + + void init(int id) { + + this->ledid = id; + } + + void toggle(void) { + + switch (this->ledid) { + + case 0: + LED0_TOGGLE; + break; + + case 1: + LED1_TOGGLE; + } + } + +}; + +Blinker blinker; + +void setup(void) { + + blinker.init(1); +} + +void loop(void) { + + blinker.toggle(); + + delay(500); +} + +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/hmc5883l/Makefile b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/hmc5883l/Makefile new file mode 100644 index 0000000..1b0cf5b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/hmc5883l/Makefile @@ -0,0 +1,170 @@ +############################################################################### +# "THE BEER-WARE LICENSE" (Revision 42): +# wrote this file. As long as you retain this notice you +# can do whatever you want with this stuff. If we meet some day, and you think +# this stuff is worth it, you can buy me a beer in return + +############################################################################### + +# Change this to wherever you put BreezySTM32 +BREEZY_DIR = ../../ + +# Fill this out with source files for your specific project +PROJECT_SRC = hmc5883l_read.c + +############################################################################### + +# You probably shouldn't modify anything below here! + +TARGET ?= myproject + +# Compile-time options +OPTIONS ?= + +# Debugger optons, must be empty or GDB +DEBUG ?= + +# Serial port/Device for flashing +SERIAL_DEVICE ?= /dev/ttyUSB0 + +# Working directories +ROOT = $(dir $(lastword $(MAKEFILE_LIST))) +SRC_DIR = $(ROOT) +CMSIS_DIR = $(BREEZY_DIR)/lib/CMSIS +STDPERIPH_DIR = $(BREEZY_DIR)/lib/STM32F10x_StdPeriph_Driver +OBJECT_DIR = $(ROOT)/obj +BIN_DIR = $(ROOT)/obj + +myproject_SRC = $(BREEZY_DIR)/main.c \ + $(BREEZY_DIR)/startup_stm32f10x_md_gcc.S \ + $(BREEZY_DIR)/drv_gpio.c \ + $(BREEZY_DIR)/drv_i2c.c \ + $(BREEZY_DIR)/drv_system.c \ + $(BREEZY_DIR)/drv_serial.c \ + $(BREEZY_DIR)/drv_uart.c \ + $(BREEZY_DIR)/drv_timer.c \ + $(BREEZY_DIR)/breezyprintf.c \ + $(BREEZY_DIR)/drv_mpu6050.c \ + $(BREEZY_DIR)/drv_hmc5883l.c \ + $(PROJECT_SRC) \ + $(CMSIS_SRC) \ + $(STDPERIPH_SRC) + +VPATH := $(SRC_DIR):$(SRC_DIR)/startups + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + +############################################################################### +# Things that might need changing to use different tools +# + +# Tool names +CC = arm-none-eabi-gcc -std=gnu99 +OBJCOPY = arm-none-eabi-objcopy + +# +# Tool options. +# +INCLUDE_DIRS = $(SRC_DIR) \ + $(BREEZY_DIR) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 + +ifeq ($(DEBUG),GDB) +OPTIMIZE = -Og + +else +OPTIMIZE = -Os +LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) +endif + +DEBUG_FLAGS = -ggdb3 + +CFLAGS = $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -Wall -pedantic -Wextra -Wshadow -Wunsafe-loop-optimizations \ + -ffunction-sections \ + -fdata-sections \ + -DSTM32F10X_MD \ + -DUSE_STDPERIPH_DRIVER \ + -D$(TARGET) + +ASFLAGS = $(ARCH_FLAGS) \ + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) + +LD_SCRIPT = $(BREEZY_DIR)/stm32_flash.ld +LDFLAGS = -lm \ + -nostartfiles \ + --specs=nano.specs \ + -lc \ + -lnosys \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_MAP) \ + -T$(LD_SCRIPT) + +# +# Things we will build +# + +TARGET_HEX = $(BIN_DIR)/$(TARGET).hex +TARGET_ELF = $(BIN_DIR)/$(TARGET).elf +TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) +TARGET_MAP = $(OBJECT_DIR)/$(TARGET).map + +# List of buildable ELF files and their object dependencies. +# It would be nice to compute these lists, but that seems to be just beyond make. + +$(TARGET_HEX): $(TARGET_ELF) + $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ + +$(TARGET_ELF): $(TARGET_OBJS) + $(CC) -o $@ $^ $(LDFLAGS) + +MKDIR_OBJDIR = @mkdir -p $(dir $@) + +# Compile +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + +# Assemble +$(OBJECT_DIR)/$(TARGET)/%.o: %.S + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(ASFLAGS) $< + +clean: + rm -rf $(TARGET_HEX) $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) obj + +flash_$(TARGET): $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 921600 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 921600 $(SERIAL_DEVICE) + +flash: flash_$(TARGET) + +unbrick: $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +listen: + miniterm.py $(SERIAL_DEVICE) 115200 + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/hmc5883l/hmc5883l_read.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/hmc5883l/hmc5883l_read.c new file mode 100644 index 0000000..b7a25fb --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/hmc5883l/hmc5883l_read.c @@ -0,0 +1,52 @@ +/* + hmc5883l_read.c : report magnetometer measurements + + Copyright (C) 2016 James Jackson + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include + +#define BOARD_REV 2 + + +volatile uint8_t mag_status = 0; +int16_t mag_data[3] = {0.0, 0.0, 0.0}; + +void setup(void) +{ + delay(500); + i2cInit(I2CDEV_2); + + // Initialize the Magnetometer + hmc5883lInit(BOARD_REV); + hmc5883l_request_async_update(); +} + +void loop(void) +{ + hmc5883l_request_async_update(); + hmc5883l_async_read(mag_data); + printf("%d\t %d\t %d\n", + (int32_t)(mag_data[0]), + (int32_t)(mag_data[1]), + (int32_t)(mag_data[2])); + delay(6); + + +} + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/i2csniff/Makefile b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/i2csniff/Makefile new file mode 100644 index 0000000..73baa70 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/i2csniff/Makefile @@ -0,0 +1,168 @@ +############################################################################### +# "THE BEER-WARE LICENSE" (Revision 42): +# wrote this file. As long as you retain this notice you +# can do whatever you want with this stuff. If we meet some day, and you think +# this stuff is worth it, you can buy me a beer in return + +############################################################################### + +# Change this to wherever you put BreezySTM32 +BREEZY_DIR = ../../ + +# Fill this out with source files for your specific project +PROJECT_SRC = i2csniff.c + +############################################################################### + +# You probably shouldn't modify anything below here! + +TARGET ?= myproject + +# Compile-time options +OPTIONS ?= + +# Debugger optons, must be empty or GDB +DEBUG ?= + +# Serial port/Device for flashing +SERIAL_DEVICE ?= /dev/ttyUSB0 + +# Working directories +ROOT = $(dir $(lastword $(MAKEFILE_LIST))) +SRC_DIR = $(ROOT) +CMSIS_DIR = $(BREEZY_DIR)/lib/CMSIS +STDPERIPH_DIR = $(BREEZY_DIR)/lib/STM32F10x_StdPeriph_Driver +OBJECT_DIR = $(ROOT)/obj +BIN_DIR = $(ROOT)/obj + +myproject_SRC = $(BREEZY_DIR)/main.c \ + $(BREEZY_DIR)/startup_stm32f10x_md_gcc.S \ + $(BREEZY_DIR)/drv_gpio.c \ + $(BREEZY_DIR)/drv_i2c.c \ + $(BREEZY_DIR)/drv_system.c \ + $(BREEZY_DIR)/drv_serial.c \ + $(BREEZY_DIR)/drv_uart.c \ + $(BREEZY_DIR)/drv_timer.c \ + $(BREEZY_DIR)/printf.c \ + $(PROJECT_SRC) \ + $(CMSIS_SRC) \ + $(STDPERIPH_SRC) + +VPATH := $(SRC_DIR):$(SRC_DIR)/startups + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + +############################################################################### +# Things that might need changing to use different tools +# + +# Tool names +CC = arm-none-eabi-gcc -std=gnu99 +OBJCOPY = arm-none-eabi-objcopy + +# +# Tool options. +# +INCLUDE_DIRS = $(SRC_DIR) \ + $(BREEZY_DIR) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 + +ifeq ($(DEBUG),GDB) +OPTIMIZE = -Og + +else +OPTIMIZE = -Os +LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) +endif + +DEBUG_FLAGS = -ggdb3 + +CFLAGS = $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -Wall -pedantic -Wextra -Wshadow -Wunsafe-loop-optimizations \ + -ffunction-sections \ + -fdata-sections \ + -DSTM32F10X_MD \ + -DUSE_STDPERIPH_DRIVER \ + -D$(TARGET) + +ASFLAGS = $(ARCH_FLAGS) \ + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) + +LD_SCRIPT = $(BREEZY_DIR)/stm32_flash.ld +LDFLAGS = -lm \ + -nostartfiles \ + --specs=nano.specs \ + -lc \ + -lnosys \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_MAP) \ + -T$(LD_SCRIPT) + +# +# Things we will build +# + +TARGET_HEX = $(BIN_DIR)/$(TARGET).hex +TARGET_ELF = $(BIN_DIR)/$(TARGET).elf +TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) +TARGET_MAP = $(OBJECT_DIR)/$(TARGET).map + +# List of buildable ELF files and their object dependencies. +# It would be nice to compute these lists, but that seems to be just beyond make. + +$(TARGET_HEX): $(TARGET_ELF) + $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ + +$(TARGET_ELF): $(TARGET_OBJS) + $(CC) -o $@ $^ $(LDFLAGS) + +MKDIR_OBJDIR = @mkdir -p $(dir $@) + +# Compile +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + +# Assemble +$(OBJECT_DIR)/$(TARGET)/%.o: %.S + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(ASFLAGS) $< + +clean: + rm -rf $(TARGET_HEX) $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) obj + +flash_$(TARGET): $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +flash: flash_$(TARGET) + +unbrick: $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +listen: + miniterm.py $(SERIAL_DEVICE) 115200 + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/i2csniff/README.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/i2csniff/README.md new file mode 100644 index 0000000..0a4edb2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/i2csniff/README.md @@ -0,0 +1,3 @@ +# i2csniff: Detect and report I2C devices + +Don't forget to supply external power for external sensors (like MB1242 sonar)! diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/i2csniff/i2csniff.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/i2csniff/i2csniff.c new file mode 100644 index 0000000..3b7c736 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/i2csniff/i2csniff.c @@ -0,0 +1,44 @@ +/* + i2sniff.c : sniff and report I^2C devices + + Copyright (C) 2016 Simon D. Levy + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_adc.c + + Don't forget to supply external power for external sensors (like MB1242 sonar)! + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include + +void setup(void) +{ + i2cInit(I2CDEV_2); +} + +void loop(void) +{ + uint8_t addr; + + for (addr=0; addr<128; ++addr) + if (i2cWrite(addr, 0x00, 0x00)) + printf("Found device at address 0X%02X\n", addr); + + printf("--------------------------\n"); + + delay(1000); +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ledblink/Makefile b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ledblink/Makefile new file mode 100644 index 0000000..857e114 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ledblink/Makefile @@ -0,0 +1,158 @@ +############################################################################### +# "THE BEER-WARE LICENSE" (Revision 42): +# wrote this file. As long as you retain this notice you +# can do whatever you want with this stuff. If we meet some day, and you think +# this stuff is worth it, you can buy me a beer in return + +############################################################################### + +# Change this to wherever you put BreezySTM32 +BREEZY_DIR = ../../ + +# Fill this out with source files for your specific project +PROJECT_SRC = ledblink.c + +############################################################################### + +# You probably shouldn't modify anything below here! + +TARGET ?= myproject + +# Compile-time options +OPTIONS ?= + +# Debugger optons, must be empty or GDB +DEBUG ?= + +# Serial port/Device for flashing +SERIAL_DEVICE ?= /dev/ttyUSB0 + +# Working directories +ROOT = $(dir $(lastword $(MAKEFILE_LIST))) +SRC_DIR = $(ROOT) +CMSIS_DIR = $(BREEZY_DIR)/lib/CMSIS +STDPERIPH_DIR = $(BREEZY_DIR)/lib/STM32F10x_StdPeriph_Driver +OBJECT_DIR = $(ROOT)/obj +BIN_DIR = $(ROOT)/obj + +myproject_SRC = $(BREEZY_DIR)/main.c \ + $(BREEZY_DIR)/startup_stm32f10x_md_gcc.S \ + $(BREEZY_DIR)/drv_gpio.c \ + $(BREEZY_DIR)/drv_adc.c \ + $(BREEZY_DIR)/drv_system.c \ + $(BREEZY_DIR)/drv_serial.c \ + $(BREEZY_DIR)/drv_uart.c \ + $(BREEZY_DIR)/printf.c \ + $(PROJECT_SRC) \ + $(CMSIS_SRC) \ + $(STDPERIPH_SRC) + +VPATH := $(SRC_DIR):$(SRC_DIR)/startups + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + +############################################################################### +# Things that might need changing to use different tools +# + +# Tool names +CC = arm-none-eabi-gcc -std=gnu99 +OBJCOPY = arm-none-eabi-objcopy + +# +# Tool options. +# +INCLUDE_DIRS = $(SRC_DIR) \ + $(BREEZY_DIR) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 + +ifeq ($(DEBUG),GDB) +OPTIMIZE = -Og + +else +OPTIMIZE = -Os +LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) +endif + +DEBUG_FLAGS = -ggdb3 + +CFLAGS = $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -Wall -pedantic -Wextra -Wshadow -Wunsafe-loop-optimizations \ + -ffunction-sections \ + -fdata-sections \ + -DSTM32F10X_MD \ + -DUSE_STDPERIPH_DRIVER \ + -D$(TARGET) + +ASFLAGS = $(ARCH_FLAGS) \ + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) + +LD_SCRIPT = $(BREEZY_DIR)/stm32_flash.ld +LDFLAGS = -lm \ + -nostartfiles \ + --specs=nano.specs \ + -lc \ + -lnosys \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_MAP) \ + -T$(LD_SCRIPT) + +# +# Things we will build +# + +TARGET_HEX = $(BIN_DIR)/$(TARGET).hex +TARGET_ELF = $(BIN_DIR)/$(TARGET).elf +TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) +TARGET_MAP = $(OBJECT_DIR)/$(TARGET).map + +# List of buildable ELF files and their object dependencies. +# It would be nice to compute these lists, but that seems to be just beyond make. + +$(TARGET_HEX): $(TARGET_ELF) + $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ + +$(TARGET_ELF): $(TARGET_OBJS) + $(CC) -o $@ $^ $(LDFLAGS) + +MKDIR_OBJDIR = @mkdir -p $(dir $@) + +# Compile +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + +# Assemble +$(OBJECT_DIR)/$(TARGET)/%.o: %.S + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(ASFLAGS) $< + +clean: + rm -rf *.o obj + +flash_$(TARGET): $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +flash: flash_$(TARGET) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ledblink/ledblink.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ledblink/ledblink.c new file mode 100644 index 0000000..465ec53 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ledblink/ledblink.c @@ -0,0 +1,32 @@ +/* + ledblink.c : blink the LED + + Copyright (C) 2016 Simon D. Levy + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include + +void setup(void) +{ +} + +void loop(void) +{ + LED0_TOGGLE; + delay(500); +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/mb10x0/Makefile b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/mb10x0/Makefile new file mode 100644 index 0000000..db127ee --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/mb10x0/Makefile @@ -0,0 +1,171 @@ +############################################################################### +# "THE BEER-WARE LICENSE" (Revision 42): +# wrote this file. As long as you retain this notice you +# can do whatever you want with this stuff. If we meet some day, and you think +# this stuff is worth it, you can buy me a beer in return + +############################################################################### + +# Change this to wherever you put BreezySTM32 +BREEZY_DIR = ../../ + +# Fill this out with source files for your specific project +PROJECT_SRC = mb10x0_read.c + +############################################################################### + +# You probably shouldn't modify anything below here! + +TARGET ?= myproject + +# Compile-time options +OPTIONS ?= + +# Debugger optons, must be empty or GDB +DEBUG ?= GDB + +# Serial port/Device for flashing +SERIAL_DEVICE ?= /dev/ttyUSB0 + +# Working directories +ROOT = $(dir $(lastword $(MAKEFILE_LIST))) +SRC_DIR = $(ROOT) +CMSIS_DIR = $(BREEZY_DIR)/lib/CMSIS +STDPERIPH_DIR = $(BREEZY_DIR)/lib/STM32F10x_StdPeriph_Driver +OBJECT_DIR = $(ROOT)/obj +BIN_DIR = $(ROOT)/obj + +myproject_SRC = $(BREEZY_DIR)/main.c \ + $(BREEZY_DIR)/startup_stm32f10x_md_gcc.S \ + $(BREEZY_DIR)/drv_gpio.c \ + $(BREEZY_DIR)/drv_i2c.c \ + $(BREEZY_DIR)/drv_adc.c \ + $(BREEZY_DIR)/drv_spi.c \ + $(BREEZY_DIR)/drv_pwm.c \ + $(BREEZY_DIR)/drv_system.c \ + $(BREEZY_DIR)/drv_serial.c \ + $(BREEZY_DIR)/drv_uart.c \ + $(BREEZY_DIR)/drv_timer.c \ + $(BREEZY_DIR)/breezyprintf.c \ + $(PROJECT_SRC) \ + $(CMSIS_SRC) \ + $(STDPERIPH_SRC) + +VPATH := $(SRC_DIR):$(SRC_DIR)/startups + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + +############################################################################### +# Things that might need changing to use different tools +# + +# Tool names +CC = arm-none-eabi-gcc -std=gnu99 +OBJCOPY = arm-none-eabi-objcopy + +# +# Tool options. +# +INCLUDE_DIRS = $(SRC_DIR) \ + $(BREEZY_DIR) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 + +ifeq ($(DEBUG),GDB) +OPTIMIZE = -Og + +else +OPTIMIZE = -Os +LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) +endif + +DEBUG_FLAGS = -ggdb3 + +CFLAGS = $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -Wall -pedantic -Wextra -Wshadow -Wunsafe-loop-optimizations \ + -ffunction-sections \ + -fdata-sections \ + -DSTM32F10X_MD \ + -DUSE_STDPERIPH_DRIVER \ + -D$(TARGET) + +ASFLAGS = $(ARCH_FLAGS) \ + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) + +LD_SCRIPT = $(BREEZY_DIR)/stm32_flash.ld +LDFLAGS = -lm \ + -nostartfiles \ + --specs=nano.specs \ + -lc \ + -lnosys \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_MAP) \ + -T$(LD_SCRIPT) + +# +# Things we will build +# + +TARGET_HEX = $(BIN_DIR)/$(TARGET).hex +TARGET_ELF = $(BIN_DIR)/$(TARGET).elf +TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) +TARGET_MAP = $(OBJECT_DIR)/$(TARGET).map + +# List of buildable ELF files and their object dependencies. +# It would be nice to compute these lists, but that seems to be just beyond make. + +$(TARGET_HEX): $(TARGET_ELF) + $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ + +$(TARGET_ELF): $(TARGET_OBJS) + $(CC) -o $@ $^ $(LDFLAGS) + +MKDIR_OBJDIR = @mkdir -p $(dir $@) + +# Compile +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + +# Assemble +$(OBJECT_DIR)/$(TARGET)/%.o: %.S + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(ASFLAGS) $< + +clean: + rm -rf $(TARGET_HEX) $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) obj + +flash_$(TARGET): $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +flash: flash_$(TARGET) + +unbrick: $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +listen: + miniterm.py $(SERIAL_DEVICE) 115200 + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/mb10x0/mb10x0_read.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/mb10x0/mb10x0_read.c new file mode 100644 index 0000000..15aa9a8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/mb10x0/mb10x0_read.c @@ -0,0 +1,26 @@ +#include + + +void setup() +{ + pwmInit(true, false, false, 490, 1000); +} + + +void loop() +{ + if (sonarPresent()) + { + printf("\nsonar read = "); + for (int i = 0; i < 7; i++) + { + float distance = sonarRead(i); + printf("%d.%dm\t", (int32_t)distance, (int32_t)(distance*1000)%1000); + } + } + else + { + printf("\nno sonar"); + } + delay(50); +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/mb1242/Makefile b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/mb1242/Makefile new file mode 100644 index 0000000..82a9f40 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/mb1242/Makefile @@ -0,0 +1,172 @@ +############################################################################### +# "THE BEER-WARE LICENSE" (Revision 42): +# wrote this file. As long as you retain this notice you +# can do whatever you want with this stuff. If we meet some day, and you think +# this stuff is worth it, you can buy me a beer in return + +############################################################################### + +# Change this to wherever you put BreezySTM32 +BREEZY_DIR = ../../ + +# Fill this out with source files for your specific project +PROJECT_SRC = mb1242read.c + +############################################################################### + +# You probably shouldn't modify anything below here! + +TARGET ?= myproject + +# Compile-time options +OPTIONS ?= + +# Debugger optons, must be empty or GDB +DEBUG ?= GDB + +# Serial port/Device for flashing +SERIAL_DEVICE ?= /dev/ttyUSB0 + +# Working directories +ROOT = $(dir $(lastword $(MAKEFILE_LIST))) +SRC_DIR = $(ROOT) +CMSIS_DIR = $(BREEZY_DIR)/lib/CMSIS +STDPERIPH_DIR = $(BREEZY_DIR)/lib/STM32F10x_StdPeriph_Driver +OBJECT_DIR = $(ROOT)/obj +BIN_DIR = $(ROOT)/obj + +myproject_SRC = $(BREEZY_DIR)/main.c \ + $(BREEZY_DIR)/startup_stm32f10x_md_gcc.S \ + $(BREEZY_DIR)/drv_gpio.c \ + $(BREEZY_DIR)/drv_i2c.c \ + $(BREEZY_DIR)/drv_mb1242.c \ + $(BREEZY_DIR)/drv_adc.c \ + $(BREEZY_DIR)/drv_spi.c \ + $(BREEZY_DIR)/drv_pwm.c \ + $(BREEZY_DIR)/drv_system.c \ + $(BREEZY_DIR)/drv_serial.c \ + $(BREEZY_DIR)/drv_uart.c \ + $(BREEZY_DIR)/drv_timer.c \ + $(BREEZY_DIR)/breezyprintf.c \ + $(PROJECT_SRC) \ + $(CMSIS_SRC) \ + $(STDPERIPH_SRC) + +VPATH := $(SRC_DIR):$(SRC_DIR)/startups + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + +############################################################################### +# Things that might need changing to use different tools +# + +# Tool names +CC = arm-none-eabi-gcc -std=gnu99 +OBJCOPY = arm-none-eabi-objcopy + +# +# Tool options. +# +INCLUDE_DIRS = $(SRC_DIR) \ + $(BREEZY_DIR) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 + +ifeq ($(DEBUG),GDB) +OPTIMIZE = -Og + +else +OPTIMIZE = -Os +LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) +endif + +DEBUG_FLAGS = -ggdb3 + +CFLAGS = $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -Wall -pedantic -Wextra -Wshadow -Wunsafe-loop-optimizations \ + -ffunction-sections \ + -fdata-sections \ + -DSTM32F10X_MD \ + -DUSE_STDPERIPH_DRIVER \ + -D$(TARGET) + +ASFLAGS = $(ARCH_FLAGS) \ + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) + +LD_SCRIPT = $(BREEZY_DIR)/stm32_flash.ld +LDFLAGS = -lm \ + -nostartfiles \ + --specs=nano.specs \ + -lc \ + -lnosys \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_MAP) \ + -T$(LD_SCRIPT) + +# +# Things we will build +# + +TARGET_HEX = $(BIN_DIR)/$(TARGET).hex +TARGET_ELF = $(BIN_DIR)/$(TARGET).elf +TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) +TARGET_MAP = $(OBJECT_DIR)/$(TARGET).map + +# List of buildable ELF files and their object dependencies. +# It would be nice to compute these lists, but that seems to be just beyond make. + +$(TARGET_HEX): $(TARGET_ELF) + $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ + +$(TARGET_ELF): $(TARGET_OBJS) + $(CC) -o $@ $^ $(LDFLAGS) + +MKDIR_OBJDIR = @mkdir -p $(dir $@) + +# Compile +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + +# Assemble +$(OBJECT_DIR)/$(TARGET)/%.o: %.S + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(ASFLAGS) $< + +clean: + rm -rf $(TARGET_HEX) $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) obj + +flash_$(TARGET): $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +flash: flash_$(TARGET) + +unbrick: $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +listen: + miniterm.py $(SERIAL_DEVICE) 115200 + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/mb1242/README.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/mb1242/README.md new file mode 100644 index 0000000..b5bc196 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/mb1242/README.md @@ -0,0 +1,3 @@ +# mb1242: Read distances from MaxBotix MB1242 ultrasonic I2C sensor + +Don't forget to supply external power to the board! diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/mb1242/mb1242read.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/mb1242/mb1242read.c new file mode 100644 index 0000000..91dfae6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/mb1242/mb1242read.c @@ -0,0 +1,47 @@ +/* + mb1242read.c : read values from MaxBotix MB1242 I^2C sonar + + Don't forget to supply external power to the board! + + Copyright (C) 2016 Simon D. Levy + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include + +static bool sonar_present; + +void setup(void) +{ + i2cInit(I2CDEV_2); + delay(500); + sonar_present = mb1242_init(); +} + +void loop(void) +{ + mb1242_async_update(); + delay(25); + LED1_TOGGLE; + if(mb1242_present() || sonar_present) + { + float distance = mb1242_async_read(); + printf("distance = %d.%dm\n", (uint32_t)distance, (uint32_t)(distance*1000)%1000); + } + else + printf("no sonar\n"); +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/memtest/Makefile b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/memtest/Makefile new file mode 100644 index 0000000..c436817 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/memtest/Makefile @@ -0,0 +1,166 @@ +############################################################################### +# "THE BEER-WARE LICENSE" (Revision 42): +# wrote this file. As long as you retain this notice you +# can do whatever you want with this stuff. If we meet some day, and you think +# this stuff is worth it, you can buy me a beer in return + +############################################################################### + +# Change this to wherever you put BreezySTM32 +BREEZY_DIR = ../../ + +# Fill this out with source files for your specific project +PROJECT_SRC = memtest.c + +############################################################################### + +# You probably shouldn't modify anything below here! + +TARGET ?= myproject + +# Compile-time options +OPTIONS ?= + +# Debugger optons, must be empty or GDB +DEBUG ?= + +# Serial port/Device for flashing +SERIAL_DEVICE ?= /dev/ttyUSB0 + +# Working directories +ROOT = $(dir $(lastword $(MAKEFILE_LIST))) +SRC_DIR = $(ROOT) +CMSIS_DIR = $(BREEZY_DIR)/lib/CMSIS +STDPERIPH_DIR = $(BREEZY_DIR)/lib/STM32F10x_StdPeriph_Driver +OBJECT_DIR = $(ROOT)/obj +BIN_DIR = $(ROOT)/obj + +myproject_SRC = $(BREEZY_DIR)/main.c \ + $(BREEZY_DIR)/startup_stm32f10x_md_gcc.S \ + $(BREEZY_DIR)/drv_spi.c \ + $(BREEZY_DIR)/drv_m25p16.c \ + $(BREEZY_DIR)/drv_flashfs.c \ + $(BREEZY_DIR)/drv_gpio.c \ + $(BREEZY_DIR)/drv_system.c \ + $(BREEZY_DIR)/drv_serial.c \ + $(BREEZY_DIR)/drv_uart.c \ + $(BREEZY_DIR)/printf.c \ + $(PROJECT_SRC) \ + $(CMSIS_SRC) \ + $(STDPERIPH_SRC) + +VPATH := $(SRC_DIR):$(SRC_DIR)/startups + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + +############################################################################### +# Things that might need changing to use different tools +# + +# Tool names +CC = arm-none-eabi-gcc -std=gnu99 +OBJCOPY = arm-none-eabi-objcopy + +# +# Tool options. +# +INCLUDE_DIRS = $(SRC_DIR) \ + $(BREEZY_DIR) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 + +ifeq ($(DEBUG),GDB) +OPTIMIZE = -Og + +else +OPTIMIZE = -Os +LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) +endif + +DEBUG_FLAGS = -ggdb3 + +CFLAGS = $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -Wall -pedantic -Wextra -Wshadow -Wunsafe-loop-optimizations \ + -ffunction-sections \ + -fdata-sections \ + -DSTM32F10X_MD \ + -DUSE_STDPERIPH_DRIVER \ + -D$(TARGET) + +ASFLAGS = $(ARCH_FLAGS) \ + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) + +LD_SCRIPT = $(BREEZY_DIR)/stm32_flash.ld +LDFLAGS = -lm \ + -nostartfiles \ + --specs=nano.specs \ + -lc \ + -lnosys \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_MAP) \ + -T$(LD_SCRIPT) + +# +# Things we will build +# + +TARGET_HEX = $(BIN_DIR)/$(TARGET).hex +TARGET_ELF = $(BIN_DIR)/$(TARGET).elf +TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) +TARGET_MAP = $(OBJECT_DIR)/$(TARGET).map + +# List of buildable ELF files and their object dependencies. +# It would be nice to compute these lists, but that seems to be just beyond make. + +$(TARGET_HEX): $(TARGET_ELF) + $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ + +$(TARGET_ELF): $(TARGET_OBJS) + $(CC) -o $@ $^ $(LDFLAGS) + +MKDIR_OBJDIR = @mkdir -p $(dir $@) + +# Compile +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + +# Assemble +$(OBJECT_DIR)/$(TARGET)/%.o: %.S + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(ASFLAGS) $< + +clean: + rm -rf *.o obj + +# Call this "upload" instead of "flash" to avoid confusion ;^) +upload_$(TARGET): $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +upload: upload_$(TARGET) + +flash: upload_$(TARGET) + +listen: + miniterm.py /dev/ttyUSB0 115200 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/memtest/memtest.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/memtest/memtest.c new file mode 100644 index 0000000..c6e353f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/memtest/memtest.c @@ -0,0 +1,50 @@ +/* + memsize.c : test the MP25P16 flash memory + + Copyright (C) 2016 Simon D. Levy + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include +#include + +const char * MESSAGE = "Hello, world!"; + +static int msglen; + +void setup(void) +{ + spiInit(SPI2); + m25p16_init(); + flashfsInit(); + + while (!flashfsIsReady()) + ; + + msglen = strlen(MESSAGE); + + flashfsWrite((uint8_t *)MESSAGE, msglen, true); // sync +} + +void loop(void) +{ + delay(500); + + char s[100]; // long enough for any message? + + printf("%s\n", flashfsReadAbs(0, (uint8_t *)s, msglen) < msglen ? "error reading bytes" : s); +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ms4525/Makefile b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ms4525/Makefile new file mode 100644 index 0000000..a2a800e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ms4525/Makefile @@ -0,0 +1,169 @@ +############################################################################### +# "THE BEER-WARE LICENSE" (Revision 42): +# wrote this file. As long as you retain this notice you +# can do whatever you want with this stuff. If we meet some day, and you think +# this stuff is worth it, you can buy me a beer in return + +############################################################################### + +# Change this to wherever you put BreezySTM32 +BREEZY_DIR = ../../ + +# Fill this out with source files for your specific project +PROJECT_SRC = ms4525.c + +############################################################################### + +# You probably shouldn't modify anything below here! + +TARGET ?= myproject + +# Compile-time options +OPTIONS ?= GDB + +# Debugger optons, must be empty or GDB +DEBUG ?= + +# Serial port/Device for flashing +SERIAL_DEVICE ?= /dev/ttyUSB0 + +# Working directories +ROOT = $(dir $(lastword $(MAKEFILE_LIST))) +SRC_DIR = $(ROOT) +CMSIS_DIR = $(BREEZY_DIR)/lib/CMSIS +STDPERIPH_DIR = $(BREEZY_DIR)/lib/STM32F10x_StdPeriph_Driver +OBJECT_DIR = $(ROOT)/obj +BIN_DIR = $(ROOT)/obj + +myproject_SRC = $(BREEZY_DIR)/main.c \ + $(BREEZY_DIR)/startup_stm32f10x_md_gcc.S \ + $(BREEZY_DIR)/drv_gpio.c \ + $(BREEZY_DIR)/drv_i2c.c \ + $(BREEZY_DIR)/drv_system.c \ + $(BREEZY_DIR)/drv_serial.c \ + $(BREEZY_DIR)/drv_uart.c \ + $(BREEZY_DIR)/drv_timer.c \ + $(BREEZY_DIR)/breezyprintf.c \ + $(BREEZY_DIR)/drv_mpu6050.c \ + $(BREEZY_DIR)/drv_ms4525.c \ + $(BREEZY_DIR)/drv_ms5611.c \ + $(PROJECT_SRC) \ + $(CMSIS_SRC) \ + $(STDPERIPH_SRC) + +VPATH := $(SRC_DIR):$(SRC_DIR)/startups + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + +############################################################################### +# Things that might need changing to use different tools +# + +# Tool names +CC = arm-none-eabi-gcc -std=gnu99 +OBJCOPY = arm-none-eabi-objcopy + +# +# Tool options. +# +INCLUDE_DIRS = $(SRC_DIR) \ + $(BREEZY_DIR) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 + +ifeq ($(DEBUG),GDB) +OPTIMIZE = -Og + +else +#OPTIMIZE = -Os +#LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) +endif + +DEBUG_FLAGS = -ggdb3 + +CFLAGS = $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -Wall -pedantic -Wextra -Wshadow -Wunsafe-loop-optimizations \ + -ffunction-sections \ + -fdata-sections \ + -DSTM32F10X_MD \ + -DUSE_STDPERIPH_DRIVER \ + -D$(TARGET) + +ASFLAGS = $(ARCH_FLAGS) \ + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) + +LD_SCRIPT = $(BREEZY_DIR)/stm32_flash.ld +LDFLAGS = -lm \ + -nostartfiles \ + --specs=nano.specs \ + -lc \ + -lnosys \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_MAP) \ + -T$(LD_SCRIPT) + +# +# Things we will build +# + +TARGET_HEX = $(BIN_DIR)/$(TARGET).hex +TARGET_ELF = $(BIN_DIR)/$(TARGET).elf +TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) +TARGET_MAP = $(OBJECT_DIR)/$(TARGET).map + +# List of buildable ELF files and their object dependencies. +# It would be nice to compute these lists, but that seems to be just beyond make. + +$(TARGET_HEX): $(TARGET_ELF) + $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ + +$(TARGET_ELF): $(TARGET_OBJS) + $(CC) -o $@ $^ $(LDFLAGS) + +MKDIR_OBJDIR = @mkdir -p $(dir $@) + +# Compile +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + +# Assemble +$(OBJECT_DIR)/$(TARGET)/%.o: %.S + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(ASFLAGS) $< + +clean: + rm -rf $(TARGET_HEX) $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) obj + +flash_$(TARGET): $(TARGET_HEX) + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 921600 $(SERIAL_DEVICE) + +flash: flash_$(TARGET) + +unbrick: $(TARGET_HEX) + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 921600 $(SERIAL_DEVICE) + +listen: + miniterm.py $(SERIAL_DEVICE) 115200 + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ms4525/ms4525.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ms4525/ms4525.c new file mode 100644 index 0000000..36ee67a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ms4525/ms4525.c @@ -0,0 +1,71 @@ +/* + ms4525.c : Airpseed Measurement Values + + Copyright (C) 2016 James Jackson + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include + +#include "math.h" + +bool airspeed_present = false; +bool barometer_present = false; + +void setup(void) +{ + delay(500); + i2cInit(I2CDEV_2); + + airspeed_present = ms4525_init(); + +// barometer_present = ms5611_init(); +} + + + +float pressure, altitude, temperature; +void loop(void) +{ +// ms5611_async_update(); + ms4525_async_update(); + + delay(10); + +// if (ms5611_present()) + { +// ms5611_async_read(&altitude, &pressure, &temperature); +// ms4525_set_atm((uint32_t) pressure); + } + if (ms4525_present()) + { + float velocity, diff_pressure, temp; + ms4525_async_read(&diff_pressure, &temp, &velocity); +// printf("calibrated = %d\tvel: %d.%d m/s\tdiff_press: %d.%dPa\ttemp:%d.%dK\n", + printf("%d.%d,\t%d.%d,\t%d.%d,\t%d.%d\n", +// ms4525_calibrated(), + (int32_t)velocity, (int32_t)(fabs(velocity)*1000)%1000, + (int32_t)diff_pressure, (int32_t)(fabs(diff_pressure)*1000)%1000, + (int32_t)temp, (int32_t)(temp*1000)%1000, + (int32_t)pressure, (int32_t)(pressure*1000)%1000); + } + else + { + printf("no airspeed\n"); + } +} + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ms5611/Makefile b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ms5611/Makefile new file mode 100644 index 0000000..078e0da --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ms5611/Makefile @@ -0,0 +1,170 @@ +############################################################################### +# "THE BEER-WARE LICENSE" (Revision 42): +# wrote this file. As long as you retain this notice you +# can do whatever you want with this stuff. If we meet some day, and you think +# this stuff is worth it, you can buy me a beer in return + +############################################################################### + +# Change this to wherever you put BreezySTM32 +BREEZY_DIR = ../../ + +# Fill this out with source files for your specific project +PROJECT_SRC = ms5611read.c + +############################################################################### + +# You probably shouldn't modify anything below here! + +TARGET ?= myproject + +# Compile-time options +OPTIONS ?= + +# Debugger optons, must be empty or GDB +DEBUG ?= GDB + +# Serial port/Device for flashing +SERIAL_DEVICE ?= /dev/ttyUSB0 + +# Working directories +ROOT = $(dir $(lastword $(MAKEFILE_LIST))) +SRC_DIR = $(ROOT) +CMSIS_DIR = $(BREEZY_DIR)/lib/CMSIS +STDPERIPH_DIR = $(BREEZY_DIR)/lib/STM32F10x_StdPeriph_Driver +OBJECT_DIR = $(ROOT)/obj +BIN_DIR = $(ROOT)/obj + +myproject_SRC = $(BREEZY_DIR)/main.c \ + $(BREEZY_DIR)/startup_stm32f10x_md_gcc.S \ + $(BREEZY_DIR)/drv_gpio.c \ + $(BREEZY_DIR)/drv_i2c.c \ + $(BREEZY_DIR)/drv_system.c \ + $(BREEZY_DIR)/drv_serial.c \ + $(BREEZY_DIR)/drv_uart.c \ + $(BREEZY_DIR)/drv_timer.c \ + $(BREEZY_DIR)/breezyprintf.c \ + $(BREEZY_DIR)/drv_mpu6050.c \ + $(BREEZY_DIR)/drv_ms5611.c \ + $(PROJECT_SRC) \ + $(CMSIS_SRC) \ + $(STDPERIPH_SRC) + +VPATH := $(SRC_DIR):$(SRC_DIR)/startups + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + +############################################################################### +# Things that might need changing to use different tools +# + +# Tool names +CC = arm-none-eabi-gcc -std=gnu99 +OBJCOPY = arm-none-eabi-objcopy + +# +# Tool options. +# +INCLUDE_DIRS = $(SRC_DIR) \ + $(BREEZY_DIR) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 + +ifeq ($(DEBUG),GDB) +OPTIMIZE = -Og + +else +OPTIMIZE = -Os +LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) +endif + +DEBUG_FLAGS = -ggdb3 + +CFLAGS = $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -Wall -pedantic -Wextra -Wshadow -Wunsafe-loop-optimizations \ + -ffunction-sections \ + -fdata-sections \ + -DSTM32F10X_MD \ + -DUSE_STDPERIPH_DRIVER \ + -D$(TARGET) + +ASFLAGS = $(ARCH_FLAGS) \ + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) + +LD_SCRIPT = $(BREEZY_DIR)/stm32_flash.ld +LDFLAGS = -lm \ + -nostartfiles \ + --specs=nano.specs \ + -lc \ + -lnosys \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_MAP) \ + -T$(LD_SCRIPT) + +# +# Things we will build +# + +TARGET_HEX = $(BIN_DIR)/$(TARGET).hex +TARGET_ELF = $(BIN_DIR)/$(TARGET).elf +TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) +TARGET_MAP = $(OBJECT_DIR)/$(TARGET).map + +# List of buildable ELF files and their object dependencies. +# It would be nice to compute these lists, but that seems to be just beyond make. + +$(TARGET_HEX): $(TARGET_ELF) + $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ + +$(TARGET_ELF): $(TARGET_OBJS) + $(CC) -o $@ $^ $(LDFLAGS) + +MKDIR_OBJDIR = @mkdir -p $(dir $@) + +# Compile +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + +# Assemble +$(OBJECT_DIR)/$(TARGET)/%.o: %.S + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(ASFLAGS) $< + +clean: + rm -rf $(TARGET_HEX) $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) obj + +flash_$(TARGET): $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +flash: flash_$(TARGET) + +unbrick: $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +listen: + miniterm.py $(SERIAL_DEVICE) 115200 + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ms5611/ms5611read.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ms5611/ms5611read.c new file mode 100644 index 0000000..9dbac98 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/ms5611/ms5611read.c @@ -0,0 +1,59 @@ +/* + ms5611read.c : read values from MS5611 barometer using I^2C + + Copyright (C) 2016 Simon D. Levy + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include + +static bool available; + +void setup(void) +{ + // Get particulars for board + i2cInit(I2CDEV_2); + + // Not sure why the ms5611 needs this, but without this line it doesn't work + i2cWrite(0,0,0); + + // attempt to initialize barometer + available = ms5611_init(); +} + +void loop(void) +{ + + float pressure, temperature; + if (available) { + ms5611_async_update(); + ms5611_async_read(&pressure, &temperature); + printf("Pressure: %d.%d Pa\tTemperature: %d.%d K, i2c_errors: %d\n", + (int32_t) pressure, + (int32_t) (pressure*1000) % 1000, + (int32_t) temperature, + (int32_t) (temperature*1000) % 1000, + (int32_t) i2cGetErrorCounter()); + } + else + { + ms5611_async_update(); + ms5611_present(); + printf("MS5611 unavailable\n"); + } + +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/multi_sense/Makefile b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/multi_sense/Makefile new file mode 100644 index 0000000..eba3901 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/multi_sense/Makefile @@ -0,0 +1,173 @@ +############################################################################### +# "THE BEER-WARE LICENSE" (Revision 42): +# wrote this file. As long as you retain this notice you +# can do whatever you want with this stuff. If we meet some day, and you think +# this stuff is worth it, you can buy me a beer in return + +############################################################################### + +# Change this to wherever you put BreezySTM32 +BREEZY_DIR = ../../ + +# Fill this out with source files for your specific project +PROJECT_SRC = multisense.c + +############################################################################### + +# You probably shouldn't modify anything below here! + +TARGET ?= myproject + +# Compile-time options +OPTIONS ?= + +# Debugger optons, must be empty or GDB +DEBUG ?= GDB + +# Serial port/Device for flashing +SERIAL_DEVICE ?= /dev/ttyUSB0 + +# Working directories +ROOT = $(dir $(lastword $(MAKEFILE_LIST))) +SRC_DIR = $(ROOT) +CMSIS_DIR = $(BREEZY_DIR)/lib/CMSIS +STDPERIPH_DIR = $(BREEZY_DIR)/lib/STM32F10x_StdPeriph_Driver +OBJECT_DIR = $(ROOT)/obj +BIN_DIR = $(ROOT)/obj + +myproject_SRC = $(BREEZY_DIR)/main.c \ + $(BREEZY_DIR)/startup_stm32f10x_md_gcc.S \ + $(BREEZY_DIR)/drv_gpio.c \ + $(BREEZY_DIR)/drv_i2c.c \ + $(BREEZY_DIR)/drv_system.c \ + $(BREEZY_DIR)/drv_serial.c \ + $(BREEZY_DIR)/drv_uart.c \ + $(BREEZY_DIR)/drv_timer.c \ + $(BREEZY_DIR)/breezyprintf.c \ + $(BREEZY_DIR)/drv_mpu6050.c \ + $(BREEZY_DIR)/drv_ms4525.c \ + $(BREEZY_DIR)/drv_ms5611.c \ + $(BREEZY_DIR)/drv_hmc5883l.c \ + $(BREEZY_DIR)/drv_mb1242.c \ + $(PROJECT_SRC) \ + $(CMSIS_SRC) \ + $(STDPERIPH_SRC) + +VPATH := $(SRC_DIR):$(SRC_DIR)/startups + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + +############################################################################### +# Things that might need changing to use different tools +# + +# Tool names +CC = arm-none-eabi-gcc -std=gnu99 +OBJCOPY = arm-none-eabi-objcopy + +# +# Tool options. +# +INCLUDE_DIRS = $(SRC_DIR) \ + $(BREEZY_DIR) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 + +ifeq ($(DEBUG),GDB) +OPTIMIZE = -Og + +else +OPTIMIZE = -Os +LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) +endif + +DEBUG_FLAGS = -ggdb3 + +CFLAGS = $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -Wall -pedantic -Wextra -Wshadow -Wunsafe-loop-optimizations \ + -ffunction-sections \ + -fdata-sections \ + -DSTM32F10X_MD \ + -DUSE_STDPERIPH_DRIVER \ + -D$(TARGET) + +ASFLAGS = $(ARCH_FLAGS) \ + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) + +LD_SCRIPT = $(BREEZY_DIR)/stm32_flash.ld +LDFLAGS = -lm \ + -nostartfiles \ + --specs=nano.specs \ + -lc \ + -lnosys \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_MAP) \ + -T$(LD_SCRIPT) + +# +# Things we will build +# + +TARGET_HEX = $(BIN_DIR)/$(TARGET).hex +TARGET_ELF = $(BIN_DIR)/$(TARGET).elf +TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) +TARGET_MAP = $(OBJECT_DIR)/$(TARGET).map + +# List of buildable ELF files and their object dependencies. +# It would be nice to compute these lists, but that seems to be just beyond make. + +$(TARGET_HEX): $(TARGET_ELF) + $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ + +$(TARGET_ELF): $(TARGET_OBJS) + $(CC) -o $@ $^ $(LDFLAGS) + +MKDIR_OBJDIR = @mkdir -p $(dir $@) + +# Compile +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + +# Assemble +$(OBJECT_DIR)/$(TARGET)/%.o: %.S + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(ASFLAGS) $< + +clean: + rm -rf $(TARGET_HEX) $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) obj + +flash_$(TARGET): $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 921600 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 921600 $(SERIAL_DEVICE) + +flash: flash_$(TARGET) + +unbrick: $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +listen: + miniterm.py $(SERIAL_DEVICE) 115200 + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/multi_sense/multisense.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/multi_sense/multisense.c new file mode 100644 index 0000000..5b0f772 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/multi_sense/multisense.c @@ -0,0 +1,122 @@ +/* + accelgyro.c : report accelerometer and gyroscope values + + Copyright (C) 2016 James Jackson + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include + +#define BOARD_REV 2 + +float accel_scale; // converts to units of m/s^2 +float gyro_scale; // converts to units of rad/s + +int16_t accel_data[3]; +int16_t gyro_data[3]; +volatile int16_t temp_data; +int16_t mag_data[3]; + +volatile uint8_t accel_status = 0; +volatile uint8_t gyro_status = 0; +volatile uint8_t temp_status = 0; +volatile bool mpu_new_measurement = false; + +uint32_t start_time = 0; + +bool baro_present= false; +bool mag_present=false; +bool sonar_present=false; +bool airspeed_present=false; +void setup(void) +{ + delay(500); + i2cInit(I2CDEV_2); + + // Init Baro + i2cWrite(0, 0, 0); + ms5611_init(); + + // Init Mag + hmc5883lInit(BOARD_REV); + + // Init Sonar + // mb1242_init(); + + // Init Airspeed + // airspeed_present = ms4525_detect(); + + //Init IMU (has to come last because of the ISR) + uint16_t acc1G; + mpu6050_init(true, &acc1G, &gyro_scale, BOARD_REV); + accel_scale = 9.80665f / acc1G; +} + +void loop(void) +{ + + float baro = 0; + float temp = 0; + // int32_t sonar = 0; + int32_t airspeed = 0; + // Update Baro + ms5611_async_update(); + if(ms5611_present()) + { + ms5611_async_read(&baro, &temp); + } + + // Update Mag + hmc5883l_request_async_update(); + if(hmc5883l_present()) + { + hmc5883l_async_read(mag_data); + } + + // // Update Sonar + // if(sonar_present) + // { + // sonar = mb1242_poll(); + // } + + // // Update Airspeed + // if(airspeed_present) + // { + // ms4525_request_async_update(); + // airspeed = ms4525_read_velocity(); + // } + + static uint64_t imu_timestamp_us = 0; + if (mpu6050_new_data()) + { + mpu6050_async_read_all(accel_data, &temp_data, gyro_data, &imu_timestamp_us); + } + + static uint32_t last_print_ms = 0; + // Throttle printing + if(millis() > last_print_ms + 10) + { + last_print_ms += 10; + printf("%d\t %d\t %d\t %d\t %d\t %d\n", + (int32_t)(accel_data[2]*accel_scale*1000.0f), + (int32_t)(gyro_data[2]*gyro_scale*1000.0f), + (int32_t)imu_timestamp_us, + (int32_t)mag_data[2], + (int32_t)baro, + (int32_t)i2cGetErrorCounter()); + } +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/sen13680/Makefile b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/sen13680/Makefile new file mode 100644 index 0000000..e858a06 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/sen13680/Makefile @@ -0,0 +1,173 @@ +############################################################################### +# "THE BEER-WARE LICENSE" (Revision 42): +# wrote this file. As long as you retain this notice you +# can do whatever you want with this stuff. If we meet some day, and you think +# this stuff is worth it, you can buy me a beer in return + +############################################################################### + +# Change this to wherever you put BreezySTM32 +BREEZY_DIR = ../../ + +# Fill this out with source files for your specific project +PROJECT_SRC = sen13680read.c + +############################################################################### + +# You probably shouldn't modify anything below here! + +TARGET ?= myproject + +# Compile-time options +OPTIONS ?= + +# Debugger optons, must be empty or GDB +DEBUG ?= GDB + +# Serial port/Device for flashing +SERIAL_DEVICE ?= /dev/ttyUSB0 + +# Working directories +ROOT = $(dir $(lastword $(MAKEFILE_LIST))) +SRC_DIR = $(ROOT) +CMSIS_DIR = $(BREEZY_DIR)/lib/CMSIS +STDPERIPH_DIR = $(BREEZY_DIR)/lib/STM32F10x_StdPeriph_Driver +OBJECT_DIR = $(ROOT)/obj +BIN_DIR = $(ROOT)/obj + +myproject_SRC = $(BREEZY_DIR)/main.c \ + $(BREEZY_DIR)/startup_stm32f10x_md_gcc.S \ + $(BREEZY_DIR)/drv_gpio.c \ + $(BREEZY_DIR)/drv_i2c.c \ + $(BREEZY_DIR)/drv_mb1242.c \ + $(BREEZY_DIR)/drv_sen13680.c \ + $(BREEZY_DIR)/drv_adc.c \ + $(BREEZY_DIR)/drv_spi.c \ + $(BREEZY_DIR)/drv_pwm.c \ + $(BREEZY_DIR)/drv_system.c \ + $(BREEZY_DIR)/drv_serial.c \ + $(BREEZY_DIR)/drv_uart.c \ + $(BREEZY_DIR)/drv_timer.c \ + $(BREEZY_DIR)/printf.c \ + $(PROJECT_SRC) \ + $(CMSIS_SRC) \ + $(STDPERIPH_SRC) + +VPATH := $(SRC_DIR):$(SRC_DIR)/startups + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + +############################################################################### +# Things that might need changing to use different tools +# + +# Tool names +CC = arm-none-eabi-gcc -std=gnu99 +OBJCOPY = arm-none-eabi-objcopy + +# +# Tool options. +# +INCLUDE_DIRS = $(SRC_DIR) \ + $(BREEZY_DIR) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 + +ifeq ($(DEBUG),GDB) +OPTIMIZE = -Og + +else +OPTIMIZE = -Os +LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) +endif + +DEBUG_FLAGS = -ggdb3 + +CFLAGS = $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -Wall -pedantic -Wextra -Wshadow -Wunsafe-loop-optimizations \ + -ffunction-sections \ + -fdata-sections \ + -DSTM32F10X_MD \ + -DUSE_STDPERIPH_DRIVER \ + -D$(TARGET) + +ASFLAGS = $(ARCH_FLAGS) \ + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) + +LD_SCRIPT = $(BREEZY_DIR)/stm32_flash.ld +LDFLAGS = -lm \ + -nostartfiles \ + --specs=nano.specs \ + -lc \ + -lnosys \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_MAP) \ + -T$(LD_SCRIPT) + +# +# Things we will build +# + +TARGET_HEX = $(BIN_DIR)/$(TARGET).hex +TARGET_ELF = $(BIN_DIR)/$(TARGET).elf +TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) +TARGET_MAP = $(OBJECT_DIR)/$(TARGET).map + +# List of buildable ELF files and their object dependencies. +# It would be nice to compute these lists, but that seems to be just beyond make. + +$(TARGET_HEX): $(TARGET_ELF) + $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ + +$(TARGET_ELF): $(TARGET_OBJS) + $(CC) -o $@ $^ $(LDFLAGS) + +MKDIR_OBJDIR = @mkdir -p $(dir $@) + +# Compile +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + +# Assemble +$(OBJECT_DIR)/$(TARGET)/%.o: %.S + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(ASFLAGS) $< + +clean: + rm -rf $(TARGET_HEX) $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) obj + +flash_$(TARGET): $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +flash: flash_$(TARGET) + +unbrick: $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +listen: + miniterm.py $(SERIAL_DEVICE) 115200 + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/sen13680/README.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/sen13680/README.md new file mode 100644 index 0000000..160c1ab --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/sen13680/README.md @@ -0,0 +1,3 @@ +# sen13680: Read distances from Sparkfun SEN13680 LIDAR-Lite v2 I2C sensor + +Don't forget to supply external power to the board! diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/sen13680/sen13680read.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/sen13680/sen13680read.c new file mode 100644 index 0000000..af60000 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/sen13680/sen13680read.c @@ -0,0 +1,51 @@ +/* + sen13680read.c : read values from Sparkfun SEN13680 LIDAR-Lite v2 I^2C lidar + + Don't forget to supply external power to the board! + + Copyright (C) 2016 Simon D. Levy + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include + +static bool lidar_present; + +// initialize i2c +void setup(void) +{ + i2cInit(I2CDEV_2); + i2cWrite(0, 0, 0); +} + +// look for the lidar and then read measurements +void loop(void) +{ + if(lidar_present) + { + sen13680_update(); + float distance = sen13680_read(); + printf("distance = %d.%dm\n", (uint32_t)distance, (uint32_t)(distance*1000)%1000); + } + else + { + printf("No lidar present. Reinitializing.\n"); + lidar_present = sen13680_init(); + } + delay(100); + LED1_TOGGLE; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/term/Makefile b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/term/Makefile new file mode 100644 index 0000000..69ee94a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/term/Makefile @@ -0,0 +1,168 @@ +############################################################################### +# "THE BEER-WARE LICENSE" (Revision 42): +# wrote this file. As long as you retain this notice you +# can do whatever you want with this stuff. If we meet some day, and you think +# this stuff is worth it, you can buy me a beer in return + +############################################################################### + +# Change this to wherever you put BreezySTM32 +BREEZY_DIR = ../../ + +# Fill this out with source files for your specific project +PROJECT_SRC = term.c + +############################################################################### + +# You probably shouldn't modify anything below here! + +TARGET ?= myproject + +# Compile-time options +OPTIONS ?= + +# Debugger optons, must be empty or GDB +DEBUG ?= GDB + +# Serial port/Device for flashing +SERIAL_DEVICE ?= /dev/ttyUSB0 + +# Working directories +ROOT = $(dir $(lastword $(MAKEFILE_LIST))) +SRC_DIR = $(ROOT) +CMSIS_DIR = $(BREEZY_DIR)/lib/CMSIS +STDPERIPH_DIR = $(BREEZY_DIR)/lib/STM32F10x_StdPeriph_Driver +OBJECT_DIR = $(ROOT)/obj +BIN_DIR = $(ROOT)/obj + +myproject_SRC = $(BREEZY_DIR)/main.c \ + $(BREEZY_DIR)/startup_stm32f10x_md_gcc.S \ + $(BREEZY_DIR)/drv_gpio.c \ + $(BREEZY_DIR)/drv_i2c.c \ + $(BREEZY_DIR)/drv_system.c \ + $(BREEZY_DIR)/drv_serial.c \ + $(BREEZY_DIR)/drv_uart.c \ + $(BREEZY_DIR)/drv_timer.c \ + $(BREEZY_DIR)/printf.c \ + $(PROJECT_SRC) \ + $(CMSIS_SRC) \ + $(STDPERIPH_SRC) + +VPATH := $(SRC_DIR):$(SRC_DIR)/startups + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + +############################################################################### +# Things that might need changing to use different tools +# + +# Tool names +CC = arm-none-eabi-gcc -std=gnu99 +OBJCOPY = arm-none-eabi-objcopy + +# +# Tool options. +# +INCLUDE_DIRS = $(SRC_DIR) \ + $(BREEZY_DIR) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 + +ifeq ($(DEBUG),GDB) +OPTIMIZE = -Og + +else +OPTIMIZE = -Os +LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE) +endif + +DEBUG_FLAGS = -ggdb3 + +CFLAGS = $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -Wall -pedantic -Wextra -Wshadow -Wunsafe-loop-optimizations \ + -ffunction-sections \ + -fdata-sections \ + -DSTM32F10X_MD \ + -DUSE_STDPERIPH_DRIVER \ + -D$(TARGET) + +ASFLAGS = $(ARCH_FLAGS) \ + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) + +LD_SCRIPT = $(BREEZY_DIR)/stm32_flash.ld +LDFLAGS = -lm \ + -nostartfiles \ + --specs=nano.specs \ + -lc \ + -lnosys \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_MAP) \ + -T$(LD_SCRIPT) + +# +# Things we will build +# + +TARGET_HEX = $(BIN_DIR)/$(TARGET).hex +TARGET_ELF = $(BIN_DIR)/$(TARGET).elf +TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) +TARGET_MAP = $(OBJECT_DIR)/$(TARGET).map + +# List of buildable ELF files and their object dependencies. +# It would be nice to compute these lists, but that seems to be just beyond make. + +$(TARGET_HEX): $(TARGET_ELF) + $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ + +$(TARGET_ELF): $(TARGET_OBJS) + $(CC) -o $@ $^ $(LDFLAGS) + +MKDIR_OBJDIR = @mkdir -p $(dir $@) + +# Compile +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + +# Assemble +$(OBJECT_DIR)/$(TARGET)/%.o: %.S + $(MKDIR_OBJDIR) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(ASFLAGS) $< + +clean: + rm -rf $(TARGET_HEX) $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) obj + +flash_$(TARGET): $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +flash: flash_$(TARGET) + +unbrick: $(TARGET_HEX) + stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +listen: + miniterm.py $(SERIAL_DEVICE) 115200 + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/term/README.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/term/README.md new file mode 100644 index 0000000..0a4edb2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/term/README.md @@ -0,0 +1,3 @@ +# i2csniff: Detect and report I2C devices + +Don't forget to supply external power for external sensors (like MB1242 sonar)! diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/term/term.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/term/term.c new file mode 100644 index 0000000..03d839d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/examples/term/term.c @@ -0,0 +1,58 @@ +/* + i2sniff.c : sniff and report I^2C devices + + Copyright (C) 2016 Simon D. Levy + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_adc.c + + Don't forget to supply external power for external sensors (like MB1242 sonar)! + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include + +void receive_cb(uint16_t c) +{ + printf('%c', (uint8_t)c); +} + +serialPort_t * Serial1; + +extern void SetSysClock(bool overclock); + +static void _putc(void *p, char c) +{ + (void)p; // avoid compiler warning about unused variable + serialWrite(Serial1, c); + + while (!isSerialTransmitBufferEmpty(Serial1)); +} + +int main(void) +{ + // Configure clock, this figures out HSE for hardware autodetect + SetSysClock(0); + + systemInit(); + + Serial1 = uartOpen(USART1, &receive_cb, 115200, MODE_RXTX); + + init_printf( NULL, _putc); + + while (1); +} + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/CoreSupport/core_cm3.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/CoreSupport/core_cm3.c new file mode 100644 index 0000000..67dd85b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/CoreSupport/core_cm3.c @@ -0,0 +1,784 @@ +/**************************************************************************//** + * @file core_cm3.c + * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Source File + * @version V1.30 + * @date 30. October 2009 + * + * @note + * Copyright (C) 2009 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#include + +/* define compiler specific symbols */ +#if defined ( __CC_ARM ) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + +#elif defined ( __ICCARM__ ) + #define __ASM __asm /*!< asm keyword for IAR Compiler */ + #define __INLINE inline /*!< inline keyword for IAR Compiler. Only avaiable in High optimization mode! */ + +#elif defined ( __GNUC__ ) + #define __ASM __asm /*!< asm keyword for GNU Compiler */ + #define __INLINE inline /*!< inline keyword for GNU Compiler */ + +#elif defined ( __TASKING__ ) + #define __ASM __asm /*!< asm keyword for TASKING Compiler */ + #define __INLINE inline /*!< inline keyword for TASKING Compiler */ + +#endif + + +/* ################### Compiler specific Intrinsics ########################### */ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +/** + * @brief Return the Process Stack Pointer + * + * @return ProcessStackPointer + * + * Return the actual process stack pointer + */ +__ASM uint32_t __get_PSP(void) +{ + mrs r0, psp + bx lr +} + +/** + * @brief Set the Process Stack Pointer + * + * @param topOfProcStack Process Stack Pointer + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +__ASM void __set_PSP(uint32_t topOfProcStack) +{ + msr psp, r0 + bx lr +} + +/** + * @brief Return the Main Stack Pointer + * + * @return Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +__ASM uint32_t __get_MSP(void) +{ + mrs r0, msp + bx lr +} + +/** + * @brief Set the Main Stack Pointer + * + * @param topOfMainStack Main Stack Pointer + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +__ASM void __set_MSP(uint32_t mainStackPointer) +{ + msr msp, r0 + bx lr +} + +/** + * @brief Reverse byte order in unsigned short value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in unsigned short value + */ +__ASM uint32_t __REV16(uint16_t value) +{ + rev16 r0, r0 + bx lr +} + +/** + * @brief Reverse byte order in signed short value with sign extension to integer + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in signed short value with sign extension to integer + */ +__ASM int32_t __REVSH(int16_t value) +{ + revsh r0, r0 + bx lr +} + + +#if (__ARMCC_VERSION < 400000) + +/** + * @brief Remove the exclusive lock created by ldrex + * + * Removes the exclusive lock which is created by ldrex. + */ +__ASM void __CLREX(void) +{ + clrex +} + +/** + * @brief Return the Base Priority value + * + * @return BasePriority + * + * Return the content of the base priority register + */ +__ASM uint32_t __get_BASEPRI(void) +{ + mrs r0, basepri + bx lr +} + +/** + * @brief Set the Base Priority value + * + * @param basePri BasePriority + * + * Set the base priority register + */ +__ASM void __set_BASEPRI(uint32_t basePri) +{ + msr basepri, r0 + bx lr +} + +/** + * @brief Return the Priority Mask value + * + * @return PriMask + * + * Return state of the priority mask bit from the priority mask register + */ +__ASM uint32_t __get_PRIMASK(void) +{ + mrs r0, primask + bx lr +} + +/** + * @brief Set the Priority Mask value + * + * @param priMask PriMask + * + * Set the priority mask bit in the priority mask register + */ +__ASM void __set_PRIMASK(uint32_t priMask) +{ + msr primask, r0 + bx lr +} + +/** + * @brief Return the Fault Mask value + * + * @return FaultMask + * + * Return the content of the fault mask register + */ +__ASM uint32_t __get_FAULTMASK(void) +{ + mrs r0, faultmask + bx lr +} + +/** + * @brief Set the Fault Mask value + * + * @param faultMask faultMask value + * + * Set the fault mask register + */ +__ASM void __set_FAULTMASK(uint32_t faultMask) +{ + msr faultmask, r0 + bx lr +} + +/** + * @brief Return the Control Register value + * + * @return Control value + * + * Return the content of the control register + */ +__ASM uint32_t __get_CONTROL(void) +{ + mrs r0, control + bx lr +} + +/** + * @brief Set the Control Register value + * + * @param control Control value + * + * Set the control register + */ +__ASM void __set_CONTROL(uint32_t control) +{ + msr control, r0 + bx lr +} + +#endif /* __ARMCC_VERSION */ + + + +#elif (defined (__ICCARM__)) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ +#pragma diag_suppress=Pe940 + +/** + * @brief Return the Process Stack Pointer + * + * @return ProcessStackPointer + * + * Return the actual process stack pointer + */ +uint32_t __get_PSP(void) +{ + __ASM("mrs r0, psp"); + __ASM("bx lr"); +} + +/** + * @brief Set the Process Stack Pointer + * + * @param topOfProcStack Process Stack Pointer + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +void __set_PSP(uint32_t topOfProcStack) +{ + __ASM("msr psp, r0"); + __ASM("bx lr"); +} + +/** + * @brief Return the Main Stack Pointer + * + * @return Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +uint32_t __get_MSP(void) +{ + __ASM("mrs r0, msp"); + __ASM("bx lr"); +} + +/** + * @brief Set the Main Stack Pointer + * + * @param topOfMainStack Main Stack Pointer + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +void __set_MSP(uint32_t topOfMainStack) +{ + __ASM("msr msp, r0"); + __ASM("bx lr"); +} + +/** + * @brief Reverse byte order in unsigned short value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in unsigned short value + */ +uint32_t __REV16(uint16_t value) +{ + __ASM("rev16 r0, r0"); + __ASM("bx lr"); +} + +/** + * @brief Reverse bit order of value + * + * @param value value to reverse + * @return reversed value + * + * Reverse bit order of value + */ +uint32_t __RBIT(uint32_t value) +{ + __ASM("rbit r0, r0"); + __ASM("bx lr"); +} + +/** + * @brief LDR Exclusive (8 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 8 bit values) + */ +uint8_t __LDREXB(uint8_t *addr) +{ + __ASM("ldrexb r0, [r0]"); + __ASM("bx lr"); +} + +/** + * @brief LDR Exclusive (16 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 16 bit values + */ +uint16_t __LDREXH(uint16_t *addr) +{ + __ASM("ldrexh r0, [r0]"); + __ASM("bx lr"); +} + +/** + * @brief LDR Exclusive (32 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 32 bit values + */ +uint32_t __LDREXW(uint32_t *addr) +{ + __ASM("ldrex r0, [r0]"); + __ASM("bx lr"); +} + +/** + * @brief STR Exclusive (8 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 8 bit values + */ +uint32_t __STREXB(uint8_t value, uint8_t *addr) +{ + __ASM("strexb r0, r0, [r1]"); + __ASM("bx lr"); +} + +/** + * @brief STR Exclusive (16 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 16 bit values + */ +uint32_t __STREXH(uint16_t value, uint16_t *addr) +{ + __ASM("strexh r0, r0, [r1]"); + __ASM("bx lr"); +} + +/** + * @brief STR Exclusive (32 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 32 bit values + */ +uint32_t __STREXW(uint32_t value, uint32_t *addr) +{ + __ASM("strex r0, r0, [r1]"); + __ASM("bx lr"); +} + +#pragma diag_default=Pe940 + + +#elif (defined (__GNUC__)) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +/** + * @brief Return the Process Stack Pointer + * + * @return ProcessStackPointer + * + * Return the actual process stack pointer + */ +uint32_t __get_PSP(void) __attribute__( ( naked ) ); +uint32_t __get_PSP(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, psp\n\t" + "MOV r0, %0 \n\t" + "BX lr \n\t" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Process Stack Pointer + * + * @param topOfProcStack Process Stack Pointer + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +void __set_PSP(uint32_t topOfProcStack) __attribute__( ( naked ) ); +void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0\n\t" + "BX lr \n\t" : : "r" (topOfProcStack) ); +} + +/** + * @brief Return the Main Stack Pointer + * + * @return Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +uint32_t __get_MSP(void) __attribute__( ( naked ) ); +uint32_t __get_MSP(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, msp\n\t" + "MOV r0, %0 \n\t" + "BX lr \n\t" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Main Stack Pointer + * + * @param topOfMainStack Main Stack Pointer + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +void __set_MSP(uint32_t topOfMainStack) __attribute__( ( naked ) ); +void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0\n\t" + "BX lr \n\t" : : "r" (topOfMainStack) ); +} + +/** + * @brief Return the Base Priority value + * + * @return BasePriority + * + * Return the content of the base priority register + */ +uint32_t __get_BASEPRI(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, basepri_max" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Base Priority value + * + * @param basePri BasePriority + * + * Set the base priority register + */ +void __set_BASEPRI(uint32_t value) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (value) ); +} + +/** + * @brief Return the Priority Mask value + * + * @return PriMask + * + * Return state of the priority mask bit from the priority mask register + */ +uint32_t __get_PRIMASK(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Priority Mask value + * + * @param priMask PriMask + * + * Set the priority mask bit in the priority mask register + */ +void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) ); +} + +/** + * @brief Return the Fault Mask value + * + * @return FaultMask + * + * Return the content of the fault mask register + */ +uint32_t __get_FAULTMASK(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Fault Mask value + * + * @param faultMask faultMask value + * + * Set the fault mask register + */ +void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) ); +} + +/** + * @brief Return the Control Register value +* +* @return Control value + * + * Return the content of the control register + */ +uint32_t __get_CONTROL(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Control Register value + * + * @param control Control value + * + * Set the control register + */ +void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) ); +} + + +/** + * @brief Reverse byte order in integer value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in integer value + */ +uint32_t __REV(uint32_t value) +{ + uint32_t result=0; + + __ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +/** + * @brief Reverse byte order in unsigned short value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in unsigned short value + */ +uint32_t __REV16(uint16_t value) +{ + uint32_t result=0; + + __ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +/** + * @brief Reverse byte order in signed short value with sign extension to integer + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in signed short value with sign extension to integer + */ +int32_t __REVSH(int16_t value) +{ + uint32_t result=0; + + __ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +/** + * @brief Reverse bit order of value + * + * @param value value to reverse + * @return reversed value + * + * Reverse bit order of value + */ +uint32_t __RBIT(uint32_t value) +{ + uint32_t result=0; + + __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +/** + * @brief LDR Exclusive (8 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 8 bit value + */ +uint8_t __LDREXB(uint8_t *addr) +{ + uint8_t result=0; + + __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + +/** + * @brief LDR Exclusive (16 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 16 bit values + */ +uint16_t __LDREXH(uint16_t *addr) +{ + uint16_t result=0; + + __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + +/** + * @brief LDR Exclusive (32 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 32 bit values + */ +uint32_t __LDREXW(uint32_t *addr) +{ + uint32_t result=0; + + __ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + +/** + * @brief STR Exclusive (8 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 8 bit values + */ +uint32_t __STREXB(uint8_t value, uint8_t *addr) +{ + uint32_t result=0; + + __ASM volatile ("strexb %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + return(result); +} + +/** + * @brief STR Exclusive (16 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 16 bit values + */ +uint32_t __STREXH(uint16_t value, uint16_t *addr) +{ + uint32_t result=0; + + __ASM volatile ("strexh %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + return(result); +} + +/** + * @brief STR Exclusive (32 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 32 bit values + */ +uint32_t __STREXW(uint32_t value, uint32_t *addr) +{ + uint32_t result=0; + + __ASM volatile ("strex %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) ); + return(result); +} + + +#elif (defined (__TASKING__)) /*------------------ TASKING Compiler ---------------------*/ +/* TASKING carm specific functions */ + +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all instrinsics, + * Including the CMSIS ones. + */ + +#endif diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/CoreSupport/core_cm3.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/CoreSupport/core_cm3.h new file mode 100644 index 0000000..a628192 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/CoreSupport/core_cm3.h @@ -0,0 +1,1820 @@ +/**************************************************************************//** + * @file core_cm3.h + * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File + * @version V1.30 + * @date 30. October 2009 + * + * @note + * Copyright (C) 2009 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#ifndef __CM3_CORE_H__ +#define __CM3_CORE_H__ + +/** @addtogroup CMSIS_CM3_core_LintCinfiguration CMSIS CM3 Core Lint Configuration + * + * List of Lint messages which will be suppressed and not shown: + * - Error 10: \n + * register uint32_t __regBasePri __asm("basepri"); \n + * Error 10: Expecting ';' + * . + * - Error 530: \n + * return(__regBasePri); \n + * Warning 530: Symbol '__regBasePri' (line 264) not initialized + * . + * - Error 550: \n + * __regBasePri = (basePri & 0x1ff); \n + * Warning 550: Symbol '__regBasePri' (line 271) not accessed + * . + * - Error 754: \n + * uint32_t RESERVED0[24]; \n + * Info 754: local structure member '' (line 109, file ./cm3_core.h) not referenced + * . + * - Error 750: \n + * #define __CM3_CORE_H__ \n + * Info 750: local macro '__CM3_CORE_H__' (line 43, file./cm3_core.h) not referenced + * . + * - Error 528: \n + * static __INLINE void NVIC_DisableIRQ(uint32_t IRQn) \n + * Warning 528: Symbol 'NVIC_DisableIRQ(unsigned int)' (line 419, file ./cm3_core.h) not referenced + * . + * - Error 751: \n + * } InterruptType_Type; \n + * Info 751: local typedef 'InterruptType_Type' (line 170, file ./cm3_core.h) not referenced + * . + * Note: To re-enable a Message, insert a space before 'lint' * + * + */ + +/*lint -save */ +/*lint -e10 */ +/*lint -e530 */ +/*lint -e550 */ +/*lint -e754 */ +/*lint -e750 */ +/*lint -e528 */ +/*lint -e751 */ + + +/** @addtogroup CMSIS_CM3_core_definitions CM3 Core Definitions + This file defines all structures and symbols for CMSIS core: + - CMSIS version number + - Cortex-M core registers and bitfields + - Cortex-M core peripheral base address + @{ + */ + +#ifdef __cplusplus + extern "C" { +#endif + +#define __CM3_CMSIS_VERSION_MAIN (0x01) /*!< [31:16] CMSIS HAL main version */ +#define __CM3_CMSIS_VERSION_SUB (0x30) /*!< [15:0] CMSIS HAL sub version */ +#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16) | __CM3_CMSIS_VERSION_SUB) /*!< CMSIS HAL version number */ + +#define __CORTEX_M (0x03) /*!< Cortex core */ + +#include /* Include standard types */ + +#if defined (__ICCARM__) + #include /* IAR Intrinsics */ +#endif + + +#ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 4 /*!< standard definition for NVIC Priority Bits */ +#endif + + + + +/** + * IO definitions + * + * define access restrictions to peripheral registers + */ + +#ifdef __cplusplus + #define __I volatile /*!< defines 'read only' permissions */ +#else + #define __I volatile const /*!< defines 'read only' permissions */ +#endif +#define __O volatile /*!< defines 'write only' permissions */ +#define __IO volatile /*!< defines 'read / write' permissions */ + + + +/******************************************************************************* + * Register Abstraction + ******************************************************************************/ +/** @addtogroup CMSIS_CM3_core_register CMSIS CM3 Core Register + @{ +*/ + + +/** @addtogroup CMSIS_CM3_NVIC CMSIS CM3 NVIC + memory mapped structure for Nested Vectored Interrupt Controller (NVIC) + @{ + */ +typedef struct +{ + __IO uint32_t ISER[8]; /*!< Offset: 0x000 Interrupt Set Enable Register */ + uint32_t RESERVED0[24]; + __IO uint32_t ICER[8]; /*!< Offset: 0x080 Interrupt Clear Enable Register */ + uint32_t RSERVED1[24]; + __IO uint32_t ISPR[8]; /*!< Offset: 0x100 Interrupt Set Pending Register */ + uint32_t RESERVED2[24]; + __IO uint32_t ICPR[8]; /*!< Offset: 0x180 Interrupt Clear Pending Register */ + uint32_t RESERVED3[24]; + __IO uint32_t IABR[8]; /*!< Offset: 0x200 Interrupt Active bit Register */ + uint32_t RESERVED4[56]; + __IO uint8_t IP[240]; /*!< Offset: 0x300 Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED5[644]; + __O uint32_t STIR; /*!< Offset: 0xE00 Software Trigger Interrupt Register */ +} NVIC_Type; +/*@}*/ /* end of group CMSIS_CM3_NVIC */ + + +/** @addtogroup CMSIS_CM3_SCB CMSIS CM3 SCB + memory mapped structure for System Control Block (SCB) + @{ + */ +typedef struct +{ + __I uint32_t CPUID; /*!< Offset: 0x00 CPU ID Base Register */ + __IO uint32_t ICSR; /*!< Offset: 0x04 Interrupt Control State Register */ + __IO uint32_t VTOR; /*!< Offset: 0x08 Vector Table Offset Register */ + __IO uint32_t AIRCR; /*!< Offset: 0x0C Application Interrupt / Reset Control Register */ + __IO uint32_t SCR; /*!< Offset: 0x10 System Control Register */ + __IO uint32_t CCR; /*!< Offset: 0x14 Configuration Control Register */ + __IO uint8_t SHP[12]; /*!< Offset: 0x18 System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IO uint32_t SHCSR; /*!< Offset: 0x24 System Handler Control and State Register */ + __IO uint32_t CFSR; /*!< Offset: 0x28 Configurable Fault Status Register */ + __IO uint32_t HFSR; /*!< Offset: 0x2C Hard Fault Status Register */ + __IO uint32_t DFSR; /*!< Offset: 0x30 Debug Fault Status Register */ + __IO uint32_t MMFAR; /*!< Offset: 0x34 Mem Manage Address Register */ + __IO uint32_t BFAR; /*!< Offset: 0x38 Bus Fault Address Register */ + __IO uint32_t AFSR; /*!< Offset: 0x3C Auxiliary Fault Status Register */ + __I uint32_t PFR[2]; /*!< Offset: 0x40 Processor Feature Register */ + __I uint32_t DFR; /*!< Offset: 0x48 Debug Feature Register */ + __I uint32_t ADR; /*!< Offset: 0x4C Auxiliary Feature Register */ + __I uint32_t MMFR[4]; /*!< Offset: 0x50 Memory Model Feature Register */ + __I uint32_t ISAR[5]; /*!< Offset: 0x60 ISA Feature Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFul << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFul << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFul << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFul << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1ul << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1ul << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1ul << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1ul << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1ul << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1ul << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1ul << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFul << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11 /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1ul << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFul << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_VTOR_TBLBASE_Pos 29 /*!< SCB VTOR: TBLBASE Position */ +#define SCB_VTOR_TBLBASE_Msk (0x1FFul << SCB_VTOR_TBLBASE_Pos) /*!< SCB VTOR: TBLBASE Mask */ + +#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x3FFFFFul << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFul << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFul << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1ul << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7ul << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1ul << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1ul << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + + /* SCB Configuration Control Register Definitions */ +#define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */ +#define SCB_AIRCR_VECTRESET_Msk (1ul << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1ul << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1ul << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1ul << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1ul << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8 /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1ul << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4 /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1ul << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1ul << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1 /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1ul << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +#define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */ +#define SCB_CCR_NONBASETHRDENA_Msk (1ul << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */ + + /* SCB Configuration Control Register Definitions */ +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_USGFAULTENA_Pos 18 /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1ul << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17 /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1ul << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16 /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1ul << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1ul << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14 /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1ul << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13 /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1ul << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12 /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1ul << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11 /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1ul << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10 /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1ul << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8 /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1ul << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7 /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1ul << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3 /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1ul << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1 /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1ul << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1ul << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Registers Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFul << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8 /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFul << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFul << SCB_CFSR_MEMFAULTSR_Pos) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* SCB Hard Fault Status Registers Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1ul << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30 /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1ul << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1 /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1ul << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4 /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1ul << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3 /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1ul << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2 /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1ul << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1 /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1ul << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1ul << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */ +/*@}*/ /* end of group CMSIS_CM3_SCB */ + + +/** @addtogroup CMSIS_CM3_SysTick CMSIS CM3 SysTick + memory mapped structure for SysTick + @{ + */ +typedef struct +{ + __IO uint32_t CTRL; /*!< Offset: 0x00 SysTick Control and Status Register */ + __IO uint32_t LOAD; /*!< Offset: 0x04 SysTick Reload Value Register */ + __IO uint32_t VAL; /*!< Offset: 0x08 SysTick Current Value Register */ + __I uint32_t CALIB; /*!< Offset: 0x0C SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1ul << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1ul << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1ul << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1ul << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFul << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFul << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1ul << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1ul << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFul << SysTick_VAL_CURRENT_Pos) /*!< SysTick CALIB: TENMS Mask */ +/*@}*/ /* end of group CMSIS_CM3_SysTick */ + + +/** @addtogroup CMSIS_CM3_ITM CMSIS CM3 ITM + memory mapped structure for Instrumentation Trace Macrocell (ITM) + @{ + */ +typedef struct +{ + __O union + { + __O uint8_t u8; /*!< Offset: ITM Stimulus Port 8-bit */ + __O uint16_t u16; /*!< Offset: ITM Stimulus Port 16-bit */ + __O uint32_t u32; /*!< Offset: ITM Stimulus Port 32-bit */ + } PORT [32]; /*!< Offset: 0x00 ITM Stimulus Port Registers */ + uint32_t RESERVED0[864]; + __IO uint32_t TER; /*!< Offset: ITM Trace Enable Register */ + uint32_t RESERVED1[15]; + __IO uint32_t TPR; /*!< Offset: ITM Trace Privilege Register */ + uint32_t RESERVED2[15]; + __IO uint32_t TCR; /*!< Offset: ITM Trace Control Register */ + uint32_t RESERVED3[29]; + __IO uint32_t IWR; /*!< Offset: ITM Integration Write Register */ + __IO uint32_t IRR; /*!< Offset: ITM Integration Read Register */ + __IO uint32_t IMCR; /*!< Offset: ITM Integration Mode Control Register */ + uint32_t RESERVED4[43]; + __IO uint32_t LAR; /*!< Offset: ITM Lock Access Register */ + __IO uint32_t LSR; /*!< Offset: ITM Lock Status Register */ + uint32_t RESERVED5[6]; + __I uint32_t PID4; /*!< Offset: ITM Peripheral Identification Register #4 */ + __I uint32_t PID5; /*!< Offset: ITM Peripheral Identification Register #5 */ + __I uint32_t PID6; /*!< Offset: ITM Peripheral Identification Register #6 */ + __I uint32_t PID7; /*!< Offset: ITM Peripheral Identification Register #7 */ + __I uint32_t PID0; /*!< Offset: ITM Peripheral Identification Register #0 */ + __I uint32_t PID1; /*!< Offset: ITM Peripheral Identification Register #1 */ + __I uint32_t PID2; /*!< Offset: ITM Peripheral Identification Register #2 */ + __I uint32_t PID3; /*!< Offset: ITM Peripheral Identification Register #3 */ + __I uint32_t CID0; /*!< Offset: ITM Component Identification Register #0 */ + __I uint32_t CID1; /*!< Offset: ITM Component Identification Register #1 */ + __I uint32_t CID2; /*!< Offset: ITM Component Identification Register #2 */ + __I uint32_t CID3; /*!< Offset: ITM Component Identification Register #3 */ +} ITM_Type; + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFul << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1ul << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_ATBID_Pos 16 /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_ATBID_Msk (0x7Ful << ITM_TCR_ATBID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_TSPrescale_Pos 8 /*!< ITM TCR: TSPrescale Position */ +#define ITM_TCR_TSPrescale_Msk (3ul << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ + +#define ITM_TCR_SWOENA_Pos 4 /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1ul << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_DWTENA_Pos 3 /*!< ITM TCR: DWTENA Position */ +#define ITM_TCR_DWTENA_Msk (1ul << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2 /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1ul << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1 /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1ul << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1ul << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */ + +/* ITM Integration Write Register Definitions */ +#define ITM_IWR_ATVALIDM_Pos 0 /*!< ITM IWR: ATVALIDM Position */ +#define ITM_IWR_ATVALIDM_Msk (1ul << ITM_IWR_ATVALIDM_Pos) /*!< ITM IWR: ATVALIDM Mask */ + +/* ITM Integration Read Register Definitions */ +#define ITM_IRR_ATREADYM_Pos 0 /*!< ITM IRR: ATREADYM Position */ +#define ITM_IRR_ATREADYM_Msk (1ul << ITM_IRR_ATREADYM_Pos) /*!< ITM IRR: ATREADYM Mask */ + +/* ITM Integration Mode Control Register Definitions */ +#define ITM_IMCR_INTEGRATION_Pos 0 /*!< ITM IMCR: INTEGRATION Position */ +#define ITM_IMCR_INTEGRATION_Msk (1ul << ITM_IMCR_INTEGRATION_Pos) /*!< ITM IMCR: INTEGRATION Mask */ + +/* ITM Lock Status Register Definitions */ +#define ITM_LSR_ByteAcc_Pos 2 /*!< ITM LSR: ByteAcc Position */ +#define ITM_LSR_ByteAcc_Msk (1ul << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ + +#define ITM_LSR_Access_Pos 1 /*!< ITM LSR: Access Position */ +#define ITM_LSR_Access_Msk (1ul << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ + +#define ITM_LSR_Present_Pos 0 /*!< ITM LSR: Present Position */ +#define ITM_LSR_Present_Msk (1ul << ITM_LSR_Present_Pos) /*!< ITM LSR: Present Mask */ +/*@}*/ /* end of group CMSIS_CM3_ITM */ + + +/** @addtogroup CMSIS_CM3_InterruptType CMSIS CM3 Interrupt Type + memory mapped structure for Interrupt Type + @{ + */ +typedef struct +{ + uint32_t RESERVED0; + __I uint32_t ICTR; /*!< Offset: 0x04 Interrupt Control Type Register */ +#if ((defined __CM3_REV) && (__CM3_REV >= 0x200)) + __IO uint32_t ACTLR; /*!< Offset: 0x08 Auxiliary Control Register */ +#else + uint32_t RESERVED1; +#endif +} InterruptType_Type; + +/* Interrupt Controller Type Register Definitions */ +#define InterruptType_ICTR_INTLINESNUM_Pos 0 /*!< InterruptType ICTR: INTLINESNUM Position */ +#define InterruptType_ICTR_INTLINESNUM_Msk (0x1Ful << InterruptType_ICTR_INTLINESNUM_Pos) /*!< InterruptType ICTR: INTLINESNUM Mask */ + +/* Auxiliary Control Register Definitions */ +#define InterruptType_ACTLR_DISFOLD_Pos 2 /*!< InterruptType ACTLR: DISFOLD Position */ +#define InterruptType_ACTLR_DISFOLD_Msk (1ul << InterruptType_ACTLR_DISFOLD_Pos) /*!< InterruptType ACTLR: DISFOLD Mask */ + +#define InterruptType_ACTLR_DISDEFWBUF_Pos 1 /*!< InterruptType ACTLR: DISDEFWBUF Position */ +#define InterruptType_ACTLR_DISDEFWBUF_Msk (1ul << InterruptType_ACTLR_DISDEFWBUF_Pos) /*!< InterruptType ACTLR: DISDEFWBUF Mask */ + +#define InterruptType_ACTLR_DISMCYCINT_Pos 0 /*!< InterruptType ACTLR: DISMCYCINT Position */ +#define InterruptType_ACTLR_DISMCYCINT_Msk (1ul << InterruptType_ACTLR_DISMCYCINT_Pos) /*!< InterruptType ACTLR: DISMCYCINT Mask */ +/*@}*/ /* end of group CMSIS_CM3_InterruptType */ + + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1) +/** @addtogroup CMSIS_CM3_MPU CMSIS CM3 MPU + memory mapped structure for Memory Protection Unit (MPU) + @{ + */ +typedef struct +{ + __I uint32_t TYPE; /*!< Offset: 0x00 MPU Type Register */ + __IO uint32_t CTRL; /*!< Offset: 0x04 MPU Control Register */ + __IO uint32_t RNR; /*!< Offset: 0x08 MPU Region RNRber Register */ + __IO uint32_t RBAR; /*!< Offset: 0x0C MPU Region Base Address Register */ + __IO uint32_t RASR; /*!< Offset: 0x10 MPU Region Attribute and Size Register */ + __IO uint32_t RBAR_A1; /*!< Offset: 0x14 MPU Alias 1 Region Base Address Register */ + __IO uint32_t RASR_A1; /*!< Offset: 0x18 MPU Alias 1 Region Attribute and Size Register */ + __IO uint32_t RBAR_A2; /*!< Offset: 0x1C MPU Alias 2 Region Base Address Register */ + __IO uint32_t RASR_A2; /*!< Offset: 0x20 MPU Alias 2 Region Attribute and Size Register */ + __IO uint32_t RBAR_A3; /*!< Offset: 0x24 MPU Alias 3 Region Base Address Register */ + __IO uint32_t RASR_A3; /*!< Offset: 0x28 MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; + +/* MPU Type Register */ +#define MPU_TYPE_IREGION_Pos 16 /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFul << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8 /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFul << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1ul << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register */ +#define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1ul << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1 /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1ul << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1ul << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register */ +#define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFul << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register */ +#define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0x7FFFFFFul << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4 /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1ul << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFul << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register */ +#define MPU_RASR_XN_Pos 28 /*!< MPU RASR: XN Position */ +#define MPU_RASR_XN_Msk (1ul << MPU_RASR_XN_Pos) /*!< MPU RASR: XN Mask */ + +#define MPU_RASR_AP_Pos 24 /*!< MPU RASR: AP Position */ +#define MPU_RASR_AP_Msk (7ul << MPU_RASR_AP_Pos) /*!< MPU RASR: AP Mask */ + +#define MPU_RASR_TEX_Pos 19 /*!< MPU RASR: TEX Position */ +#define MPU_RASR_TEX_Msk (7ul << MPU_RASR_TEX_Pos) /*!< MPU RASR: TEX Mask */ + +#define MPU_RASR_S_Pos 18 /*!< MPU RASR: Shareable bit Position */ +#define MPU_RASR_S_Msk (1ul << MPU_RASR_S_Pos) /*!< MPU RASR: Shareable bit Mask */ + +#define MPU_RASR_C_Pos 17 /*!< MPU RASR: Cacheable bit Position */ +#define MPU_RASR_C_Msk (1ul << MPU_RASR_C_Pos) /*!< MPU RASR: Cacheable bit Mask */ + +#define MPU_RASR_B_Pos 16 /*!< MPU RASR: Bufferable bit Position */ +#define MPU_RASR_B_Msk (1ul << MPU_RASR_B_Pos) /*!< MPU RASR: Bufferable bit Mask */ + +#define MPU_RASR_SRD_Pos 8 /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFul << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1 /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1Ful << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENA_Pos 0 /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENA_Msk (0x1Ful << MPU_RASR_ENA_Pos) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@}*/ /* end of group CMSIS_CM3_MPU */ +#endif + + +/** @addtogroup CMSIS_CM3_CoreDebug CMSIS CM3 Core Debug + memory mapped structure for Core Debug Register + @{ + */ +typedef struct +{ + __IO uint32_t DHCSR; /*!< Offset: 0x00 Debug Halting Control and Status Register */ + __O uint32_t DCRSR; /*!< Offset: 0x04 Debug Core Register Selector Register */ + __IO uint32_t DCRDR; /*!< Offset: 0x08 Debug Core Register Data Register */ + __IO uint32_t DEMCR; /*!< Offset: 0x0C Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16 /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFul << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25 /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1ul << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24 /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1ul << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19 /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1ul << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18 /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1ul << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17 /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1ul << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16 /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1ul << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5 /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1ul << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3 /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1ul << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2 /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1ul << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1 /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1ul << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1ul << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register */ +#define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1ul << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1Ful << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register */ +#define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1ul << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19 /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1ul << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18 /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1ul << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17 /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1ul << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16 /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1ul << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10 /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1ul << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9 /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1ul << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8 /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1ul << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7 /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1ul << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6 /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1ul << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5 /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1ul << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4 /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1ul << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1ul << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ +/*@}*/ /* end of group CMSIS_CM3_CoreDebug */ + + +/* Memory mapping of Cortex-M3 Hardware */ +#define SCS_BASE (0xE000E000) /*!< System Control Space Base Address */ +#define ITM_BASE (0xE0000000) /*!< ITM Base Address */ +#define CoreDebug_BASE (0xE000EDF0) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00) /*!< System Control Block Base Address */ + +#define InterruptType ((InterruptType_Type *) SCS_BASE) /*!< Interrupt Type Register */ +#define SCB ((SCB_Type *) SCB_BASE) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE) /*!< NVIC configuration struct */ +#define ITM ((ITM_Type *) ITM_BASE) /*!< ITM configuration struct */ +#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1) + #define MPU_BASE (SCS_BASE + 0x0D90) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type*) MPU_BASE) /*!< Memory Protection Unit */ +#endif + +/*@}*/ /* end of group CMSIS_CM3_core_register */ + + +/******************************************************************************* + * Hardware Abstraction Layer + ******************************************************************************/ + +#if defined ( __CC_ARM ) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + +#elif defined ( __ICCARM__ ) + #define __ASM __asm /*!< asm keyword for IAR Compiler */ + #define __INLINE inline /*!< inline keyword for IAR Compiler. Only avaiable in High optimization mode! */ + +#elif defined ( __GNUC__ ) + #define __ASM __asm /*!< asm keyword for GNU Compiler */ + #define __INLINE inline /*!< inline keyword for GNU Compiler */ + +#elif defined ( __TASKING__ ) + #define __ASM __asm /*!< asm keyword for TASKING Compiler */ + #define __INLINE inline /*!< inline keyword for TASKING Compiler */ + +#endif + + +/* ################### Compiler specific Intrinsics ########################### */ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +#define __enable_fault_irq __enable_fiq +#define __disable_fault_irq __disable_fiq + +#define __NOP __nop +#define __WFI __wfi +#define __WFE __wfe +#define __SEV __sev +#define __ISB() __isb(0) +#define __DSB() __dsb(0) +#define __DMB() __dmb(0) +#define __REV __rev +#define __RBIT __rbit +#define __LDREXB(ptr) ((unsigned char ) __ldrex(ptr)) +#define __LDREXH(ptr) ((unsigned short) __ldrex(ptr)) +#define __LDREXW(ptr) ((unsigned int ) __ldrex(ptr)) +#define __STREXB(value, ptr) __strex(value, ptr) +#define __STREXH(value, ptr) __strex(value, ptr) +#define __STREXW(value, ptr) __strex(value, ptr) + + +/* intrinsic unsigned long long __ldrexd(volatile void *ptr) */ +/* intrinsic int __strexd(unsigned long long val, volatile void *ptr) */ +/* intrinsic void __enable_irq(); */ +/* intrinsic void __disable_irq(); */ + + +/** + * @brief Return the Process Stack Pointer + * + * @return ProcessStackPointer + * + * Return the actual process stack pointer + */ +extern uint32_t __get_PSP(void); + +/** + * @brief Set the Process Stack Pointer + * + * @param topOfProcStack Process Stack Pointer + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +extern void __set_PSP(uint32_t topOfProcStack); + +/** + * @brief Return the Main Stack Pointer + * + * @return Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +extern uint32_t __get_MSP(void); + +/** + * @brief Set the Main Stack Pointer + * + * @param topOfMainStack Main Stack Pointer + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +extern void __set_MSP(uint32_t topOfMainStack); + +/** + * @brief Reverse byte order in unsigned short value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in unsigned short value + */ +extern uint32_t __REV16(uint16_t value); + +/** + * @brief Reverse byte order in signed short value with sign extension to integer + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in signed short value with sign extension to integer + */ +extern int32_t __REVSH(int16_t value); + + +#if (__ARMCC_VERSION < 400000) + +/** + * @brief Remove the exclusive lock created by ldrex + * + * Removes the exclusive lock which is created by ldrex. + */ +extern void __CLREX(void); + +/** + * @brief Return the Base Priority value + * + * @return BasePriority + * + * Return the content of the base priority register + */ +extern uint32_t __get_BASEPRI(void); + +/** + * @brief Set the Base Priority value + * + * @param basePri BasePriority + * + * Set the base priority register + */ +extern void __set_BASEPRI(uint32_t basePri); + +/** + * @brief Return the Priority Mask value + * + * @return PriMask + * + * Return state of the priority mask bit from the priority mask register + */ +extern uint32_t __get_PRIMASK(void); + +/** + * @brief Set the Priority Mask value + * + * @param priMask PriMask + * + * Set the priority mask bit in the priority mask register + */ +extern void __set_PRIMASK(uint32_t priMask); + +/** + * @brief Return the Fault Mask value + * + * @return FaultMask + * + * Return the content of the fault mask register + */ +extern uint32_t __get_FAULTMASK(void); + +/** + * @brief Set the Fault Mask value + * + * @param faultMask faultMask value + * + * Set the fault mask register + */ +extern void __set_FAULTMASK(uint32_t faultMask); + +/** + * @brief Return the Control Register value + * + * @return Control value + * + * Return the content of the control register + */ +extern uint32_t __get_CONTROL(void); + +/** + * @brief Set the Control Register value + * + * @param control Control value + * + * Set the control register + */ +extern void __set_CONTROL(uint32_t control); + +#else /* (__ARMCC_VERSION >= 400000) */ + +/** + * @brief Remove the exclusive lock created by ldrex + * + * Removes the exclusive lock which is created by ldrex. + */ +#define __CLREX __clrex + +/** + * @brief Return the Base Priority value + * + * @return BasePriority + * + * Return the content of the base priority register + */ +static __INLINE uint32_t __get_BASEPRI(void) +{ + register uint32_t __regBasePri __ASM("basepri"); + return(__regBasePri); +} + +/** + * @brief Set the Base Priority value + * + * @param basePri BasePriority + * + * Set the base priority register + */ +static __INLINE void __set_BASEPRI(uint32_t basePri) +{ + register uint32_t __regBasePri __ASM("basepri"); + __regBasePri = (basePri & 0xff); +} + +/** + * @brief Return the Priority Mask value + * + * @return PriMask + * + * Return state of the priority mask bit from the priority mask register + */ +static __INLINE uint32_t __get_PRIMASK(void) +{ + register uint32_t __regPriMask __ASM("primask"); + return(__regPriMask); +} + +/** + * @brief Set the Priority Mask value + * + * @param priMask PriMask + * + * Set the priority mask bit in the priority mask register + */ +static __INLINE void __set_PRIMASK(uint32_t priMask) +{ + register uint32_t __regPriMask __ASM("primask"); + __regPriMask = (priMask); +} + +/** + * @brief Return the Fault Mask value + * + * @return FaultMask + * + * Return the content of the fault mask register + */ +static __INLINE uint32_t __get_FAULTMASK(void) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + return(__regFaultMask); +} + +/** + * @brief Set the Fault Mask value + * + * @param faultMask faultMask value + * + * Set the fault mask register + */ +static __INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + __regFaultMask = (faultMask & 1); +} + +/** + * @brief Return the Control Register value + * + * @return Control value + * + * Return the content of the control register + */ +static __INLINE uint32_t __get_CONTROL(void) +{ + register uint32_t __regControl __ASM("control"); + return(__regControl); +} + +/** + * @brief Set the Control Register value + * + * @param control Control value + * + * Set the control register + */ +static __INLINE void __set_CONTROL(uint32_t control) +{ + register uint32_t __regControl __ASM("control"); + __regControl = control; +} + +#endif /* __ARMCC_VERSION */ + + + +#elif (defined (__ICCARM__)) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ + +#define __enable_irq __enable_interrupt /*!< global Interrupt enable */ +#define __disable_irq __disable_interrupt /*!< global Interrupt disable */ + +static __INLINE void __enable_fault_irq() { __ASM ("cpsie f"); } +static __INLINE void __disable_fault_irq() { __ASM ("cpsid f"); } + +#define __NOP __no_operation /*!< no operation intrinsic in IAR Compiler */ +static __INLINE void __WFI() { __ASM ("wfi"); } +static __INLINE void __WFE() { __ASM ("wfe"); } +static __INLINE void __SEV() { __ASM ("sev"); } +static __INLINE void __CLREX() { __ASM ("clrex"); } + +/* intrinsic void __ISB(void) */ +/* intrinsic void __DSB(void) */ +/* intrinsic void __DMB(void) */ +/* intrinsic void __set_PRIMASK(); */ +/* intrinsic void __get_PRIMASK(); */ +/* intrinsic void __set_FAULTMASK(); */ +/* intrinsic void __get_FAULTMASK(); */ +/* intrinsic uint32_t __REV(uint32_t value); */ +/* intrinsic uint32_t __REVSH(uint32_t value); */ +/* intrinsic unsigned long __STREX(unsigned long, unsigned long); */ +/* intrinsic unsigned long __LDREX(unsigned long *); */ + + +/** + * @brief Return the Process Stack Pointer + * + * @return ProcessStackPointer + * + * Return the actual process stack pointer + */ +extern uint32_t __get_PSP(void); + +/** + * @brief Set the Process Stack Pointer + * + * @param topOfProcStack Process Stack Pointer + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +extern void __set_PSP(uint32_t topOfProcStack); + +/** + * @brief Return the Main Stack Pointer + * + * @return Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +extern uint32_t __get_MSP(void); + +/** + * @brief Set the Main Stack Pointer + * + * @param topOfMainStack Main Stack Pointer + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +extern void __set_MSP(uint32_t topOfMainStack); + +/** + * @brief Reverse byte order in unsigned short value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in unsigned short value + */ +extern uint32_t __REV16(uint16_t value); + +/** + * @brief Reverse bit order of value + * + * @param value value to reverse + * @return reversed value + * + * Reverse bit order of value + */ +extern uint32_t __RBIT(uint32_t value); + +/** + * @brief LDR Exclusive (8 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 8 bit values) + */ +extern uint8_t __LDREXB(uint8_t *addr); + +/** + * @brief LDR Exclusive (16 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 16 bit values + */ +extern uint16_t __LDREXH(uint16_t *addr); + +/** + * @brief LDR Exclusive (32 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 32 bit values + */ +extern uint32_t __LDREXW(uint32_t *addr); + +/** + * @brief STR Exclusive (8 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 8 bit values + */ +extern uint32_t __STREXB(uint8_t value, uint8_t *addr); + +/** + * @brief STR Exclusive (16 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 16 bit values + */ +extern uint32_t __STREXH(uint16_t value, uint16_t *addr); + +/** + * @brief STR Exclusive (32 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 32 bit values + */ +extern uint32_t __STREXW(uint32_t value, uint32_t *addr); + + + +#elif (defined (__GNUC__)) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +static __INLINE void __enable_irq() { __ASM volatile ("cpsie i"); } +static __INLINE void __disable_irq() { __ASM volatile ("cpsid i"); } + +static __INLINE void __enable_fault_irq() { __ASM volatile ("cpsie f"); } +static __INLINE void __disable_fault_irq() { __ASM volatile ("cpsid f"); } + +static __INLINE void __NOP() { __ASM volatile ("nop"); } +static __INLINE void __WFI() { __ASM volatile ("wfi"); } +static __INLINE void __WFE() { __ASM volatile ("wfe"); } +static __INLINE void __SEV() { __ASM volatile ("sev"); } +static __INLINE void __ISB() { __ASM volatile ("isb"); } +static __INLINE void __DSB() { __ASM volatile ("dsb"); } +static __INLINE void __DMB() { __ASM volatile ("dmb"); } +static __INLINE void __CLREX() { __ASM volatile ("clrex"); } + + +/** + * @brief Return the Process Stack Pointer + * + * @return ProcessStackPointer + * + * Return the actual process stack pointer + */ +extern uint32_t __get_PSP(void); + +/** + * @brief Set the Process Stack Pointer + * + * @param topOfProcStack Process Stack Pointer + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +extern void __set_PSP(uint32_t topOfProcStack); + +/** + * @brief Return the Main Stack Pointer + * + * @return Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +extern uint32_t __get_MSP(void); + +/** + * @brief Set the Main Stack Pointer + * + * @param topOfMainStack Main Stack Pointer + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +extern void __set_MSP(uint32_t topOfMainStack); + +/** + * @brief Return the Base Priority value + * + * @return BasePriority + * + * Return the content of the base priority register + */ +extern uint32_t __get_BASEPRI(void); + +/** + * @brief Set the Base Priority value + * + * @param basePri BasePriority + * + * Set the base priority register + */ +extern void __set_BASEPRI(uint32_t basePri); + +/** + * @brief Return the Priority Mask value + * + * @return PriMask + * + * Return state of the priority mask bit from the priority mask register + */ +extern uint32_t __get_PRIMASK(void); + +/** + * @brief Set the Priority Mask value + * + * @param priMask PriMask + * + * Set the priority mask bit in the priority mask register + */ +extern void __set_PRIMASK(uint32_t priMask); + +/** + * @brief Return the Fault Mask value + * + * @return FaultMask + * + * Return the content of the fault mask register + */ +extern uint32_t __get_FAULTMASK(void); + +/** + * @brief Set the Fault Mask value + * + * @param faultMask faultMask value + * + * Set the fault mask register + */ +extern void __set_FAULTMASK(uint32_t faultMask); + +/** + * @brief Return the Control Register value +* +* @return Control value + * + * Return the content of the control register + */ +extern uint32_t __get_CONTROL(void); + +/** + * @brief Set the Control Register value + * + * @param control Control value + * + * Set the control register + */ +extern void __set_CONTROL(uint32_t control); + +/** + * @brief Reverse byte order in integer value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in integer value + */ +extern uint32_t __REV(uint32_t value); + +/** + * @brief Reverse byte order in unsigned short value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in unsigned short value + */ +extern uint32_t __REV16(uint16_t value); + +/** + * @brief Reverse byte order in signed short value with sign extension to integer + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in signed short value with sign extension to integer + */ +extern int32_t __REVSH(int16_t value); + +/** + * @brief Reverse bit order of value + * + * @param value value to reverse + * @return reversed value + * + * Reverse bit order of value + */ +extern uint32_t __RBIT(uint32_t value); + +/** + * @brief LDR Exclusive (8 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 8 bit value + */ +extern uint8_t __LDREXB(uint8_t *addr); + +/** + * @brief LDR Exclusive (16 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 16 bit values + */ +extern uint16_t __LDREXH(uint16_t *addr); + +/** + * @brief LDR Exclusive (32 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 32 bit values + */ +extern uint32_t __LDREXW(uint32_t *addr); + +/** + * @brief STR Exclusive (8 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 8 bit values + */ +extern uint32_t __STREXB(uint8_t value, uint8_t *addr); + +/** + * @brief STR Exclusive (16 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 16 bit values + */ +extern uint32_t __STREXH(uint16_t value, uint16_t *addr); + +/** + * @brief STR Exclusive (32 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 32 bit values + */ +extern uint32_t __STREXW(uint32_t value, uint32_t *addr); + + +#elif (defined (__TASKING__)) /*------------------ TASKING Compiler ---------------------*/ +/* TASKING carm specific functions */ + +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all instrinsics, + * Including the CMSIS ones. + */ + +#endif + + +/** @addtogroup CMSIS_CM3_Core_FunctionInterface CMSIS CM3 Core Function Interface + Core Function Interface containing: + - Core NVIC Functions + - Core SysTick Functions + - Core Reset Functions +*/ +/*@{*/ + +/* ########################## NVIC functions #################################### */ + +/** + * @brief Set the Priority Grouping in NVIC Interrupt Controller + * + * @param PriorityGroup is priority grouping field + * + * Set the priority grouping field using the required unlock sequence. + * The parameter priority_grouping is assigned to the field + * SCB->AIRCR [10:8] PRIGROUP field. Only values from 0..7 are used. + * In case of a conflict between priority grouping and available + * priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + */ +static __INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ + reg_value = (reg_value | + (0x5FA << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << 8)); /* Insert write key and priorty group */ + SCB->AIRCR = reg_value; +} + +/** + * @brief Get the Priority Grouping from NVIC Interrupt Controller + * + * @return priority grouping field + * + * Get the priority grouping from NVIC Interrupt Controller. + * priority grouping is SCB->AIRCR [10:8] PRIGROUP field. + */ +static __INLINE uint32_t NVIC_GetPriorityGrouping(void) +{ + return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */ +} + +/** + * @brief Enable Interrupt in NVIC Interrupt Controller + * + * @param IRQn The positive number of the external interrupt to enable + * + * Enable a device specific interupt in the NVIC interrupt controller. + * The interrupt number cannot be a negative value. + */ +static __INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) +{ + NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* enable interrupt */ +} + +/** + * @brief Disable the interrupt line for external interrupt specified + * + * @param IRQn The positive number of the external interrupt to disable + * + * Disable a device specific interupt in the NVIC interrupt controller. + * The interrupt number cannot be a negative value. + */ +static __INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) +{ + NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */ +} + +/** + * @brief Read the interrupt pending bit for a device specific interrupt source + * + * @param IRQn The number of the device specifc interrupt + * @return 1 = interrupt pending, 0 = interrupt not pending + * + * Read the pending register in NVIC and return 1 if its status is pending, + * otherwise it returns 0 + */ +static __INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */ +} + +/** + * @brief Set the pending bit for an external interrupt + * + * @param IRQn The number of the interrupt for set pending + * + * Set the pending bit for the specified interrupt. + * The interrupt number cannot be a negative value. + */ +static __INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */ +} + +/** + * @brief Clear the pending bit for an external interrupt + * + * @param IRQn The number of the interrupt for clear pending + * + * Clear the pending bit for the specified interrupt. + * The interrupt number cannot be a negative value. + */ +static __INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ +} + +/** + * @brief Read the active bit for an external interrupt + * + * @param IRQn The number of the interrupt for read active bit + * @return 1 = interrupt active, 0 = interrupt not active + * + * Read the active register in NVIC and returns 1 if its status is active, + * otherwise it returns 0. + */ +static __INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) +{ + return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */ +} + +/** + * @brief Set the priority for an interrupt + * + * @param IRQn The number of the interrupt for set priority + * @param priority The priority to set + * + * Set the priority for the specified interrupt. The interrupt + * number can be positive to specify an external (device specific) + * interrupt, or negative to specify an internal (core) interrupt. + * + * Note: The priority cannot be set for every core interrupt. + */ +static __INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if(IRQn < 0) { + SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M3 System Interrupts */ + else { + NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */ +} + +/** + * @brief Read the priority for an interrupt + * + * @param IRQn The number of the interrupt for get priority + * @return The priority for the interrupt + * + * Read the priority for the specified interrupt. The interrupt + * number can be positive to specify an external (device specific) + * interrupt, or negative to specify an internal (core) interrupt. + * + * The returned priority value is automatically aligned to the implemented + * priority bits of the microcontroller. + * + * Note: The priority cannot be set for every core interrupt. + */ +static __INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) +{ + + if(IRQn < 0) { + return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M3 system interrupts */ + else { + return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ +} + + +/** + * @brief Encode the priority for an interrupt + * + * @param PriorityGroup The used priority group + * @param PreemptPriority The preemptive priority value (starting from 0) + * @param SubPriority The sub priority value (starting from 0) + * @return The encoded priority for the interrupt + * + * Encode the priority for an interrupt with the given priority group, + * preemptive priority value and sub priority value. + * In case of a conflict between priority grouping and available + * priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. + * + * The returned priority value can be used for NVIC_SetPriority(...) function + */ +static __INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + return ( + ((PreemptPriority & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) | + ((SubPriority & ((1 << (SubPriorityBits )) - 1))) + ); +} + + +/** + * @brief Decode the priority of an interrupt + * + * @param Priority The priority for the interrupt + * @param PriorityGroup The used priority group + * @param pPreemptPriority The preemptive priority value (starting from 0) + * @param pSubPriority The sub priority value (starting from 0) + * + * Decode an interrupt priority value with the given priority group to + * preemptive priority value and sub priority value. + * In case of a conflict between priority grouping and available + * priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. + * + * The priority value can be retrieved with NVIC_GetPriority(...) function + */ +static __INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + *pPreemptPriority = (Priority >> SubPriorityBits) & ((1 << (PreemptPriorityBits)) - 1); + *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1); +} + + + +/* ################################## SysTick function ############################################ */ + +#if (!defined (__Vendor_SysTickConfig)) || (__Vendor_SysTickConfig == 0) + +/** + * @brief Initialize and start the SysTick counter and its interrupt. + * + * @param ticks number of ticks between two interrupts + * @return 1 = failed, 0 = successful + * + * Initialise the system tick timer and its interrupt and start the + * system tick timer / counter in free running mode to generate + * periodical interrupts. + */ +static __INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if (ticks > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + + SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Cortex-M0 System Interrupts */ + SysTick->VAL = 0; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0); /* Function successful */ +} + +#endif + + + + +/* ################################## Reset function ############################################ */ + +/** + * @brief Initiate a system reset request. + * + * Initiate a system reset request to reset the MCU + */ +static __INLINE void NVIC_SystemReset(void) +{ + SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + while(1); /* wait until reset */ +} + +/*@}*/ /* end of group CMSIS_CM3_Core_FunctionInterface */ + + + +/* ##################################### Debug In/Output function ########################################### */ + +/** @addtogroup CMSIS_CM3_CoreDebugInterface CMSIS CM3 Core Debug Interface + Core Debug Interface containing: + - Core Debug Receive / Transmit Functions + - Core Debug Defines + - Core Debug Variables +*/ +/*@{*/ + +extern volatile int ITM_RxBuffer; /*!< variable to receive characters */ +#define ITM_RXBUFFER_EMPTY 0x5AA55AA5 /*!< value identifying ITM_RxBuffer is ready for next character */ + + +/** + * @brief Outputs a character via the ITM channel 0 + * + * @param ch character to output + * @return character to output + * + * The function outputs a character via the ITM channel 0. + * The function returns when no debugger is connected that has booked the output. + * It is blocking when a debugger is connected, but the previous character send is not transmitted. + */ +static __INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if ((CoreDebug->DEMCR & CoreDebug_DEMCR_TRCENA_Msk) && /* Trace enabled */ + (ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */ + (ITM->TER & (1ul << 0) ) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0].u32 == 0); + ITM->PORT[0].u8 = (uint8_t) ch; + } + return (ch); +} + + +/** + * @brief Inputs a character via variable ITM_RxBuffer + * + * @return received character, -1 = no character received + * + * The function inputs a character via variable ITM_RxBuffer. + * The function returns when no debugger is connected that has booked the output. + * It is blocking when a debugger is connected, but the previous character send is not transmitted. + */ +static __INLINE int ITM_ReceiveChar (void) { + int ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** + * @brief Check if a character via variable ITM_RxBuffer is available + * + * @return 1 = character available, 0 = no character available + * + * The function checks variable ITM_RxBuffer whether a character is available or not. + * The function returns '1' if a character is available and '0' if no character is available. + */ +static __INLINE int ITM_CheckChar (void) { + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) { + return (0); /* no character available */ + } else { + return (1); /* character available */ + } +} + +/*@}*/ /* end of group CMSIS_CM3_core_DebugInterface */ + + +#ifdef __cplusplus +} +#endif + +/*@}*/ /* end of group CMSIS_CM3_core_definitions */ + +#endif /* __CM3_CORE_H__ */ + +/*lint -restore */ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/Release_Notes.html b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/Release_Notes.html new file mode 100644 index 0000000..fde27c9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/Release_Notes.html @@ -0,0 +1,284 @@ + + + + + + + + + + + + +Release Notes for STM32F10x CMSIS + + + + + +
+


+

+
+ + + + + + +
+ + + + + + + + + +
Back to Release page
+

Release +Notes for STM32F10x CMSIS

+

Copyright 2011 STMicroelectronics

+

+
+

 

+ + + + + + +
+

Contents

+
    +
  1. STM32F10x CMSIS +update History
  2. +
  3. License
  4. +
+ +

STM32F10x CMSIS +update History


+

V3.5.0 / 11-March-2011

+

Main +Changes

+ +
    +
  • stm32f10x.h +and startup_stm32f10x_hd_vl.s files: remove the FSMC interrupt +definition for STM32F10x High-density Value line devices.
    +
  • +
  • system_stm32f10x.c file provided within the CMSIS folder.
    +
  • + +
+ +

3.4.0 +- 10/15/2010

+ +
    +
  1. General
  2. +
+ +
    +
  • Add support +for STM32F10x High-density Value line devices.
  • +
+
    +
  1. STM32F10x CMSIS Device Peripheral Access Layer
  2. +
+ + + +
    +
  • STM32F10x CMSIS Cortex-M3 Device Peripheral Access Layer Header File: stm32f10x.h
    +
    • Update to support High-density Value line devices
      • Add new define STM32F10X_HD_VL
      • +
      • RCC, AFIO, FSMC bits definition updated
      • +
      +
    • + + All +STM32 devices definitions are commented by default. User has to select the +appropriate device before starting else an error will be signaled on compile +time.
    • +
    • Add new IRQs definitons inside the IRQn_Type enumeration for STM23 High-density Value line devices.
    • +
    • "bool" type removed.
      +
    • +
  • STM32F10x CMSIS Cortex-M3 Device Peripheral Access Layer System Files: system_stm32f10x.h and system_stm32f10x.c
    +
  • +
      +
    • "system_stm32f10x.c" moved to to "STM32F10x_StdPeriph_Template" directory. This file is also moved to each example directory under "STM32F10x_StdPeriph_Examples".
      +
    • +
    • SystemInit_ExtMemCtl() function: update to support High-density Value line devices.
    • +
    • Add "VECT_TAB_SRAM" inside "system_stm32f10x.c" +to select if the user want to place the Vector Table in internal SRAM. +An additional define is also to specify the Vector Table offset "VECT_TAB_OFFSET".
      +
    • + +
    +
  • STM32F10x CMSIS startup files:startup_stm32f10x_xx.s
    • Add three +startup files for STM32 High-density Value line devices: + startup_stm32f10x_hd_vl.s
    +
+

3.3.0 +- 04/16/2010

+ +
  1. General
+
  • Add support +for STM32F10x XL-density devices.
  • Add startup files for TrueSTUDIO toolchain
  1. STM32F10x CMSIS Device Peripheral Access Layer
+ +
  • STM32F10x CMSIS Cortex-M3 Device Peripheral Access Layer Header File: stm32f10x.h
    +
    • Update to support XL-density devices
      • Add new define STM32F10X_XL
      • Add new IRQs for TIM9..14
      • Update FLASH_TypeDef structure
      • Add new IP instances TIM9..14
      • RCC, AFIO, DBGMCU bits definition updated
    • Correct IRQs definition for MD-, LD-, MD_VL- and LD_VL-density devices (remove comma "," at the end of enum list)
  • STM32F10x CMSIS Cortex-M3 Device Peripheral Access Layer System Files: system_stm32f10x.h and system_stm32f10x.c
    +
    • SystemInit_ExtMemCtl() function: update to support XL-density devices
    • SystemInit() function: swap the order of SetSysClock() and SystemInit_ExtMemCtl() functions. 
      +
  • STM32F10x CMSIS startup files:
    • add three +startup files for STM32 XL-density devices: + startup_stm32f10x_xl.s
    • startup_stm32f10x_md_vl.s for RIDE7: add USART3 IRQ Handler (was missing in previous version)
    • Add startup files for TrueSTUDIO toolchain
+

3.2.0 +- 03/01/2010

+
    +
  1. General
  2. +
+
    + +
  • STM32F10x CMSIS files updated to CMSIS V1.30 release
  • +
  • Directory structure updated to be aligned with CMSIS V1.30
    +
  • +
  • Add support +for STM32 Low-density Value line (STM32F100x4/6) and +Medium-density Value line (STM32F100x8/B) devices
  • + +
+
    +
  1. CMSIS Core Peripheral Access Layer
+ +
    +
  1. STM32F10x CMSIS Device Peripheral Access Layer
  2. + +
+ +
    + +
  • STM32F10x CMSIS Cortex-M3 Device Peripheral Access Layer Header File: stm32f10x.h
    +
  • +
      +
    • Update +the stm32f10x.h file to support new Value line devices features: CEC +peripheral, new General purpose timers TIM15, TIM16 and TIM17.
    • +
    • Peripherals Bits definitions updated to be in line with Value line devices available features.
      +
    • +
    • HSE_Value, +HSI_Value and HSEStartup_TimeOut changed to upper case: HSE_VALUE, +HSI_VALUE and HSE_STARTUP_TIMEOUT. Old names are kept for legacy +purposes.
      +
    • +
    +
  • STM32F10x CMSIS Cortex-M3 Device Peripheral Access Layer System Files: system_stm32f10x.h and system_stm32f10x.c
    +
  • +
      +
    • SystemFrequency variable name changed to SystemCoreClock
      +
    • +
    • Default + SystemCoreClock is changed to 24MHz when Value line devices are selected and to 72MHz on other devices.
      +
    • +
    • All while(1) loop were removed from all clock setting functions. User has to handle the HSE startup failure.
      +
    • +
    • Additional function void SystemCoreClockUpdate (void) is provided.
      +
    • +
    +
  • STM32F10x CMSIS Startup files: startup_stm32f10x_xx.s
  • +
      +
    • Add new +startup files for STM32 Low-density Value line devices: + startup_stm32f10x_ld_vl.s
    • +
    • Add new startup +files for STM32 Medium-density Value line devices: + startup_stm32f10x_md_vl.s
    • +
    • SystemInit() function is called from startup file (startup_stm32f10x_xx.s) before to branch to application main.
      +To reconfigure the default setting of SystemInit() function, refer to system_stm32f10x.c file
      +
    • +
    • GNU startup file for Low density devices (startup_stm32f10x_ld.s) is updated to fix compilation errors.
      +
    • +
    + +
+ +
    +
+

License

+

The +enclosed firmware and all the related documentation are not covered by +a License Agreement, if you need such License you can contact your +local STMicroelectronics office.

+

THE +PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO +SAVE TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR +ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY +CLAIMS ARISING FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY +CUSTOMERS OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH +THEIR PRODUCTS.

+

 

+
+
+

For +complete documentation on STM32(CORTEX M3) 32-Bit Microcontrollers +visit www.st.com/STM32

+
+

+
+
+

 

+
+ \ No newline at end of file diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_cl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_cl.s new file mode 100644 index 0000000..d84d468 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_cl.s @@ -0,0 +1,473 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_cl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Connectivity line Devices vector table for Atollic + * toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR + * address. + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss + +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler + +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word CAN1_TX_IRQHandler + .word CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word OTG_FS_WKUP_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_IRQHandler + .word DMA2_Channel5_IRQHandler + .word ETH_IRQHandler + .word ETH_WKUP_IRQHandler + .word CAN2_TX_IRQHandler + .word CAN2_RX0_IRQHandler + .word CAN2_RX1_IRQHandler + .word CAN2_SCE_IRQHandler + .word OTG_FS_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x Connectivity line Devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak CAN1_TX_IRQHandler + .thumb_set CAN1_TX_IRQHandler,Default_Handler + + .weak CAN1_RX0_IRQHandler + .thumb_set CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak OTG_FS_WKUP_IRQHandler + .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_IRQHandler + .thumb_set DMA2_Channel4_IRQHandler,Default_Handler + + .weak DMA2_Channel5_IRQHandler + .thumb_set DMA2_Channel5_IRQHandler,Default_Handler + + .weak ETH_IRQHandler + .thumb_set ETH_IRQHandler,Default_Handler + + .weak ETH_WKUP_IRQHandler + .thumb_set ETH_WKUP_IRQHandler,Default_Handler + + .weak CAN2_TX_IRQHandler + .thumb_set CAN2_TX_IRQHandler,Default_Handler + + .weak CAN2_RX0_IRQHandler + .thumb_set CAN2_RX0_IRQHandler,Default_Handler + + .weak CAN2_RX1_IRQHandler + .thumb_set CAN2_RX1_IRQHandler,Default_Handler + + .weak CAN2_SCE_IRQHandler + .thumb_set CAN2_SCE_IRQHandler,Default_Handler + + .weak OTG_FS_IRQHandler + .thumb_set OTG_FS_IRQHandler ,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_hd.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_hd.s new file mode 100644 index 0000000..a93e59b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_hd.s @@ -0,0 +1,469 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_hd.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x High Density Devices vector table for Atollic toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address, + * - Configure the clock system + * - Configure external SRAM mounted on STM3210E-EVAL board + * to be used as data memory (optional, to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word TIM8_BRK_IRQHandler + .word TIM8_UP_IRQHandler + .word TIM8_TRG_COM_IRQHandler + .word TIM8_CC_IRQHandler + .word ADC3_IRQHandler + .word FSMC_IRQHandler + .word SDIO_IRQHandler + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_5_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x High Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + .weak TIM8_BRK_IRQHandler + .thumb_set TIM8_BRK_IRQHandler,Default_Handler + + .weak TIM8_UP_IRQHandler + .thumb_set TIM8_UP_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_IRQHandler + .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak ADC3_IRQHandler + .thumb_set ADC3_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_5_IRQHandler + .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_hd_vl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_hd_vl.s new file mode 100644 index 0000000..4945a70 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_hd_vl.s @@ -0,0 +1,451 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_hd_vl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x High Density Value Line Devices vector table for Atollic + * toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Configure external SRAM mounted on STM32100E-EVAL board + * to be used as data memory (optional, to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM15_IRQHandler + .word TIM1_UP_TIM16_IRQHandler + .word TIM1_TRG_COM_TIM17_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word CEC_IRQHandler + .word TIM12_IRQHandler + .word TIM13_IRQHandler + .word TIM14_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_DAC_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_5_IRQHandler + .word DMA2_Channel5_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x High Density Value line devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM15_IRQHandler + .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM16_IRQHandler + .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM17_IRQHandler + .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak CEC_IRQHandler + .thumb_set CEC_IRQHandler,Default_Handler + + .weak TIM12_IRQHandler + .thumb_set TIM12_IRQHandler,Default_Handler + + .weak TIM13_IRQHandler + .thumb_set TIM13_IRQHandler,Default_Handler + + .weak TIM14_IRQHandler + .thumb_set TIM14_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_5_IRQHandler + .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler + + .weak DMA2_Channel5_IRQHandler + .thumb_set DMA2_Channel5_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_ld.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_ld.s new file mode 100644 index 0000000..5f9df3d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_ld.s @@ -0,0 +1,347 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_ld.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Low Density Devices vector table for Atollic toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address. + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word 0 + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word 0 + .word 0 + .word SPI1_IRQHandler + .word 0 + .word USART1_IRQHandler + .word USART2_IRQHandler + .word 0 + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Low Density devices.*/ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_ld_vl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_ld_vl.s new file mode 100644 index 0000000..3224b40 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_ld_vl.s @@ -0,0 +1,392 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_ld_vl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Low Density Value Line Devices vector table for Atollic toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM15_IRQHandler + .word TIM1_UP_TIM16_IRQHandler + .word TIM1_TRG_COM_TIM17_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word 0 + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word 0 + .word 0 + .word SPI1_IRQHandler + .word 0 + .word USART1_IRQHandler + .word USART2_IRQHandler + .word 0 + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word CEC_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM6_DAC_IRQHandler + .word TIM7_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x01CC. This is for boot in RAM mode for + STM32F10x Medium Value Line Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM15_IRQHandler + .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM16_IRQHandler + .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM17_IRQHandler + .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak CEC_IRQHandler + .thumb_set CEC_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_md.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_md.s new file mode 100644 index 0000000..bec2639 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_md.s @@ -0,0 +1,363 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_md.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Medium Density Devices vector table for Atollic toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Medium Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_md_vl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_md_vl.s new file mode 100644 index 0000000..b2fd0db --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_md_vl.s @@ -0,0 +1,408 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_md_vl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Medium Density Value Line Devices vector table for Atollic + * toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM15_IRQHandler + .word TIM1_UP_TIM16_IRQHandler + .word TIM1_TRG_COM_TIM17_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word CEC_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM6_DAC_IRQHandler + .word TIM7_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x01CC. This is for boot in RAM mode for + STM32F10x Medium Value Line Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM15_IRQHandler + .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM16_IRQHandler + .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM17_IRQHandler + .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak CEC_IRQHandler + .thumb_set CEC_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_xl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_xl.s new file mode 100644 index 0000000..baf697b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_xl.s @@ -0,0 +1,467 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_xl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x XL-Density Devices vector table for TrueSTUDIO toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system and the external SRAM mounted on + * STM3210E-EVAL board to be used as data memory (optional, + * to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM9_IRQHandler + .word TIM1_UP_TIM10_IRQHandler + .word TIM1_TRG_COM_TIM11_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word TIM8_BRK_TIM12_IRQHandler + .word TIM8_UP_TIM13_IRQHandler + .word TIM8_TRG_COM_TIM14_IRQHandler + .word TIM8_CC_IRQHandler + .word ADC3_IRQHandler + .word FSMC_IRQHandler + .word SDIO_IRQHandler + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_5_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x XL-Density devices. */ +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM9_IRQHandler + .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM10_IRQHandler + .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM11_IRQHandler + .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + .weak TIM8_BRK_TIM12_IRQHandler + .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler + + .weak TIM8_UP_TIM13_IRQHandler + .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_TIM14_IRQHandler + .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak ADC3_IRQHandler + .thumb_set ADC3_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_5_IRQHandler + .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_cl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_cl.s new file mode 100644 index 0000000..833ece4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_cl.s @@ -0,0 +1,368 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_cl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Connectivity line devices vector table for MDK-ARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 and ADC2 + DCD CAN1_TX_IRQHandler ; CAN1 TX + DCD CAN1_RX0_IRQHandler ; CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C1 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC alarm through EXTI line + DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_IRQHandler ; TIM6 + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_IRQHandler ; DMA2 Channel4 + DCD DMA2_Channel5_IRQHandler ; DMA2 Channel5 + DCD ETH_IRQHandler ; Ethernet + DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line + DCD CAN2_TX_IRQHandler ; CAN2 TX + DCD CAN2_RX0_IRQHandler ; CAN2 RX0 + DCD CAN2_RX1_IRQHandler ; CAN2 RX1 + DCD CAN2_SCE_IRQHandler ; CAN2 SCE + DCD OTG_FS_IRQHandler ; USB OTG FS +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT SystemInit + IMPORT __main + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_2_IRQHandler [WEAK] + EXPORT CAN1_TX_IRQHandler [WEAK] + EXPORT CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_IRQHandler [WEAK] + EXPORT TIM1_UP_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT TIM4_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT OTG_FS_WKUP_IRQHandler [WEAK] + EXPORT TIM5_IRQHandler [WEAK] + EXPORT SPI3_IRQHandler [WEAK] + EXPORT UART4_IRQHandler [WEAK] + EXPORT UART5_IRQHandler [WEAK] + EXPORT TIM6_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] + EXPORT DMA2_Channel1_IRQHandler [WEAK] + EXPORT DMA2_Channel2_IRQHandler [WEAK] + EXPORT DMA2_Channel3_IRQHandler [WEAK] + EXPORT DMA2_Channel4_IRQHandler [WEAK] + EXPORT DMA2_Channel5_IRQHandler [WEAK] + EXPORT ETH_IRQHandler [WEAK] + EXPORT ETH_WKUP_IRQHandler [WEAK] + EXPORT CAN2_TX_IRQHandler [WEAK] + EXPORT CAN2_RX0_IRQHandler [WEAK] + EXPORT CAN2_RX1_IRQHandler [WEAK] + EXPORT CAN2_SCE_IRQHandler [WEAK] + EXPORT OTG_FS_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_2_IRQHandler +CAN1_TX_IRQHandler +CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_IRQHandler +TIM1_UP_IRQHandler +TIM1_TRG_COM_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +TIM4_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +OTG_FS_WKUP_IRQHandler +TIM5_IRQHandler +SPI3_IRQHandler +UART4_IRQHandler +UART5_IRQHandler +TIM6_IRQHandler +TIM7_IRQHandler +DMA2_Channel1_IRQHandler +DMA2_Channel2_IRQHandler +DMA2_Channel3_IRQHandler +DMA2_Channel4_IRQHandler +DMA2_Channel5_IRQHandler +ETH_IRQHandler +ETH_WKUP_IRQHandler +CAN2_TX_IRQHandler +CAN2_RX0_IRQHandler +CAN2_RX1_IRQHandler +CAN2_SCE_IRQHandler +OTG_FS_IRQHandler + + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_hd.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_hd.s new file mode 100644 index 0000000..8a19827 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_hd.s @@ -0,0 +1,358 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_hd.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x High Density Devices vector table for MDK-ARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system and also configure the external +;* SRAM mounted on STM3210E-EVAL board to be used as data +;* memory (optional, to be enabled by user) +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 & ADC2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend + DCD TIM8_BRK_IRQHandler ; TIM8 Break + DCD TIM8_UP_IRQHandler ; TIM8 Update + DCD TIM8_TRG_COM_IRQHandler ; TIM8 Trigger and Commutation + DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare + DCD ADC3_IRQHandler ; ADC3 + DCD FSMC_IRQHandler ; FSMC + DCD SDIO_IRQHandler ; SDIO + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_IRQHandler ; TIM6 + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5 +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_2_IRQHandler [WEAK] + EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK] + EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_IRQHandler [WEAK] + EXPORT TIM1_UP_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT TIM4_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT USBWakeUp_IRQHandler [WEAK] + EXPORT TIM8_BRK_IRQHandler [WEAK] + EXPORT TIM8_UP_IRQHandler [WEAK] + EXPORT TIM8_TRG_COM_IRQHandler [WEAK] + EXPORT TIM8_CC_IRQHandler [WEAK] + EXPORT ADC3_IRQHandler [WEAK] + EXPORT FSMC_IRQHandler [WEAK] + EXPORT SDIO_IRQHandler [WEAK] + EXPORT TIM5_IRQHandler [WEAK] + EXPORT SPI3_IRQHandler [WEAK] + EXPORT UART4_IRQHandler [WEAK] + EXPORT UART5_IRQHandler [WEAK] + EXPORT TIM6_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] + EXPORT DMA2_Channel1_IRQHandler [WEAK] + EXPORT DMA2_Channel2_IRQHandler [WEAK] + EXPORT DMA2_Channel3_IRQHandler [WEAK] + EXPORT DMA2_Channel4_5_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_2_IRQHandler +USB_HP_CAN1_TX_IRQHandler +USB_LP_CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_IRQHandler +TIM1_UP_IRQHandler +TIM1_TRG_COM_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +TIM4_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +USBWakeUp_IRQHandler +TIM8_BRK_IRQHandler +TIM8_UP_IRQHandler +TIM8_TRG_COM_IRQHandler +TIM8_CC_IRQHandler +ADC3_IRQHandler +FSMC_IRQHandler +SDIO_IRQHandler +TIM5_IRQHandler +SPI3_IRQHandler +UART4_IRQHandler +UART5_IRQHandler +TIM6_IRQHandler +TIM7_IRQHandler +DMA2_Channel1_IRQHandler +DMA2_Channel2_IRQHandler +DMA2_Channel3_IRQHandler +DMA2_Channel4_5_IRQHandler + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_hd_vl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_hd_vl.s new file mode 100644 index 0000000..2768298 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_hd_vl.s @@ -0,0 +1,346 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_hd_vl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x High Density Value Line Devices vector table +;* for MDK-ARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system and also configure the external +;* SRAM mounted on STM32100E-EVAL board to be used as data +;* memory (optional, to be enabled by user) +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger and Commutation and TIM17 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD CEC_IRQHandler ; HDMI-CEC + DCD TIM12_IRQHandler ; TIM12 + DCD TIM13_IRQHandler ; TIM13 + DCD TIM14_IRQHandler ; TIM14 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC underrun + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5 + DCD DMA2_Channel5_IRQHandler ; DMA2 Channel5 +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_TIM15_IRQHandler [WEAK] + EXPORT TIM1_UP_TIM16_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_TIM17_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT TIM4_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT CEC_IRQHandler [WEAK] + EXPORT TIM12_IRQHandler [WEAK] + EXPORT TIM13_IRQHandler [WEAK] + EXPORT TIM14_IRQHandler [WEAK] + EXPORT TIM5_IRQHandler [WEAK] + EXPORT SPI3_IRQHandler [WEAK] + EXPORT UART4_IRQHandler [WEAK] + EXPORT UART5_IRQHandler [WEAK] + EXPORT TIM6_DAC_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] + EXPORT DMA2_Channel1_IRQHandler [WEAK] + EXPORT DMA2_Channel2_IRQHandler [WEAK] + EXPORT DMA2_Channel3_IRQHandler [WEAK] + EXPORT DMA2_Channel4_5_IRQHandler [WEAK] + EXPORT DMA2_Channel5_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_TIM15_IRQHandler +TIM1_UP_TIM16_IRQHandler +TIM1_TRG_COM_TIM17_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +TIM4_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +CEC_IRQHandler +TIM12_IRQHandler +TIM13_IRQHandler +TIM14_IRQHandler +TIM5_IRQHandler +SPI3_IRQHandler +UART4_IRQHandler +UART5_IRQHandler +TIM6_DAC_IRQHandler +TIM7_IRQHandler +DMA2_Channel1_IRQHandler +DMA2_Channel2_IRQHandler +DMA2_Channel3_IRQHandler +DMA2_Channel4_5_IRQHandler +DMA2_Channel5_IRQHandler + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_ld.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_ld.s new file mode 100644 index 0000000..f18be4b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_ld.s @@ -0,0 +1,297 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_ld.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Low Density Devices vector table for MDK-ARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1_2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD 0 ; Reserved + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SPI1_IRQHandler ; SPI1 + DCD 0 ; Reserved + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD 0 ; Reserved + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler routine +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_2_IRQHandler [WEAK] + EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK] + EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_IRQHandler [WEAK] + EXPORT TIM1_UP_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT USBWakeUp_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_2_IRQHandler +USB_HP_CAN1_TX_IRQHandler +USB_LP_CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_IRQHandler +TIM1_UP_IRQHandler +TIM1_TRG_COM_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +SPI1_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +USBWakeUp_IRQHandler + + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_ld_vl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_ld_vl.s new file mode 100644 index 0000000..f7240dc --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_ld_vl.s @@ -0,0 +1,304 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_ld_vl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Low Density Value Line Devices vector table +;* for MDK-ARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger and Commutation and TIM17 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD 0 ; Reserved + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SPI1_IRQHandler ; SPI1 + DCD 0 ; Reserved + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD 0 ; Reserved + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD CEC_IRQHandler ; HDMI-CEC + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC underrun + DCD TIM7_IRQHandler ; TIM7 +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_TIM15_IRQHandler [WEAK] + EXPORT TIM1_UP_TIM16_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_TIM17_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT CEC_IRQHandler [WEAK] + EXPORT TIM6_DAC_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_TIM15_IRQHandler +TIM1_UP_TIM16_IRQHandler +TIM1_TRG_COM_TIM17_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +SPI1_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +CEC_IRQHandler +TIM6_DAC_IRQHandler +TIM7_IRQHandler + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_md.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_md.s new file mode 100644 index 0000000..8c515ce --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_md.s @@ -0,0 +1,307 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_md.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Medium Density Devices vector table for MDK-ARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00001000 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1_2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_2_IRQHandler [WEAK] + EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK] + EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_IRQHandler [WEAK] + EXPORT TIM1_UP_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT TIM4_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT USBWakeUp_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_2_IRQHandler +USB_HP_CAN1_TX_IRQHandler +USB_LP_CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_IRQHandler +TIM1_UP_IRQHandler +TIM1_TRG_COM_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +TIM4_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +USBWakeUp_IRQHandler + + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_md_vl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_md_vl.s new file mode 100644 index 0000000..076aa7f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_md_vl.s @@ -0,0 +1,315 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_md_vl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Medium Density Value Line Devices vector table +;* for MDK-ARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger and Commutation and TIM17 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD CEC_IRQHandler ; HDMI-CEC + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC underrun + DCD TIM7_IRQHandler ; TIM7 +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_TIM15_IRQHandler [WEAK] + EXPORT TIM1_UP_TIM16_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_TIM17_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT TIM4_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT CEC_IRQHandler [WEAK] + EXPORT TIM6_DAC_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_TIM15_IRQHandler +TIM1_UP_TIM16_IRQHandler +TIM1_TRG_COM_TIM17_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +TIM4_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +CEC_IRQHandler +TIM6_DAC_IRQHandler +TIM7_IRQHandler + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_xl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_xl.s new file mode 100644 index 0000000..9fbc640 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_xl.s @@ -0,0 +1,358 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_xl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x XL-Density Devices vector table for MDK-ARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system and also configure the external +;* SRAM mounted on STM3210E-EVAL board to be used as data +;* memory (optional, to be enabled by user) +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 & ADC2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 + DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 + DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend + DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 + DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 + DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 + DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare + DCD ADC3_IRQHandler ; ADC3 + DCD FSMC_IRQHandler ; FSMC + DCD SDIO_IRQHandler ; SDIO + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_IRQHandler ; TIM6 + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5 +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_2_IRQHandler [WEAK] + EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK] + EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_TIM9_IRQHandler [WEAK] + EXPORT TIM1_UP_TIM10_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_TIM11_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT TIM4_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT USBWakeUp_IRQHandler [WEAK] + EXPORT TIM8_BRK_TIM12_IRQHandler [WEAK] + EXPORT TIM8_UP_TIM13_IRQHandler [WEAK] + EXPORT TIM8_TRG_COM_TIM14_IRQHandler [WEAK] + EXPORT TIM8_CC_IRQHandler [WEAK] + EXPORT ADC3_IRQHandler [WEAK] + EXPORT FSMC_IRQHandler [WEAK] + EXPORT SDIO_IRQHandler [WEAK] + EXPORT TIM5_IRQHandler [WEAK] + EXPORT SPI3_IRQHandler [WEAK] + EXPORT UART4_IRQHandler [WEAK] + EXPORT UART5_IRQHandler [WEAK] + EXPORT TIM6_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] + EXPORT DMA2_Channel1_IRQHandler [WEAK] + EXPORT DMA2_Channel2_IRQHandler [WEAK] + EXPORT DMA2_Channel3_IRQHandler [WEAK] + EXPORT DMA2_Channel4_5_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_2_IRQHandler +USB_HP_CAN1_TX_IRQHandler +USB_LP_CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_TIM9_IRQHandler +TIM1_UP_TIM10_IRQHandler +TIM1_TRG_COM_TIM11_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +TIM4_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +USBWakeUp_IRQHandler +TIM8_BRK_TIM12_IRQHandler +TIM8_UP_TIM13_IRQHandler +TIM8_TRG_COM_TIM14_IRQHandler +TIM8_CC_IRQHandler +ADC3_IRQHandler +FSMC_IRQHandler +SDIO_IRQHandler +TIM5_IRQHandler +SPI3_IRQHandler +UART4_IRQHandler +UART5_IRQHandler +TIM6_IRQHandler +TIM7_IRQHandler +DMA2_Channel1_IRQHandler +DMA2_Channel2_IRQHandler +DMA2_Channel3_IRQHandler +DMA2_Channel4_5_IRQHandler + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_cl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_cl.s new file mode 100644 index 0000000..cf0531e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_cl.s @@ -0,0 +1,468 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_cl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Connectivity line Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR + * address. + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss + +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler + +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word CAN1_TX_IRQHandler + .word CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word OTG_FS_WKUP_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_IRQHandler + .word DMA2_Channel5_IRQHandler + .word ETH_IRQHandler + .word ETH_WKUP_IRQHandler + .word CAN2_TX_IRQHandler + .word CAN2_RX0_IRQHandler + .word CAN2_RX1_IRQHandler + .word CAN2_SCE_IRQHandler + .word OTG_FS_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x Connectivity line Devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak CAN1_TX_IRQHandler + .thumb_set CAN1_TX_IRQHandler,Default_Handler + + .weak CAN1_RX0_IRQHandler + .thumb_set CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak OTG_FS_WKUP_IRQHandler + .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_IRQHandler + .thumb_set DMA2_Channel4_IRQHandler,Default_Handler + + .weak DMA2_Channel5_IRQHandler + .thumb_set DMA2_Channel5_IRQHandler,Default_Handler + + .weak ETH_IRQHandler + .thumb_set ETH_IRQHandler,Default_Handler + + .weak ETH_WKUP_IRQHandler + .thumb_set ETH_WKUP_IRQHandler,Default_Handler + + .weak CAN2_TX_IRQHandler + .thumb_set CAN2_TX_IRQHandler,Default_Handler + + .weak CAN2_RX0_IRQHandler + .thumb_set CAN2_RX0_IRQHandler,Default_Handler + + .weak CAN2_RX1_IRQHandler + .thumb_set CAN2_RX1_IRQHandler,Default_Handler + + .weak CAN2_SCE_IRQHandler + .thumb_set CAN2_SCE_IRQHandler,Default_Handler + + .weak OTG_FS_IRQHandler + .thumb_set OTG_FS_IRQHandler ,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd.s new file mode 100644 index 0000000..09291a5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd.s @@ -0,0 +1,465 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_hd.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x High Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system and the external SRAM mounted on + * STM3210E-EVAL board to be used as data memory (optional, + * to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word TIM8_BRK_IRQHandler + .word TIM8_UP_IRQHandler + .word TIM8_TRG_COM_IRQHandler + .word TIM8_CC_IRQHandler + .word ADC3_IRQHandler + .word FSMC_IRQHandler + .word SDIO_IRQHandler + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_5_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x High Density devices. */ +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + .weak TIM8_BRK_IRQHandler + .thumb_set TIM8_BRK_IRQHandler,Default_Handler + + .weak TIM8_UP_IRQHandler + .thumb_set TIM8_UP_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_IRQHandler + .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak ADC3_IRQHandler + .thumb_set ADC3_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_5_IRQHandler + .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd_vl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd_vl.s new file mode 100644 index 0000000..460f06c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd_vl.s @@ -0,0 +1,442 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_hd_vl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x High Density Value Line Devices vector table for RIDE7 + * toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system and the external SRAM mounted on + * STM32100E-EVAL board to be used as data memory (optional, + * to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM15_IRQHandler + .word TIM1_UP_TIM16_IRQHandler + .word TIM1_TRG_COM_TIM17_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word CEC_IRQHandler + .word TIM12_IRQHandler + .word TIM13_IRQHandler + .word TIM14_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_DAC_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_5_IRQHandler + .word DMA2_Channel5_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x High Density Value line devices. */ + +/******************************************************************************* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM15_IRQHandler + .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM16_IRQHandler + .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM17_IRQHandler + .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak CEC_IRQHandler + .thumb_set CEC_IRQHandler,Default_Handler + + .weak TIM12_IRQHandler + .thumb_set TIM12_IRQHandler,Default_Handler + + .weak TIM13_IRQHandler + .thumb_set TIM13_IRQHandler,Default_Handler + + .weak TIM14_IRQHandler + .thumb_set TIM14_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_5_IRQHandler + .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler + + .weak DMA2_Channel5_IRQHandler + .thumb_set DMA2_Channel5_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld.s new file mode 100644 index 0000000..d771126 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld.s @@ -0,0 +1,343 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_ld.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Low Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word 0 + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word 0 + .word 0 + .word SPI1_IRQHandler + .word 0 + .word USART1_IRQHandler + .word USART2_IRQHandler + .word 0 + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Low Density devices.*/ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld_vl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld_vl.s new file mode 100644 index 0000000..9ca6afb --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld_vl.s @@ -0,0 +1,383 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_ld_vl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Low Density Value Line Devices vector table for RIDE7 + * toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM15_IRQHandler + .word TIM1_UP_TIM16_IRQHandler + .word TIM1_TRG_COM_TIM17_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word 0 + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word 0 + .word 0 + .word SPI1_IRQHandler + .word 0 + .word USART1_IRQHandler + .word USART2_IRQHandler + .word 0 + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word CEC_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM6_DAC_IRQHandler + .word TIM7_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x01CC. This is for boot in RAM mode for + STM32F10x Low Density Value Line devices. */ + +/******************************************************************************* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM15_IRQHandler + .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM16_IRQHandler + .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM17_IRQHandler + .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak CEC_IRQHandler + .thumb_set CEC_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md.s new file mode 100644 index 0000000..7333b16 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md.s @@ -0,0 +1,358 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_md.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Medium Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Medium Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md_vl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md_vl.s new file mode 100644 index 0000000..7371513 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md_vl.s @@ -0,0 +1,399 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_md_vl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Medium Density Value Line Devices vector table for RIDE7 + * toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM15_IRQHandler + .word TIM1_UP_TIM16_IRQHandler + .word TIM1_TRG_COM_TIM17_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word CEC_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM6_DAC_IRQHandler + .word TIM7_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x01CC. This is for boot in RAM mode for + STM32F10x Medium Value Line Density devices. */ + +/******************************************************************************* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM15_IRQHandler + .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM16_IRQHandler + .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM17_IRQHandler + .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak CEC_IRQHandler + .thumb_set CEC_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_xl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_xl.s new file mode 100644 index 0000000..3bc91f8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_xl.s @@ -0,0 +1,465 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_xl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x XL-Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system and the external SRAM mounted on + * STM3210E-EVAL board to be used as data memory (optional, + * to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM9_IRQHandler + .word TIM1_UP_TIM10_IRQHandler + .word TIM1_TRG_COM_TIM11_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word TIM8_BRK_TIM12_IRQHandler + .word TIM8_UP_TIM13_IRQHandler + .word TIM8_TRG_COM_TIM14_IRQHandler + .word TIM8_CC_IRQHandler + .word ADC3_IRQHandler + .word FSMC_IRQHandler + .word SDIO_IRQHandler + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_5_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x XL Density devices. */ +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM9_IRQHandler + .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM10_IRQHandler + .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM11_IRQHandler + .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + .weak TIM8_BRK_TIM12_IRQHandler + .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler + + .weak TIM8_UP_TIM13_IRQHandler + .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_TIM14_IRQHandler + .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak ADC3_IRQHandler + .thumb_set ADC3_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_5_IRQHandler + .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_cl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_cl.s new file mode 100644 index 0000000..0c87160 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_cl.s @@ -0,0 +1,507 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************* +;* File Name : startup_stm32f10x_cl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Connectivity line devices vector table for +;* EWARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR +;* address. +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 and ADC2 + DCD CAN1_TX_IRQHandler ; CAN1 TX + DCD CAN1_RX0_IRQHandler ; CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C1 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC alarm through EXTI line + DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_IRQHandler ; TIM6 + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_IRQHandler ; DMA2 Channel4 + DCD DMA2_Channel5_IRQHandler ; DMA2 Channel5 + DCD ETH_IRQHandler ; Ethernet + DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line + DCD CAN2_TX_IRQHandler ; CAN2 TX + DCD CAN2_RX0_IRQHandler ; CAN2 RX0 + DCD CAN2_RX1_IRQHandler ; CAN2 RX1 + DCD CAN2_SCE_IRQHandler ; CAN2 SCE + DCD OTG_FS_IRQHandler ; USB OTG FS + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_2_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_2_IRQHandler + B ADC1_2_IRQHandler + + PUBWEAK CAN1_TX_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_TX_IRQHandler + B CAN1_TX_IRQHandler + + PUBWEAK CAN1_RX0_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_RX0_IRQHandler + B CAN1_RX0_IRQHandler + + PUBWEAK CAN1_RX1_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_RX1_IRQHandler + B CAN1_RX1_IRQHandler + + PUBWEAK CAN1_SCE_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_SCE_IRQHandler + B CAN1_SCE_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_IRQHandler + B TIM1_BRK_IRQHandler + + PUBWEAK TIM1_UP_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_IRQHandler + B TIM1_UP_IRQHandler + + PUBWEAK TIM1_TRG_COM_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_IRQHandler + B TIM1_TRG_COM_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK TIM4_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM4_IRQHandler + B TIM4_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK I2C2_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_EV_IRQHandler + B I2C2_EV_IRQHandler + + PUBWEAK I2C2_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_ER_IRQHandler + B I2C2_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK SPI2_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI2_IRQHandler + B SPI2_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK USART3_IRQHandler + SECTION .text:CODE:REORDER(1) +USART3_IRQHandler + B USART3_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK OTG_FS_WKUP_IRQHandler + SECTION .text:CODE:REORDER(1) +OTG_FS_WKUP_IRQHandler + B OTG_FS_WKUP_IRQHandler + + PUBWEAK TIM5_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM5_IRQHandler + B TIM5_IRQHandler + + PUBWEAK SPI3_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI3_IRQHandler + B SPI3_IRQHandler + + PUBWEAK UART4_IRQHandler + SECTION .text:CODE:REORDER(1) +UART4_IRQHandler + B UART4_IRQHandler + + PUBWEAK UART5_IRQHandler + SECTION .text:CODE:REORDER(1) +UART5_IRQHandler + B UART5_IRQHandler + + PUBWEAK TIM6_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM6_IRQHandler + B TIM6_IRQHandler + + PUBWEAK TIM7_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM7_IRQHandler + B TIM7_IRQHandler + + PUBWEAK DMA2_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel1_IRQHandler + B DMA2_Channel1_IRQHandler + + PUBWEAK DMA2_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel2_IRQHandler + B DMA2_Channel2_IRQHandler + + PUBWEAK DMA2_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel3_IRQHandler + B DMA2_Channel3_IRQHandler + + PUBWEAK DMA2_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel4_IRQHandler + B DMA2_Channel4_IRQHandler + + PUBWEAK DMA2_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel5_IRQHandler + B DMA2_Channel5_IRQHandler + + PUBWEAK ETH_IRQHandler + SECTION .text:CODE:REORDER(1) +ETH_IRQHandler + B ETH_IRQHandler + + PUBWEAK ETH_WKUP_IRQHandler + SECTION .text:CODE:REORDER(1) +ETH_WKUP_IRQHandler + B ETH_WKUP_IRQHandler + + PUBWEAK CAN2_TX_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN2_TX_IRQHandler + B CAN2_TX_IRQHandler + + PUBWEAK CAN2_RX0_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN2_RX0_IRQHandler + B CAN2_RX0_IRQHandler + + PUBWEAK CAN2_RX1_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN2_RX1_IRQHandler + B CAN2_RX1_IRQHandler + + PUBWEAK CAN2_SCE_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN2_SCE_IRQHandler + B CAN2_SCE_IRQHandler + + PUBWEAK OTG_FS_IRQHandler + SECTION .text:CODE:REORDER(1) +OTG_FS_IRQHandler + B OTG_FS_IRQHandler + + END +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_hd.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_hd.s new file mode 100644 index 0000000..11ccfe3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_hd.s @@ -0,0 +1,496 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_hd.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x High Density Devices vector table for EWARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system and the external SRAM +;* mounted on STM3210E-EVAL board to be used as data +;* memory (optional, to be enabled by user) +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR address, +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA + +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 & ADC2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend + DCD TIM8_BRK_IRQHandler ; TIM8 Break + DCD TIM8_UP_IRQHandler ; TIM8 Update + DCD TIM8_TRG_COM_IRQHandler ; TIM8 Trigger and Commutation + DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare + DCD ADC3_IRQHandler ; ADC3 + DCD FSMC_IRQHandler ; FSMC + DCD SDIO_IRQHandler ; SDIO + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_IRQHandler ; TIM6 + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5 +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_2_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_2_IRQHandler + B ADC1_2_IRQHandler + + PUBWEAK USB_HP_CAN1_TX_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_HP_CAN1_TX_IRQHandler + B USB_HP_CAN1_TX_IRQHandler + + PUBWEAK USB_LP_CAN1_RX0_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_LP_CAN1_RX0_IRQHandler + B USB_LP_CAN1_RX0_IRQHandler + + PUBWEAK CAN1_RX1_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_RX1_IRQHandler + B CAN1_RX1_IRQHandler + + PUBWEAK CAN1_SCE_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_SCE_IRQHandler + B CAN1_SCE_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_IRQHandler + B TIM1_BRK_IRQHandler + + PUBWEAK TIM1_UP_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_IRQHandler + B TIM1_UP_IRQHandler + + PUBWEAK TIM1_TRG_COM_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_IRQHandler + B TIM1_TRG_COM_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK TIM4_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM4_IRQHandler + B TIM4_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK I2C2_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_EV_IRQHandler + B I2C2_EV_IRQHandler + + PUBWEAK I2C2_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_ER_IRQHandler + B I2C2_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK SPI2_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI2_IRQHandler + B SPI2_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK USART3_IRQHandler + SECTION .text:CODE:REORDER(1) +USART3_IRQHandler + B USART3_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK USBWakeUp_IRQHandler + SECTION .text:CODE:REORDER(1) +USBWakeUp_IRQHandler + B USBWakeUp_IRQHandler + + PUBWEAK TIM8_BRK_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_BRK_IRQHandler + B TIM8_BRK_IRQHandler + + PUBWEAK TIM8_UP_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_UP_IRQHandler + B TIM8_UP_IRQHandler + + PUBWEAK TIM8_TRG_COM_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_TRG_COM_IRQHandler + B TIM8_TRG_COM_IRQHandler + + PUBWEAK TIM8_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_CC_IRQHandler + B TIM8_CC_IRQHandler + + PUBWEAK ADC3_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC3_IRQHandler + B ADC3_IRQHandler + + PUBWEAK FSMC_IRQHandler + SECTION .text:CODE:REORDER(1) +FSMC_IRQHandler + B FSMC_IRQHandler + + PUBWEAK SDIO_IRQHandler + SECTION .text:CODE:REORDER(1) +SDIO_IRQHandler + B SDIO_IRQHandler + + PUBWEAK TIM5_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM5_IRQHandler + B TIM5_IRQHandler + + PUBWEAK SPI3_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI3_IRQHandler + B SPI3_IRQHandler + + PUBWEAK UART4_IRQHandler + SECTION .text:CODE:REORDER(1) +UART4_IRQHandler + B UART4_IRQHandler + + PUBWEAK UART5_IRQHandler + SECTION .text:CODE:REORDER(1) +UART5_IRQHandler + B UART5_IRQHandler + + PUBWEAK TIM6_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM6_IRQHandler + B TIM6_IRQHandler + + PUBWEAK TIM7_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM7_IRQHandler + B TIM7_IRQHandler + + PUBWEAK DMA2_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel1_IRQHandler + B DMA2_Channel1_IRQHandler + + PUBWEAK DMA2_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel2_IRQHandler + B DMA2_Channel2_IRQHandler + + PUBWEAK DMA2_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel3_IRQHandler + B DMA2_Channel3_IRQHandler + + PUBWEAK DMA2_Channel4_5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel4_5_IRQHandler + B DMA2_Channel4_5_IRQHandler + + + END + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_hd_vl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_hd_vl.s new file mode 100644 index 0000000..401d67e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_hd_vl.s @@ -0,0 +1,461 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_hd_vl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x High Density Value Line Devices vector table +;* for EWARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system and the external SRAM +;* mounted on STM32100E-EVAL board to be used as data +;* memory (optional, to be enabled by user) +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR +;* address. +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger and Commutation and TIM17 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD CEC_IRQHandler ; HDMI-CEC + DCD TIM12_IRQHandler ; TIM12 + DCD TIM13_IRQHandler ; TIM13 + DCD TIM14_IRQHandler ; TIM14 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC underrun + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5 + DCD DMA2_Channel5_IRQHandler ; DMA2 Channel5 + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_IRQHandler + B ADC1_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_TIM15_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_TIM15_IRQHandler + B TIM1_BRK_TIM15_IRQHandler + + PUBWEAK TIM1_UP_TIM16_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_TIM16_IRQHandler + B TIM1_UP_TIM16_IRQHandler + + PUBWEAK TIM1_TRG_COM_TIM17_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_TIM17_IRQHandler + B TIM1_TRG_COM_TIM17_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK TIM4_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM4_IRQHandler + B TIM4_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK I2C2_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_EV_IRQHandler + B I2C2_EV_IRQHandler + + PUBWEAK I2C2_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_ER_IRQHandler + B I2C2_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK SPI2_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI2_IRQHandler + B SPI2_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK USART3_IRQHandler + SECTION .text:CODE:REORDER(1) +USART3_IRQHandler + B USART3_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK CEC_IRQHandler + SECTION .text:CODE:REORDER(1) +CEC_IRQHandler + B CEC_IRQHandler + + PUBWEAK TIM12_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM12_IRQHandler + B TIM12_IRQHandler + + PUBWEAK TIM13_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM13_IRQHandler + B TIM13_IRQHandler + + PUBWEAK TIM14_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM14_IRQHandler + B TIM14_IRQHandler + + PUBWEAK TIM5_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM5_IRQHandler + B TIM5_IRQHandler + + PUBWEAK SPI3_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI3_IRQHandler + B SPI3_IRQHandler + + PUBWEAK UART4_IRQHandler + SECTION .text:CODE:REORDER(1) +UART4_IRQHandler + B UART4_IRQHandler + + PUBWEAK UART5_IRQHandler + SECTION .text:CODE:REORDER(1) +UART5_IRQHandler + B UART5_IRQHandler + + PUBWEAK TIM6_DAC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM6_DAC_IRQHandler + B TIM6_DAC_IRQHandler + + PUBWEAK TIM7_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM7_IRQHandler + B TIM7_IRQHandler + + PUBWEAK DMA2_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel1_IRQHandler + B DMA2_Channel1_IRQHandler + + PUBWEAK DMA2_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel2_IRQHandler + B DMA2_Channel2_IRQHandler + + PUBWEAK DMA2_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel3_IRQHandler + B DMA2_Channel3_IRQHandler + + PUBWEAK DMA2_Channel4_5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel4_5_IRQHandler + B DMA2_Channel4_5_IRQHandler + + PUBWEAK DMA2_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel5_IRQHandler + B DMA2_Channel5_IRQHandler + + END +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_ld.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_ld.s new file mode 100644 index 0000000..1c0a3e1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_ld.s @@ -0,0 +1,366 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_ld.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Low Density Devices vector table for EWARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR +;* address. +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 & ADC2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD 0 ; Reserved + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SPI1_IRQHandler ; SPI1 + DCD 0 ; Reserved + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD 0 ; Reserved + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_2_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_2_IRQHandler + B ADC1_2_IRQHandler + + PUBWEAK USB_HP_CAN1_TX_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_HP_CAN1_TX_IRQHandler + B USB_HP_CAN1_TX_IRQHandler + + PUBWEAK USB_LP_CAN1_RX0_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_LP_CAN1_RX0_IRQHandler + B USB_LP_CAN1_RX0_IRQHandler + + PUBWEAK CAN1_RX1_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_RX1_IRQHandler + B CAN1_RX1_IRQHandler + + PUBWEAK CAN1_SCE_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_SCE_IRQHandler + B CAN1_SCE_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_IRQHandler + B TIM1_BRK_IRQHandler + + PUBWEAK TIM1_UP_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_IRQHandler + B TIM1_UP_IRQHandler + + PUBWEAK TIM1_TRG_COM_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_IRQHandler + B TIM1_TRG_COM_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK USBWakeUp_IRQHandler + SECTION .text:CODE:REORDER(1) +USBWakeUp_IRQHandler + B USBWakeUp_IRQHandler + + END +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_ld_vl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_ld_vl.s new file mode 100644 index 0000000..85531c5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_ld_vl.s @@ -0,0 +1,369 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_ld_vl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Low Density Value Line Devices vector table +;* for EWARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR +;* address. +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger and Commutation and TIM17 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD 0 ; Reserved + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SPI1_IRQHandler ; SPI1 + DCD 0 ; Reserved + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD 0 ; Reserved + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD CEC_IRQHandler ; HDMI-CEC + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC underrun + DCD TIM7_IRQHandler ; TIM7 + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_IRQHandler + B ADC1_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_TIM15_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_TIM15_IRQHandler + B TIM1_BRK_TIM15_IRQHandler + + PUBWEAK TIM1_UP_TIM16_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_TIM16_IRQHandler + B TIM1_UP_TIM16_IRQHandler + + PUBWEAK TIM1_TRG_COM_TIM17_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_TIM17_IRQHandler + B TIM1_TRG_COM_TIM17_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK CEC_IRQHandler + SECTION .text:CODE:REORDER(1) +CEC_IRQHandler + B CEC_IRQHandler + + PUBWEAK TIM6_DAC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM6_DAC_IRQHandler + B TIM6_DAC_IRQHandler + + PUBWEAK TIM7_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM7_IRQHandler + B TIM7_IRQHandler + + END +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_md.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_md.s new file mode 100644 index 0000000..48b14c3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_md.s @@ -0,0 +1,391 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_md.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Medium Density Devices vector table for +;* EWARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR +;* address. +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 & ADC2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_2_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_2_IRQHandler + B ADC1_2_IRQHandler + + PUBWEAK USB_HP_CAN1_TX_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_HP_CAN1_TX_IRQHandler + B USB_HP_CAN1_TX_IRQHandler + + PUBWEAK USB_LP_CAN1_RX0_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_LP_CAN1_RX0_IRQHandler + B USB_LP_CAN1_RX0_IRQHandler + + PUBWEAK CAN1_RX1_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_RX1_IRQHandler + B CAN1_RX1_IRQHandler + + PUBWEAK CAN1_SCE_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_SCE_IRQHandler + B CAN1_SCE_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_IRQHandler + B TIM1_BRK_IRQHandler + + PUBWEAK TIM1_UP_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_IRQHandler + B TIM1_UP_IRQHandler + + PUBWEAK TIM1_TRG_COM_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_IRQHandler + B TIM1_TRG_COM_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK TIM4_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM4_IRQHandler + B TIM4_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK I2C2_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_EV_IRQHandler + B I2C2_EV_IRQHandler + + PUBWEAK I2C2_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_ER_IRQHandler + B I2C2_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK SPI2_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI2_IRQHandler + B SPI2_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK USART3_IRQHandler + SECTION .text:CODE:REORDER(1) +USART3_IRQHandler + B USART3_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK USBWakeUp_IRQHandler + SECTION .text:CODE:REORDER(1) +USBWakeUp_IRQHandler + B USBWakeUp_IRQHandler + + END +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_md_vl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_md_vl.s new file mode 100644 index 0000000..7a25707 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_md_vl.s @@ -0,0 +1,394 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_md_vl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Medium Density Value Line Devices vector table +;* for EWARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR +;* address. +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger and Commutation and TIM17 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD CEC_IRQHandler ; HDMI-CEC + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC underrun + DCD TIM7_IRQHandler ; TIM7 + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_IRQHandler + B ADC1_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_TIM15_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_TIM15_IRQHandler + B TIM1_BRK_TIM15_IRQHandler + + PUBWEAK TIM1_UP_TIM16_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_TIM16_IRQHandler + B TIM1_UP_TIM16_IRQHandler + + PUBWEAK TIM1_TRG_COM_TIM17_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_TIM17_IRQHandler + B TIM1_TRG_COM_TIM17_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK TIM4_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM4_IRQHandler + B TIM4_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK I2C2_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_EV_IRQHandler + B I2C2_EV_IRQHandler + + PUBWEAK I2C2_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_ER_IRQHandler + B I2C2_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK SPI2_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI2_IRQHandler + B SPI2_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK USART3_IRQHandler + SECTION .text:CODE:REORDER(1) +USART3_IRQHandler + B USART3_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK CEC_IRQHandler + SECTION .text:CODE:REORDER(1) +CEC_IRQHandler + B CEC_IRQHandler + + PUBWEAK TIM6_DAC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM6_DAC_IRQHandler + B TIM6_DAC_IRQHandler + + PUBWEAK TIM7_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM7_IRQHandler + B TIM7_IRQHandler + + END +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_xl.s b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_xl.s new file mode 100644 index 0000000..029761a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_xl.s @@ -0,0 +1,496 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_xl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x XL-Density Devices vector table for EWARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system and the external SRAM +;* mounted on STM3210E-EVAL board to be used as data +;* memory (optional, to be enabled by user) +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR address, +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA + +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 & ADC2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 + DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 + DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend + DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 + DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 + DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 + DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare + DCD ADC3_IRQHandler ; ADC3 + DCD FSMC_IRQHandler ; FSMC + DCD SDIO_IRQHandler ; SDIO + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_IRQHandler ; TIM6 + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5 +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_2_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_2_IRQHandler + B ADC1_2_IRQHandler + + PUBWEAK USB_HP_CAN1_TX_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_HP_CAN1_TX_IRQHandler + B USB_HP_CAN1_TX_IRQHandler + + PUBWEAK USB_LP_CAN1_RX0_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_LP_CAN1_RX0_IRQHandler + B USB_LP_CAN1_RX0_IRQHandler + + PUBWEAK CAN1_RX1_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_RX1_IRQHandler + B CAN1_RX1_IRQHandler + + PUBWEAK CAN1_SCE_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_SCE_IRQHandler + B CAN1_SCE_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_TIM9_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_TIM9_IRQHandler + B TIM1_BRK_TIM9_IRQHandler + + PUBWEAK TIM1_UP_TIM10_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_TIM10_IRQHandler + B TIM1_UP_TIM10_IRQHandler + + PUBWEAK TIM1_TRG_COM_TIM11_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_TIM11_IRQHandler + B TIM1_TRG_COM_TIM11_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK TIM4_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM4_IRQHandler + B TIM4_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK I2C2_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_EV_IRQHandler + B I2C2_EV_IRQHandler + + PUBWEAK I2C2_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_ER_IRQHandler + B I2C2_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK SPI2_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI2_IRQHandler + B SPI2_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK USART3_IRQHandler + SECTION .text:CODE:REORDER(1) +USART3_IRQHandler + B USART3_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK USBWakeUp_IRQHandler + SECTION .text:CODE:REORDER(1) +USBWakeUp_IRQHandler + B USBWakeUp_IRQHandler + + PUBWEAK TIM8_BRK_TIM12_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_BRK_TIM12_IRQHandler + B TIM8_BRK_TIM12_IRQHandler + + PUBWEAK TIM8_UP_TIM13_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_UP_TIM13_IRQHandler + B TIM8_UP_TIM13_IRQHandler + + PUBWEAK TIM8_TRG_COM_TIM14_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_TRG_COM_TIM14_IRQHandler + B TIM8_TRG_COM_TIM14_IRQHandler + + PUBWEAK TIM8_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_CC_IRQHandler + B TIM8_CC_IRQHandler + + PUBWEAK ADC3_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC3_IRQHandler + B ADC3_IRQHandler + + PUBWEAK FSMC_IRQHandler + SECTION .text:CODE:REORDER(1) +FSMC_IRQHandler + B FSMC_IRQHandler + + PUBWEAK SDIO_IRQHandler + SECTION .text:CODE:REORDER(1) +SDIO_IRQHandler + B SDIO_IRQHandler + + PUBWEAK TIM5_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM5_IRQHandler + B TIM5_IRQHandler + + PUBWEAK SPI3_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI3_IRQHandler + B SPI3_IRQHandler + + PUBWEAK UART4_IRQHandler + SECTION .text:CODE:REORDER(1) +UART4_IRQHandler + B UART4_IRQHandler + + PUBWEAK UART5_IRQHandler + SECTION .text:CODE:REORDER(1) +UART5_IRQHandler + B UART5_IRQHandler + + PUBWEAK TIM6_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM6_IRQHandler + B TIM6_IRQHandler + + PUBWEAK TIM7_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM7_IRQHandler + B TIM7_IRQHandler + + PUBWEAK DMA2_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel1_IRQHandler + B DMA2_Channel1_IRQHandler + + PUBWEAK DMA2_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel2_IRQHandler + B DMA2_Channel2_IRQHandler + + PUBWEAK DMA2_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel3_IRQHandler + B DMA2_Channel3_IRQHandler + + PUBWEAK DMA2_Channel4_5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel4_5_IRQHandler + B DMA2_Channel4_5_IRQHandler + + + END + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x.h new file mode 100644 index 0000000..8bf7624 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x.h @@ -0,0 +1,8336 @@ +/** + ****************************************************************************** + * @file stm32f10x.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief CMSIS Cortex-M3 Device Peripheral Access Layer Header File. + * This file contains all the peripheral register's definitions, bits + * definitions and memory mapping for STM32F10x Connectivity line, + * High density, High density value line, Medium density, + * Medium density Value line, Low density, Low density Value line + * and XL-density devices. + * + * The file is the unique include file that the application programmer + * is using in the C source code, usually in main.c. This file contains: + * - Configuration section that allows to select: + * - The device used in the target application + * - To use or not the peripheral’s drivers in application code(i.e. + * code will be based on direct access to peripheral’s registers + * rather than drivers API), this option is controlled by + * "#define USE_STDPERIPH_DRIVER" + * - To change few application-specific parameters such as the HSE + * crystal frequency + * - Data structures and the address mapping for all peripherals + * - Peripheral's registers declarations and bits definition + * - Macros to access peripheral’s registers hardware + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f10x + * @{ + */ + +#ifndef __STM32F10x_H +#define __STM32F10x_H + +#ifdef __cplusplus + extern "C" { +#endif + +/** @addtogroup Library_configuration_section + * @{ + */ + +/* Uncomment the line below according to the target STM32 device used in your + application + */ + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD) && !defined (STM32F10X_HD_VL) && !defined (STM32F10X_XL) && !defined (STM32F10X_CL) + /* #define STM32F10X_LD */ /*!< STM32F10X_LD: STM32 Low density devices */ + /* #define STM32F10X_LD_VL */ /*!< STM32F10X_LD_VL: STM32 Low density Value Line devices */ + /* #define STM32F10X_MD */ /*!< STM32F10X_MD: STM32 Medium density devices */ + /* #define STM32F10X_MD_VL */ /*!< STM32F10X_MD_VL: STM32 Medium density Value Line devices */ + /* #define STM32F10X_HD */ /*!< STM32F10X_HD: STM32 High density devices */ + /* #define STM32F10X_HD_VL */ /*!< STM32F10X_HD_VL: STM32 High density value line devices */ + /* #define STM32F10X_XL */ /*!< STM32F10X_XL: STM32 XL-density devices */ + /* #define STM32F10X_CL */ /*!< STM32F10X_CL: STM32 Connectivity line devices */ +#endif +/* Tip: To avoid modifying this file each time you need to switch between these + devices, you can define the device in your toolchain compiler preprocessor. + + - Low-density devices are STM32F101xx, STM32F102xx and STM32F103xx microcontrollers + where the Flash memory density ranges between 16 and 32 Kbytes. + - Low-density value line devices are STM32F100xx microcontrollers where the Flash + memory density ranges between 16 and 32 Kbytes. + - Medium-density devices are STM32F101xx, STM32F102xx and STM32F103xx microcontrollers + where the Flash memory density ranges between 64 and 128 Kbytes. + - Medium-density value line devices are STM32F100xx microcontrollers where the + Flash memory density ranges between 64 and 128 Kbytes. + - High-density devices are STM32F101xx and STM32F103xx microcontrollers where + the Flash memory density ranges between 256 and 512 Kbytes. + - High-density value line devices are STM32F100xx microcontrollers where the + Flash memory density ranges between 256 and 512 Kbytes. + - XL-density devices are STM32F101xx and STM32F103xx microcontrollers where + the Flash memory density ranges between 512 and 1024 Kbytes. + - Connectivity line devices are STM32F105xx and STM32F107xx microcontrollers. + */ + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD) && !defined (STM32F10X_HD_VL) && !defined (STM32F10X_XL) && !defined (STM32F10X_CL) + #error "Please select first the target STM32F10x device used in your application (in stm32f10x.h file)" +#endif + +#if !defined USE_STDPERIPH_DRIVER +/** + * @brief Comment the line below if you will not use the peripherals drivers. + In this case, these drivers will not be included and the application code will + be based on direct access to peripherals registers + */ + /*#define USE_STDPERIPH_DRIVER*/ +#endif + +/** + * @brief In the following line adjust the value of External High Speed oscillator (HSE) + used in your application + + Tip: To avoid modifying this file each time you need to use different HSE, you + can define the HSE value in your toolchain compiler preprocessor. + */ +#if !defined HSE_VALUE + #ifdef STM32F10X_CL + #define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */ + #else + #define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */ + #endif /* STM32F10X_CL */ +#endif /* HSE_VALUE */ + + +/** + * @brief In the following line adjust the External High Speed oscillator (HSE) Startup + Timeout value + */ +#define HSE_STARTUP_TIMEOUT ((uint16_t)0x0500) /*!< Time out for HSE start up */ + +#define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/ + +/** + * @brief STM32F10x Standard Peripheral Library version number + */ +#define __STM32F10X_STDPERIPH_VERSION_MAIN (0x03) /*!< [31:24] main version */ +#define __STM32F10X_STDPERIPH_VERSION_SUB1 (0x05) /*!< [23:16] sub1 version */ +#define __STM32F10X_STDPERIPH_VERSION_SUB2 (0x00) /*!< [15:8] sub2 version */ +#define __STM32F10X_STDPERIPH_VERSION_RC (0x00) /*!< [7:0] release candidate */ +#define __STM32F10X_STDPERIPH_VERSION ( (__STM32F10X_STDPERIPH_VERSION_MAIN << 24)\ + |(__STM32F10X_STDPERIPH_VERSION_SUB1 << 16)\ + |(__STM32F10X_STDPERIPH_VERSION_SUB2 << 8)\ + |(__STM32F10X_STDPERIPH_VERSION_RC)) + +/** + * @} + */ + +/** @addtogroup Configuration_section_for_CMSIS + * @{ + */ + +/** + * @brief Configuration of the Cortex-M3 Processor and Core Peripherals + */ +#ifdef STM32F10X_XL + #define __MPU_PRESENT 1 /*!< STM32 XL-density devices provide an MPU */ +#else + #define __MPU_PRESENT 0 /*!< Other STM32 devices does not provide an MPU */ +#endif /* STM32F10X_XL */ +#define __NVIC_PRIO_BITS 4 /*!< STM32 uses 4 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ + +/** + * @brief STM32F10x Interrupt Number Definition, according to the selected device + * in @ref Library_configuration_section + */ +typedef enum IRQn +{ +/****** Cortex-M3 Processor Exceptions Numbers ***************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + MemoryManagement_IRQn = -12, /*!< 4 Cortex-M3 Memory Management Interrupt */ + BusFault_IRQn = -11, /*!< 5 Cortex-M3 Bus Fault Interrupt */ + UsageFault_IRQn = -10, /*!< 6 Cortex-M3 Usage Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 Cortex-M3 SV Call Interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 Cortex-M3 Debug Monitor Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M3 Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M3 System Tick Interrupt */ + +/****** STM32 specific Interrupt Numbers *********************************************************/ + WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ + PVD_IRQn = 1, /*!< PVD through EXTI Line detection Interrupt */ + TAMPER_IRQn = 2, /*!< Tamper Interrupt */ + RTC_IRQn = 3, /*!< RTC global Interrupt */ + FLASH_IRQn = 4, /*!< FLASH global Interrupt */ + RCC_IRQn = 5, /*!< RCC global Interrupt */ + EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ + EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ + EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ + EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ + EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ + DMA1_Channel1_IRQn = 11, /*!< DMA1 Channel 1 global Interrupt */ + DMA1_Channel2_IRQn = 12, /*!< DMA1 Channel 2 global Interrupt */ + DMA1_Channel3_IRQn = 13, /*!< DMA1 Channel 3 global Interrupt */ + DMA1_Channel4_IRQn = 14, /*!< DMA1 Channel 4 global Interrupt */ + DMA1_Channel5_IRQn = 15, /*!< DMA1 Channel 5 global Interrupt */ + DMA1_Channel6_IRQn = 16, /*!< DMA1 Channel 6 global Interrupt */ + DMA1_Channel7_IRQn = 17, /*!< DMA1 Channel 7 global Interrupt */ + +#ifdef STM32F10X_LD + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ + USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ + TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ + TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + USBWakeUp_IRQn = 42 /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ +#endif /* STM32F10X_LD */ + +#ifdef STM32F10X_LD_VL + ADC1_IRQn = 18, /*!< ADC1 global Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM15_IRQn = 24, /*!< TIM1 Break and TIM15 Interrupts */ + TIM1_UP_TIM16_IRQn = 25, /*!< TIM1 Update and TIM16 Interrupts */ + TIM1_TRG_COM_TIM17_IRQn = 26, /*!< TIM1 Trigger and Commutation and TIM17 Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + CEC_IRQn = 42, /*!< HDMI-CEC Interrupt */ + TIM6_DAC_IRQn = 54, /*!< TIM6 and DAC underrun Interrupt */ + TIM7_IRQn = 55 /*!< TIM7 Interrupt */ +#endif /* STM32F10X_LD_VL */ + +#ifdef STM32F10X_MD + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ + USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ + TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ + TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + USBWakeUp_IRQn = 42 /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ +#endif /* STM32F10X_MD */ + +#ifdef STM32F10X_MD_VL + ADC1_IRQn = 18, /*!< ADC1 global Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM15_IRQn = 24, /*!< TIM1 Break and TIM15 Interrupts */ + TIM1_UP_TIM16_IRQn = 25, /*!< TIM1 Update and TIM16 Interrupts */ + TIM1_TRG_COM_TIM17_IRQn = 26, /*!< TIM1 Trigger and Commutation and TIM17 Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + CEC_IRQn = 42, /*!< HDMI-CEC Interrupt */ + TIM6_DAC_IRQn = 54, /*!< TIM6 and DAC underrun Interrupt */ + TIM7_IRQn = 55 /*!< TIM7 Interrupt */ +#endif /* STM32F10X_MD_VL */ + +#ifdef STM32F10X_HD + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ + USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ + TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ + TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + USBWakeUp_IRQn = 42, /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ + TIM8_BRK_IRQn = 43, /*!< TIM8 Break Interrupt */ + TIM8_UP_IRQn = 44, /*!< TIM8 Update Interrupt */ + TIM8_TRG_COM_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt */ + TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ + ADC3_IRQn = 47, /*!< ADC3 global Interrupt */ + FSMC_IRQn = 48, /*!< FSMC global Interrupt */ + SDIO_IRQn = 49, /*!< SDIO global Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_IRQn = 54, /*!< TIM6 global Interrupt */ + TIM7_IRQn = 55, /*!< TIM7 global Interrupt */ + DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ + DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ + DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ + DMA2_Channel4_5_IRQn = 59 /*!< DMA2 Channel 4 and Channel 5 global Interrupt */ +#endif /* STM32F10X_HD */ + +#ifdef STM32F10X_HD_VL + ADC1_IRQn = 18, /*!< ADC1 global Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM15_IRQn = 24, /*!< TIM1 Break and TIM15 Interrupts */ + TIM1_UP_TIM16_IRQn = 25, /*!< TIM1 Update and TIM16 Interrupts */ + TIM1_TRG_COM_TIM17_IRQn = 26, /*!< TIM1 Trigger and Commutation and TIM17 Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + CEC_IRQn = 42, /*!< HDMI-CEC Interrupt */ + TIM12_IRQn = 43, /*!< TIM12 global Interrupt */ + TIM13_IRQn = 44, /*!< TIM13 global Interrupt */ + TIM14_IRQn = 45, /*!< TIM14 global Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_DAC_IRQn = 54, /*!< TIM6 and DAC underrun Interrupt */ + TIM7_IRQn = 55, /*!< TIM7 Interrupt */ + DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ + DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ + DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ + DMA2_Channel4_5_IRQn = 59, /*!< DMA2 Channel 4 and Channel 5 global Interrupt */ + DMA2_Channel5_IRQn = 60 /*!< DMA2 Channel 5 global Interrupt (DMA2 Channel 5 is + mapped at position 60 only if the MISC_REMAP bit in + the AFIO_MAPR2 register is set) */ +#endif /* STM32F10X_HD_VL */ + +#ifdef STM32F10X_XL + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ + USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM9_IRQn = 24, /*!< TIM1 Break Interrupt and TIM9 global Interrupt */ + TIM1_UP_TIM10_IRQn = 25, /*!< TIM1 Update Interrupt and TIM10 global Interrupt */ + TIM1_TRG_COM_TIM11_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + USBWakeUp_IRQn = 42, /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ + TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global Interrupt */ + TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global Interrupt */ + TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ + TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ + ADC3_IRQn = 47, /*!< ADC3 global Interrupt */ + FSMC_IRQn = 48, /*!< FSMC global Interrupt */ + SDIO_IRQn = 49, /*!< SDIO global Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_IRQn = 54, /*!< TIM6 global Interrupt */ + TIM7_IRQn = 55, /*!< TIM7 global Interrupt */ + DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ + DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ + DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ + DMA2_Channel4_5_IRQn = 59 /*!< DMA2 Channel 4 and Channel 5 global Interrupt */ +#endif /* STM32F10X_XL */ + +#ifdef STM32F10X_CL + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ + CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ + TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ + TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS WakeUp from suspend through EXTI Line Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_IRQn = 54, /*!< TIM6 global Interrupt */ + TIM7_IRQn = 55, /*!< TIM7 global Interrupt */ + DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ + DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ + DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ + DMA2_Channel4_IRQn = 59, /*!< DMA2 Channel 4 global Interrupt */ + DMA2_Channel5_IRQn = 60, /*!< DMA2 Channel 5 global Interrupt */ + ETH_IRQn = 61, /*!< Ethernet global Interrupt */ + ETH_WKUP_IRQn = 62, /*!< Ethernet Wakeup through EXTI line Interrupt */ + CAN2_TX_IRQn = 63, /*!< CAN2 TX Interrupt */ + CAN2_RX0_IRQn = 64, /*!< CAN2 RX0 Interrupt */ + CAN2_RX1_IRQn = 65, /*!< CAN2 RX1 Interrupt */ + CAN2_SCE_IRQn = 66, /*!< CAN2 SCE Interrupt */ + OTG_FS_IRQn = 67 /*!< USB OTG FS global Interrupt */ +#endif /* STM32F10X_CL */ +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm3.h" +#include "system_stm32f10x.h" +#include + +/** @addtogroup Exported_types + * @{ + */ + +/*!< STM32F10x Standard Peripheral Library old types (maintained for legacy purpose) */ +typedef int32_t s32; +typedef int16_t s16; +typedef int8_t s8; + +typedef const int32_t sc32; /*!< Read Only */ +typedef const int16_t sc16; /*!< Read Only */ +typedef const int8_t sc8; /*!< Read Only */ + +typedef __IO int32_t vs32; +typedef __IO int16_t vs16; +typedef __IO int8_t vs8; + +typedef __I int32_t vsc32; /*!< Read Only */ +typedef __I int16_t vsc16; /*!< Read Only */ +typedef __I int8_t vsc8; /*!< Read Only */ + +typedef uint32_t u32; +typedef uint16_t u16; +typedef uint8_t u8; + +typedef const uint32_t uc32; /*!< Read Only */ +typedef const uint16_t uc16; /*!< Read Only */ +typedef const uint8_t uc8; /*!< Read Only */ + +typedef __IO uint32_t vu32; +typedef __IO uint16_t vu16; +typedef __IO uint8_t vu8; + +typedef __I uint32_t vuc32; /*!< Read Only */ +typedef __I uint16_t vuc16; /*!< Read Only */ +typedef __I uint8_t vuc8; /*!< Read Only */ + +typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus; + +typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; +#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) + +typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrorStatus; + +/*!< STM32F10x Standard Peripheral Library old definitions (maintained for legacy purpose) */ +#define HSEStartUp_TimeOut HSE_STARTUP_TIMEOUT +#define HSE_Value HSE_VALUE +#define HSI_Value HSI_VALUE +/** + * @} + */ + +/** @addtogroup Peripheral_registers_structures + * @{ + */ + +/** + * @brief Analog to Digital Converter + */ + +typedef struct +{ + __IO uint32_t SR; + __IO uint32_t CR1; + __IO uint32_t CR2; + __IO uint32_t SMPR1; + __IO uint32_t SMPR2; + __IO uint32_t JOFR1; + __IO uint32_t JOFR2; + __IO uint32_t JOFR3; + __IO uint32_t JOFR4; + __IO uint32_t HTR; + __IO uint32_t LTR; + __IO uint32_t SQR1; + __IO uint32_t SQR2; + __IO uint32_t SQR3; + __IO uint32_t JSQR; + __IO uint32_t JDR1; + __IO uint32_t JDR2; + __IO uint32_t JDR3; + __IO uint32_t JDR4; + __IO uint32_t DR; +} ADC_TypeDef; + +/** + * @brief Backup Registers + */ + +typedef struct +{ + uint32_t RESERVED0; + __IO uint16_t DR1; + uint16_t RESERVED1; + __IO uint16_t DR2; + uint16_t RESERVED2; + __IO uint16_t DR3; + uint16_t RESERVED3; + __IO uint16_t DR4; + uint16_t RESERVED4; + __IO uint16_t DR5; + uint16_t RESERVED5; + __IO uint16_t DR6; + uint16_t RESERVED6; + __IO uint16_t DR7; + uint16_t RESERVED7; + __IO uint16_t DR8; + uint16_t RESERVED8; + __IO uint16_t DR9; + uint16_t RESERVED9; + __IO uint16_t DR10; + uint16_t RESERVED10; + __IO uint16_t RTCCR; + uint16_t RESERVED11; + __IO uint16_t CR; + uint16_t RESERVED12; + __IO uint16_t CSR; + uint16_t RESERVED13[5]; + __IO uint16_t DR11; + uint16_t RESERVED14; + __IO uint16_t DR12; + uint16_t RESERVED15; + __IO uint16_t DR13; + uint16_t RESERVED16; + __IO uint16_t DR14; + uint16_t RESERVED17; + __IO uint16_t DR15; + uint16_t RESERVED18; + __IO uint16_t DR16; + uint16_t RESERVED19; + __IO uint16_t DR17; + uint16_t RESERVED20; + __IO uint16_t DR18; + uint16_t RESERVED21; + __IO uint16_t DR19; + uint16_t RESERVED22; + __IO uint16_t DR20; + uint16_t RESERVED23; + __IO uint16_t DR21; + uint16_t RESERVED24; + __IO uint16_t DR22; + uint16_t RESERVED25; + __IO uint16_t DR23; + uint16_t RESERVED26; + __IO uint16_t DR24; + uint16_t RESERVED27; + __IO uint16_t DR25; + uint16_t RESERVED28; + __IO uint16_t DR26; + uint16_t RESERVED29; + __IO uint16_t DR27; + uint16_t RESERVED30; + __IO uint16_t DR28; + uint16_t RESERVED31; + __IO uint16_t DR29; + uint16_t RESERVED32; + __IO uint16_t DR30; + uint16_t RESERVED33; + __IO uint16_t DR31; + uint16_t RESERVED34; + __IO uint16_t DR32; + uint16_t RESERVED35; + __IO uint16_t DR33; + uint16_t RESERVED36; + __IO uint16_t DR34; + uint16_t RESERVED37; + __IO uint16_t DR35; + uint16_t RESERVED38; + __IO uint16_t DR36; + uint16_t RESERVED39; + __IO uint16_t DR37; + uint16_t RESERVED40; + __IO uint16_t DR38; + uint16_t RESERVED41; + __IO uint16_t DR39; + uint16_t RESERVED42; + __IO uint16_t DR40; + uint16_t RESERVED43; + __IO uint16_t DR41; + uint16_t RESERVED44; + __IO uint16_t DR42; + uint16_t RESERVED45; +} BKP_TypeDef; + +/** + * @brief Controller Area Network TxMailBox + */ + +typedef struct +{ + __IO uint32_t TIR; + __IO uint32_t TDTR; + __IO uint32_t TDLR; + __IO uint32_t TDHR; +} CAN_TxMailBox_TypeDef; + +/** + * @brief Controller Area Network FIFOMailBox + */ + +typedef struct +{ + __IO uint32_t RIR; + __IO uint32_t RDTR; + __IO uint32_t RDLR; + __IO uint32_t RDHR; +} CAN_FIFOMailBox_TypeDef; + +/** + * @brief Controller Area Network FilterRegister + */ + +typedef struct +{ + __IO uint32_t FR1; + __IO uint32_t FR2; +} CAN_FilterRegister_TypeDef; + +/** + * @brief Controller Area Network + */ + +typedef struct +{ + __IO uint32_t MCR; + __IO uint32_t MSR; + __IO uint32_t TSR; + __IO uint32_t RF0R; + __IO uint32_t RF1R; + __IO uint32_t IER; + __IO uint32_t ESR; + __IO uint32_t BTR; + uint32_t RESERVED0[88]; + CAN_TxMailBox_TypeDef sTxMailBox[3]; + CAN_FIFOMailBox_TypeDef sFIFOMailBox[2]; + uint32_t RESERVED1[12]; + __IO uint32_t FMR; + __IO uint32_t FM1R; + uint32_t RESERVED2; + __IO uint32_t FS1R; + uint32_t RESERVED3; + __IO uint32_t FFA1R; + uint32_t RESERVED4; + __IO uint32_t FA1R; + uint32_t RESERVED5[8]; +#ifndef STM32F10X_CL + CAN_FilterRegister_TypeDef sFilterRegister[14]; +#else + CAN_FilterRegister_TypeDef sFilterRegister[28]; +#endif /* STM32F10X_CL */ +} CAN_TypeDef; + +/** + * @brief Consumer Electronics Control (CEC) + */ +typedef struct +{ + __IO uint32_t CFGR; + __IO uint32_t OAR; + __IO uint32_t PRES; + __IO uint32_t ESR; + __IO uint32_t CSR; + __IO uint32_t TXD; + __IO uint32_t RXD; +} CEC_TypeDef; + +/** + * @brief CRC calculation unit + */ + +typedef struct +{ + __IO uint32_t DR; + __IO uint8_t IDR; + uint8_t RESERVED0; + uint16_t RESERVED1; + __IO uint32_t CR; +} CRC_TypeDef; + +/** + * @brief Digital to Analog Converter + */ + +typedef struct +{ + __IO uint32_t CR; + __IO uint32_t SWTRIGR; + __IO uint32_t DHR12R1; + __IO uint32_t DHR12L1; + __IO uint32_t DHR8R1; + __IO uint32_t DHR12R2; + __IO uint32_t DHR12L2; + __IO uint32_t DHR8R2; + __IO uint32_t DHR12RD; + __IO uint32_t DHR12LD; + __IO uint32_t DHR8RD; + __IO uint32_t DOR1; + __IO uint32_t DOR2; +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + __IO uint32_t SR; +#endif +} DAC_TypeDef; + +/** + * @brief Debug MCU + */ + +typedef struct +{ + __IO uint32_t IDCODE; + __IO uint32_t CR; +}DBGMCU_TypeDef; + +/** + * @brief DMA Controller + */ + +typedef struct +{ + __IO uint32_t CCR; + __IO uint32_t CNDTR; + __IO uint32_t CPAR; + __IO uint32_t CMAR; +} DMA_Channel_TypeDef; + +typedef struct +{ + __IO uint32_t ISR; + __IO uint32_t IFCR; +} DMA_TypeDef; + +/** + * @brief Ethernet MAC + */ + +typedef struct +{ + __IO uint32_t MACCR; + __IO uint32_t MACFFR; + __IO uint32_t MACHTHR; + __IO uint32_t MACHTLR; + __IO uint32_t MACMIIAR; + __IO uint32_t MACMIIDR; + __IO uint32_t MACFCR; + __IO uint32_t MACVLANTR; /* 8 */ + uint32_t RESERVED0[2]; + __IO uint32_t MACRWUFFR; /* 11 */ + __IO uint32_t MACPMTCSR; + uint32_t RESERVED1[2]; + __IO uint32_t MACSR; /* 15 */ + __IO uint32_t MACIMR; + __IO uint32_t MACA0HR; + __IO uint32_t MACA0LR; + __IO uint32_t MACA1HR; + __IO uint32_t MACA1LR; + __IO uint32_t MACA2HR; + __IO uint32_t MACA2LR; + __IO uint32_t MACA3HR; + __IO uint32_t MACA3LR; /* 24 */ + uint32_t RESERVED2[40]; + __IO uint32_t MMCCR; /* 65 */ + __IO uint32_t MMCRIR; + __IO uint32_t MMCTIR; + __IO uint32_t MMCRIMR; + __IO uint32_t MMCTIMR; /* 69 */ + uint32_t RESERVED3[14]; + __IO uint32_t MMCTGFSCCR; /* 84 */ + __IO uint32_t MMCTGFMSCCR; + uint32_t RESERVED4[5]; + __IO uint32_t MMCTGFCR; + uint32_t RESERVED5[10]; + __IO uint32_t MMCRFCECR; + __IO uint32_t MMCRFAECR; + uint32_t RESERVED6[10]; + __IO uint32_t MMCRGUFCR; + uint32_t RESERVED7[334]; + __IO uint32_t PTPTSCR; + __IO uint32_t PTPSSIR; + __IO uint32_t PTPTSHR; + __IO uint32_t PTPTSLR; + __IO uint32_t PTPTSHUR; + __IO uint32_t PTPTSLUR; + __IO uint32_t PTPTSAR; + __IO uint32_t PTPTTHR; + __IO uint32_t PTPTTLR; + uint32_t RESERVED8[567]; + __IO uint32_t DMABMR; + __IO uint32_t DMATPDR; + __IO uint32_t DMARPDR; + __IO uint32_t DMARDLAR; + __IO uint32_t DMATDLAR; + __IO uint32_t DMASR; + __IO uint32_t DMAOMR; + __IO uint32_t DMAIER; + __IO uint32_t DMAMFBOCR; + uint32_t RESERVED9[9]; + __IO uint32_t DMACHTDR; + __IO uint32_t DMACHRDR; + __IO uint32_t DMACHTBAR; + __IO uint32_t DMACHRBAR; +} ETH_TypeDef; + +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ + __IO uint32_t IMR; + __IO uint32_t EMR; + __IO uint32_t RTSR; + __IO uint32_t FTSR; + __IO uint32_t SWIER; + __IO uint32_t PR; +} EXTI_TypeDef; + +/** + * @brief FLASH Registers + */ + +typedef struct +{ + __IO uint32_t ACR; + __IO uint32_t KEYR; + __IO uint32_t OPTKEYR; + __IO uint32_t SR; + __IO uint32_t CR; + __IO uint32_t AR; + __IO uint32_t RESERVED; + __IO uint32_t OBR; + __IO uint32_t WRPR; +#ifdef STM32F10X_XL + uint32_t RESERVED1[8]; + __IO uint32_t KEYR2; + uint32_t RESERVED2; + __IO uint32_t SR2; + __IO uint32_t CR2; + __IO uint32_t AR2; +#endif /* STM32F10X_XL */ +} FLASH_TypeDef; + +/** + * @brief Option Bytes Registers + */ + +typedef struct +{ + __IO uint16_t RDP; + __IO uint16_t USER; + __IO uint16_t Data0; + __IO uint16_t Data1; + __IO uint16_t WRP0; + __IO uint16_t WRP1; + __IO uint16_t WRP2; + __IO uint16_t WRP3; +} OB_TypeDef; + +/** + * @brief Flexible Static Memory Controller + */ + +typedef struct +{ + __IO uint32_t BTCR[8]; +} FSMC_Bank1_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank1E + */ + +typedef struct +{ + __IO uint32_t BWTR[7]; +} FSMC_Bank1E_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank2 + */ + +typedef struct +{ + __IO uint32_t PCR2; + __IO uint32_t SR2; + __IO uint32_t PMEM2; + __IO uint32_t PATT2; + uint32_t RESERVED0; + __IO uint32_t ECCR2; +} FSMC_Bank2_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank3 + */ + +typedef struct +{ + __IO uint32_t PCR3; + __IO uint32_t SR3; + __IO uint32_t PMEM3; + __IO uint32_t PATT3; + uint32_t RESERVED0; + __IO uint32_t ECCR3; +} FSMC_Bank3_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank4 + */ + +typedef struct +{ + __IO uint32_t PCR4; + __IO uint32_t SR4; + __IO uint32_t PMEM4; + __IO uint32_t PATT4; + __IO uint32_t PIO4; +} FSMC_Bank4_TypeDef; + +/** + * @brief General Purpose I/O + */ + +typedef struct +{ + __IO uint32_t CRL; + __IO uint32_t CRH; + __IO uint32_t IDR; + __IO uint32_t ODR; + __IO uint32_t BSRR; + __IO uint32_t BRR; + __IO uint32_t LCKR; +} GPIO_TypeDef; + +/** + * @brief Alternate Function I/O + */ + +typedef struct +{ + __IO uint32_t EVCR; + __IO uint32_t MAPR; + __IO uint32_t EXTICR[4]; + uint32_t RESERVED0; + __IO uint32_t MAPR2; +} AFIO_TypeDef; +/** + * @brief Inter Integrated Circuit Interface + */ + +typedef struct +{ + __IO uint16_t CR1; + uint16_t RESERVED0; + __IO uint16_t CR2; + uint16_t RESERVED1; + __IO uint16_t OAR1; + uint16_t RESERVED2; + __IO uint16_t OAR2; + uint16_t RESERVED3; + __IO uint16_t DR; + uint16_t RESERVED4; + __IO uint16_t SR1; + uint16_t RESERVED5; + __IO uint16_t SR2; + uint16_t RESERVED6; + __IO uint16_t CCR; + uint16_t RESERVED7; + __IO uint16_t TRISE; + uint16_t RESERVED8; +} I2C_TypeDef; + +/** + * @brief Independent WATCHDOG + */ + +typedef struct +{ + __IO uint32_t KR; + __IO uint32_t PR; + __IO uint32_t RLR; + __IO uint32_t SR; +} IWDG_TypeDef; + +/** + * @brief Power Control + */ + +typedef struct +{ + __IO uint32_t CR; + __IO uint32_t CSR; +} PWR_TypeDef; + +/** + * @brief Reset and Clock Control + */ + +typedef struct +{ + __IO uint32_t CR; + __IO uint32_t CFGR; + __IO uint32_t CIR; + __IO uint32_t APB2RSTR; + __IO uint32_t APB1RSTR; + __IO uint32_t AHBENR; + __IO uint32_t APB2ENR; + __IO uint32_t APB1ENR; + __IO uint32_t BDCR; + __IO uint32_t CSR; + +#ifdef STM32F10X_CL + __IO uint32_t AHBRSTR; + __IO uint32_t CFGR2; +#endif /* STM32F10X_CL */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + uint32_t RESERVED0; + __IO uint32_t CFGR2; +#endif /* STM32F10X_LD_VL || STM32F10X_MD_VL || STM32F10X_HD_VL */ +} RCC_TypeDef; + +/** + * @brief Real-Time Clock + */ + +typedef struct +{ + __IO uint16_t CRH; + uint16_t RESERVED0; + __IO uint16_t CRL; + uint16_t RESERVED1; + __IO uint16_t PRLH; + uint16_t RESERVED2; + __IO uint16_t PRLL; + uint16_t RESERVED3; + __IO uint16_t DIVH; + uint16_t RESERVED4; + __IO uint16_t DIVL; + uint16_t RESERVED5; + __IO uint16_t CNTH; + uint16_t RESERVED6; + __IO uint16_t CNTL; + uint16_t RESERVED7; + __IO uint16_t ALRH; + uint16_t RESERVED8; + __IO uint16_t ALRL; + uint16_t RESERVED9; +} RTC_TypeDef; + +/** + * @brief SD host Interface + */ + +typedef struct +{ + __IO uint32_t POWER; + __IO uint32_t CLKCR; + __IO uint32_t ARG; + __IO uint32_t CMD; + __I uint32_t RESPCMD; + __I uint32_t RESP1; + __I uint32_t RESP2; + __I uint32_t RESP3; + __I uint32_t RESP4; + __IO uint32_t DTIMER; + __IO uint32_t DLEN; + __IO uint32_t DCTRL; + __I uint32_t DCOUNT; + __I uint32_t STA; + __IO uint32_t ICR; + __IO uint32_t MASK; + uint32_t RESERVED0[2]; + __I uint32_t FIFOCNT; + uint32_t RESERVED1[13]; + __IO uint32_t FIFO; +} SDIO_TypeDef; + +/** + * @brief Serial Peripheral Interface + */ + +typedef struct +{ + __IO uint16_t CR1; + uint16_t RESERVED0; + __IO uint16_t CR2; + uint16_t RESERVED1; + __IO uint16_t SR; + uint16_t RESERVED2; + __IO uint16_t DR; + uint16_t RESERVED3; + __IO uint16_t CRCPR; + uint16_t RESERVED4; + __IO uint16_t RXCRCR; + uint16_t RESERVED5; + __IO uint16_t TXCRCR; + uint16_t RESERVED6; + __IO uint16_t I2SCFGR; + uint16_t RESERVED7; + __IO uint16_t I2SPR; + uint16_t RESERVED8; +} SPI_TypeDef; + +/** + * @brief TIM + */ + +typedef struct +{ + __IO uint16_t CR1; + uint16_t RESERVED0; + __IO uint16_t CR2; + uint16_t RESERVED1; + __IO uint16_t SMCR; + uint16_t RESERVED2; + __IO uint16_t DIER; + uint16_t RESERVED3; + __IO uint16_t SR; + uint16_t RESERVED4; + __IO uint16_t EGR; + uint16_t RESERVED5; + __IO uint16_t CCMR1; + uint16_t RESERVED6; + __IO uint16_t CCMR2; + uint16_t RESERVED7; + __IO uint16_t CCER; + uint16_t RESERVED8; + __IO uint16_t CNT; + uint16_t RESERVED9; + __IO uint16_t PSC; + uint16_t RESERVED10; + __IO uint16_t ARR; + uint16_t RESERVED11; + __IO uint16_t RCR; + uint16_t RESERVED12; + __IO uint16_t CCR1; + uint16_t RESERVED13; + __IO uint16_t CCR2; + uint16_t RESERVED14; + __IO uint16_t CCR3; + uint16_t RESERVED15; + __IO uint16_t CCR4; + uint16_t RESERVED16; + __IO uint16_t BDTR; + uint16_t RESERVED17; + __IO uint16_t DCR; + uint16_t RESERVED18; + __IO uint16_t DMAR; + uint16_t RESERVED19; +} TIM_TypeDef; + +/** + * @brief Universal Synchronous Asynchronous Receiver Transmitter + */ + +typedef struct +{ + __IO uint16_t SR; + uint16_t RESERVED0; + __IO uint16_t DR; + uint16_t RESERVED1; + __IO uint16_t BRR; + uint16_t RESERVED2; + __IO uint16_t CR1; + uint16_t RESERVED3; + __IO uint16_t CR2; + uint16_t RESERVED4; + __IO uint16_t CR3; + uint16_t RESERVED5; + __IO uint16_t GTPR; + uint16_t RESERVED6; +} USART_TypeDef; + +/** + * @brief Window WATCHDOG + */ + +typedef struct +{ + __IO uint32_t CR; + __IO uint32_t CFR; + __IO uint32_t SR; +} WWDG_TypeDef; + +/** + * @} + */ + +/** @addtogroup Peripheral_memory_map + * @{ + */ + + +#define FLASH_BASE ((uint32_t)0x08000000) /*!< FLASH base address in the alias region */ +#define SRAM_BASE ((uint32_t)0x20000000) /*!< SRAM base address in the alias region */ +#define PERIPH_BASE ((uint32_t)0x40000000) /*!< Peripheral base address in the alias region */ + +#define SRAM_BB_BASE ((uint32_t)0x22000000) /*!< SRAM base address in the bit-band region */ +#define PERIPH_BB_BASE ((uint32_t)0x42000000) /*!< Peripheral base address in the bit-band region */ + +#define FSMC_R_BASE ((uint32_t)0xA0000000) /*!< FSMC registers base address */ + +/*!< Peripheral memory map */ +#define APB1PERIPH_BASE PERIPH_BASE +#define APB2PERIPH_BASE (PERIPH_BASE + 0x10000) +#define AHBPERIPH_BASE (PERIPH_BASE + 0x20000) + +#define TIM2_BASE (APB1PERIPH_BASE + 0x0000) +#define TIM3_BASE (APB1PERIPH_BASE + 0x0400) +#define TIM4_BASE (APB1PERIPH_BASE + 0x0800) +#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00) +#define TIM6_BASE (APB1PERIPH_BASE + 0x1000) +#define TIM7_BASE (APB1PERIPH_BASE + 0x1400) +#define TIM12_BASE (APB1PERIPH_BASE + 0x1800) +#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00) +#define TIM14_BASE (APB1PERIPH_BASE + 0x2000) +#define RTC_BASE (APB1PERIPH_BASE + 0x2800) +#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00) +#define IWDG_BASE (APB1PERIPH_BASE + 0x3000) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00) +#define UART5_BASE (APB1PERIPH_BASE + 0x5000) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800) +#define CAN1_BASE (APB1PERIPH_BASE + 0x6400) +#define CAN2_BASE (APB1PERIPH_BASE + 0x6800) +#define BKP_BASE (APB1PERIPH_BASE + 0x6C00) +#define PWR_BASE (APB1PERIPH_BASE + 0x7000) +#define DAC_BASE (APB1PERIPH_BASE + 0x7400) +#define CEC_BASE (APB1PERIPH_BASE + 0x7800) + +#define AFIO_BASE (APB2PERIPH_BASE + 0x0000) +#define EXTI_BASE (APB2PERIPH_BASE + 0x0400) +#define GPIOA_BASE (APB2PERIPH_BASE + 0x0800) +#define GPIOB_BASE (APB2PERIPH_BASE + 0x0C00) +#define GPIOC_BASE (APB2PERIPH_BASE + 0x1000) +#define GPIOD_BASE (APB2PERIPH_BASE + 0x1400) +#define GPIOE_BASE (APB2PERIPH_BASE + 0x1800) +#define GPIOF_BASE (APB2PERIPH_BASE + 0x1C00) +#define GPIOG_BASE (APB2PERIPH_BASE + 0x2000) +#define ADC1_BASE (APB2PERIPH_BASE + 0x2400) +#define ADC2_BASE (APB2PERIPH_BASE + 0x2800) +#define TIM1_BASE (APB2PERIPH_BASE + 0x2C00) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000) +#define TIM8_BASE (APB2PERIPH_BASE + 0x3400) +#define USART1_BASE (APB2PERIPH_BASE + 0x3800) +#define ADC3_BASE (APB2PERIPH_BASE + 0x3C00) +#define TIM15_BASE (APB2PERIPH_BASE + 0x4000) +#define TIM16_BASE (APB2PERIPH_BASE + 0x4400) +#define TIM17_BASE (APB2PERIPH_BASE + 0x4800) +#define TIM9_BASE (APB2PERIPH_BASE + 0x4C00) +#define TIM10_BASE (APB2PERIPH_BASE + 0x5000) +#define TIM11_BASE (APB2PERIPH_BASE + 0x5400) + +#define SDIO_BASE (PERIPH_BASE + 0x18000) + +#define DMA1_BASE (AHBPERIPH_BASE + 0x0000) +#define DMA1_Channel1_BASE (AHBPERIPH_BASE + 0x0008) +#define DMA1_Channel2_BASE (AHBPERIPH_BASE + 0x001C) +#define DMA1_Channel3_BASE (AHBPERIPH_BASE + 0x0030) +#define DMA1_Channel4_BASE (AHBPERIPH_BASE + 0x0044) +#define DMA1_Channel5_BASE (AHBPERIPH_BASE + 0x0058) +#define DMA1_Channel6_BASE (AHBPERIPH_BASE + 0x006C) +#define DMA1_Channel7_BASE (AHBPERIPH_BASE + 0x0080) +#define DMA2_BASE (AHBPERIPH_BASE + 0x0400) +#define DMA2_Channel1_BASE (AHBPERIPH_BASE + 0x0408) +#define DMA2_Channel2_BASE (AHBPERIPH_BASE + 0x041C) +#define DMA2_Channel3_BASE (AHBPERIPH_BASE + 0x0430) +#define DMA2_Channel4_BASE (AHBPERIPH_BASE + 0x0444) +#define DMA2_Channel5_BASE (AHBPERIPH_BASE + 0x0458) +#define RCC_BASE (AHBPERIPH_BASE + 0x1000) +#define CRC_BASE (AHBPERIPH_BASE + 0x3000) + +#define FLASH_R_BASE (AHBPERIPH_BASE + 0x2000) /*!< Flash registers base address */ +#define OB_BASE ((uint32_t)0x1FFFF800) /*!< Flash Option Bytes base address */ + +#define ETH_BASE (AHBPERIPH_BASE + 0x8000) +#define ETH_MAC_BASE (ETH_BASE) +#define ETH_MMC_BASE (ETH_BASE + 0x0100) +#define ETH_PTP_BASE (ETH_BASE + 0x0700) +#define ETH_DMA_BASE (ETH_BASE + 0x1000) + +#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000) /*!< FSMC Bank1 registers base address */ +#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104) /*!< FSMC Bank1E registers base address */ +#define FSMC_Bank2_R_BASE (FSMC_R_BASE + 0x0060) /*!< FSMC Bank2 registers base address */ +#define FSMC_Bank3_R_BASE (FSMC_R_BASE + 0x0080) /*!< FSMC Bank3 registers base address */ +#define FSMC_Bank4_R_BASE (FSMC_R_BASE + 0x00A0) /*!< FSMC Bank4 registers base address */ + +#define DBGMCU_BASE ((uint32_t)0xE0042000) /*!< Debug MCU registers base address */ + +/** + * @} + */ + +/** @addtogroup Peripheral_declaration + * @{ + */ + +#define TIM2 ((TIM_TypeDef *) TIM2_BASE) +#define TIM3 ((TIM_TypeDef *) TIM3_BASE) +#define TIM4 ((TIM_TypeDef *) TIM4_BASE) +#define TIM5 ((TIM_TypeDef *) TIM5_BASE) +#define TIM6 ((TIM_TypeDef *) TIM6_BASE) +#define TIM7 ((TIM_TypeDef *) TIM7_BASE) +#define TIM12 ((TIM_TypeDef *) TIM12_BASE) +#define TIM13 ((TIM_TypeDef *) TIM13_BASE) +#define TIM14 ((TIM_TypeDef *) TIM14_BASE) +#define RTC ((RTC_TypeDef *) RTC_BASE) +#define WWDG ((WWDG_TypeDef *) WWDG_BASE) +#define IWDG ((IWDG_TypeDef *) IWDG_BASE) +#define SPI2 ((SPI_TypeDef *) SPI2_BASE) +#define SPI3 ((SPI_TypeDef *) SPI3_BASE) +#define USART2 ((USART_TypeDef *) USART2_BASE) +#define USART3 ((USART_TypeDef *) USART3_BASE) +#define UART4 ((USART_TypeDef *) UART4_BASE) +#define UART5 ((USART_TypeDef *) UART5_BASE) +#define I2C1 ((I2C_TypeDef *) I2C1_BASE) +#define I2C2 ((I2C_TypeDef *) I2C2_BASE) +#define CAN1 ((CAN_TypeDef *) CAN1_BASE) +#define CAN2 ((CAN_TypeDef *) CAN2_BASE) +#define BKP ((BKP_TypeDef *) BKP_BASE) +#define PWR ((PWR_TypeDef *) PWR_BASE) +#define DAC ((DAC_TypeDef *) DAC_BASE) +#define CEC ((CEC_TypeDef *) CEC_BASE) +#define AFIO ((AFIO_TypeDef *) AFIO_BASE) +#define EXTI ((EXTI_TypeDef *) EXTI_BASE) +#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) +#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) +#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) +#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) +#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) +#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) +#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) +#define ADC1 ((ADC_TypeDef *) ADC1_BASE) +#define ADC2 ((ADC_TypeDef *) ADC2_BASE) +#define TIM1 ((TIM_TypeDef *) TIM1_BASE) +#define SPI1 ((SPI_TypeDef *) SPI1_BASE) +#define TIM8 ((TIM_TypeDef *) TIM8_BASE) +#define USART1 ((USART_TypeDef *) USART1_BASE) +#define ADC3 ((ADC_TypeDef *) ADC3_BASE) +#define TIM15 ((TIM_TypeDef *) TIM15_BASE) +#define TIM16 ((TIM_TypeDef *) TIM16_BASE) +#define TIM17 ((TIM_TypeDef *) TIM17_BASE) +#define TIM9 ((TIM_TypeDef *) TIM9_BASE) +#define TIM10 ((TIM_TypeDef *) TIM10_BASE) +#define TIM11 ((TIM_TypeDef *) TIM11_BASE) +#define SDIO ((SDIO_TypeDef *) SDIO_BASE) +#define DMA1 ((DMA_TypeDef *) DMA1_BASE) +#define DMA2 ((DMA_TypeDef *) DMA2_BASE) +#define DMA1_Channel1 ((DMA_Channel_TypeDef *) DMA1_Channel1_BASE) +#define DMA1_Channel2 ((DMA_Channel_TypeDef *) DMA1_Channel2_BASE) +#define DMA1_Channel3 ((DMA_Channel_TypeDef *) DMA1_Channel3_BASE) +#define DMA1_Channel4 ((DMA_Channel_TypeDef *) DMA1_Channel4_BASE) +#define DMA1_Channel5 ((DMA_Channel_TypeDef *) DMA1_Channel5_BASE) +#define DMA1_Channel6 ((DMA_Channel_TypeDef *) DMA1_Channel6_BASE) +#define DMA1_Channel7 ((DMA_Channel_TypeDef *) DMA1_Channel7_BASE) +#define DMA2_Channel1 ((DMA_Channel_TypeDef *) DMA2_Channel1_BASE) +#define DMA2_Channel2 ((DMA_Channel_TypeDef *) DMA2_Channel2_BASE) +#define DMA2_Channel3 ((DMA_Channel_TypeDef *) DMA2_Channel3_BASE) +#define DMA2_Channel4 ((DMA_Channel_TypeDef *) DMA2_Channel4_BASE) +#define DMA2_Channel5 ((DMA_Channel_TypeDef *) DMA2_Channel5_BASE) +#define RCC ((RCC_TypeDef *) RCC_BASE) +#define CRC ((CRC_TypeDef *) CRC_BASE) +#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) +#define OB ((OB_TypeDef *) OB_BASE) +#define ETH ((ETH_TypeDef *) ETH_BASE) +#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) +#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) +#define FSMC_Bank2 ((FSMC_Bank2_TypeDef *) FSMC_Bank2_R_BASE) +#define FSMC_Bank3 ((FSMC_Bank3_TypeDef *) FSMC_Bank3_R_BASE) +#define FSMC_Bank4 ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE) +#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) + +/** + * @} + */ + +/** @addtogroup Exported_constants + * @{ + */ + + /** @addtogroup Peripheral_Registers_Bits_Definition + * @{ + */ + +/******************************************************************************/ +/* Peripheral Registers_Bits_Definition */ +/******************************************************************************/ + +/******************************************************************************/ +/* */ +/* CRC calculation unit */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for CRC_DR register *********************/ +#define CRC_DR_DR ((uint32_t)0xFFFFFFFF) /*!< Data register bits */ + + +/******************* Bit definition for CRC_IDR register ********************/ +#define CRC_IDR_IDR ((uint8_t)0xFF) /*!< General-purpose 8-bit data register bits */ + + +/******************** Bit definition for CRC_CR register ********************/ +#define CRC_CR_RESET ((uint8_t)0x01) /*!< RESET bit */ + +/******************************************************************************/ +/* */ +/* Power Control */ +/* */ +/******************************************************************************/ + +/******************** Bit definition for PWR_CR register ********************/ +#define PWR_CR_LPDS ((uint16_t)0x0001) /*!< Low-Power Deepsleep */ +#define PWR_CR_PDDS ((uint16_t)0x0002) /*!< Power Down Deepsleep */ +#define PWR_CR_CWUF ((uint16_t)0x0004) /*!< Clear Wakeup Flag */ +#define PWR_CR_CSBF ((uint16_t)0x0008) /*!< Clear Standby Flag */ +#define PWR_CR_PVDE ((uint16_t)0x0010) /*!< Power Voltage Detector Enable */ + +#define PWR_CR_PLS ((uint16_t)0x00E0) /*!< PLS[2:0] bits (PVD Level Selection) */ +#define PWR_CR_PLS_0 ((uint16_t)0x0020) /*!< Bit 0 */ +#define PWR_CR_PLS_1 ((uint16_t)0x0040) /*!< Bit 1 */ +#define PWR_CR_PLS_2 ((uint16_t)0x0080) /*!< Bit 2 */ + +/*!< PVD level configuration */ +#define PWR_CR_PLS_2V2 ((uint16_t)0x0000) /*!< PVD level 2.2V */ +#define PWR_CR_PLS_2V3 ((uint16_t)0x0020) /*!< PVD level 2.3V */ +#define PWR_CR_PLS_2V4 ((uint16_t)0x0040) /*!< PVD level 2.4V */ +#define PWR_CR_PLS_2V5 ((uint16_t)0x0060) /*!< PVD level 2.5V */ +#define PWR_CR_PLS_2V6 ((uint16_t)0x0080) /*!< PVD level 2.6V */ +#define PWR_CR_PLS_2V7 ((uint16_t)0x00A0) /*!< PVD level 2.7V */ +#define PWR_CR_PLS_2V8 ((uint16_t)0x00C0) /*!< PVD level 2.8V */ +#define PWR_CR_PLS_2V9 ((uint16_t)0x00E0) /*!< PVD level 2.9V */ + +#define PWR_CR_DBP ((uint16_t)0x0100) /*!< Disable Backup Domain write protection */ + + +/******************* Bit definition for PWR_CSR register ********************/ +#define PWR_CSR_WUF ((uint16_t)0x0001) /*!< Wakeup Flag */ +#define PWR_CSR_SBF ((uint16_t)0x0002) /*!< Standby Flag */ +#define PWR_CSR_PVDO ((uint16_t)0x0004) /*!< PVD Output */ +#define PWR_CSR_EWUP ((uint16_t)0x0100) /*!< Enable WKUP pin */ + +/******************************************************************************/ +/* */ +/* Backup registers */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for BKP_DR1 register ********************/ +#define BKP_DR1_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR2 register ********************/ +#define BKP_DR2_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR3 register ********************/ +#define BKP_DR3_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR4 register ********************/ +#define BKP_DR4_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR5 register ********************/ +#define BKP_DR5_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR6 register ********************/ +#define BKP_DR6_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR7 register ********************/ +#define BKP_DR7_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR8 register ********************/ +#define BKP_DR8_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR9 register ********************/ +#define BKP_DR9_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR10 register *******************/ +#define BKP_DR10_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR11 register *******************/ +#define BKP_DR11_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR12 register *******************/ +#define BKP_DR12_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR13 register *******************/ +#define BKP_DR13_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR14 register *******************/ +#define BKP_DR14_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR15 register *******************/ +#define BKP_DR15_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR16 register *******************/ +#define BKP_DR16_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR17 register *******************/ +#define BKP_DR17_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/****************** Bit definition for BKP_DR18 register ********************/ +#define BKP_DR18_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR19 register *******************/ +#define BKP_DR19_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR20 register *******************/ +#define BKP_DR20_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR21 register *******************/ +#define BKP_DR21_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR22 register *******************/ +#define BKP_DR22_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR23 register *******************/ +#define BKP_DR23_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR24 register *******************/ +#define BKP_DR24_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR25 register *******************/ +#define BKP_DR25_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR26 register *******************/ +#define BKP_DR26_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR27 register *******************/ +#define BKP_DR27_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR28 register *******************/ +#define BKP_DR28_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR29 register *******************/ +#define BKP_DR29_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR30 register *******************/ +#define BKP_DR30_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR31 register *******************/ +#define BKP_DR31_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR32 register *******************/ +#define BKP_DR32_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR33 register *******************/ +#define BKP_DR33_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR34 register *******************/ +#define BKP_DR34_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR35 register *******************/ +#define BKP_DR35_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR36 register *******************/ +#define BKP_DR36_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR37 register *******************/ +#define BKP_DR37_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR38 register *******************/ +#define BKP_DR38_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR39 register *******************/ +#define BKP_DR39_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR40 register *******************/ +#define BKP_DR40_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR41 register *******************/ +#define BKP_DR41_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR42 register *******************/ +#define BKP_DR42_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/****************** Bit definition for BKP_RTCCR register *******************/ +#define BKP_RTCCR_CAL ((uint16_t)0x007F) /*!< Calibration value */ +#define BKP_RTCCR_CCO ((uint16_t)0x0080) /*!< Calibration Clock Output */ +#define BKP_RTCCR_ASOE ((uint16_t)0x0100) /*!< Alarm or Second Output Enable */ +#define BKP_RTCCR_ASOS ((uint16_t)0x0200) /*!< Alarm or Second Output Selection */ + +/******************** Bit definition for BKP_CR register ********************/ +#define BKP_CR_TPE ((uint8_t)0x01) /*!< TAMPER pin enable */ +#define BKP_CR_TPAL ((uint8_t)0x02) /*!< TAMPER pin active level */ + +/******************* Bit definition for BKP_CSR register ********************/ +#define BKP_CSR_CTE ((uint16_t)0x0001) /*!< Clear Tamper event */ +#define BKP_CSR_CTI ((uint16_t)0x0002) /*!< Clear Tamper Interrupt */ +#define BKP_CSR_TPIE ((uint16_t)0x0004) /*!< TAMPER Pin interrupt enable */ +#define BKP_CSR_TEF ((uint16_t)0x0100) /*!< Tamper Event Flag */ +#define BKP_CSR_TIF ((uint16_t)0x0200) /*!< Tamper Interrupt Flag */ + +/******************************************************************************/ +/* */ +/* Reset and Clock Control */ +/* */ +/******************************************************************************/ + +/******************** Bit definition for RCC_CR register ********************/ +#define RCC_CR_HSION ((uint32_t)0x00000001) /*!< Internal High Speed clock enable */ +#define RCC_CR_HSIRDY ((uint32_t)0x00000002) /*!< Internal High Speed clock ready flag */ +#define RCC_CR_HSITRIM ((uint32_t)0x000000F8) /*!< Internal High Speed clock trimming */ +#define RCC_CR_HSICAL ((uint32_t)0x0000FF00) /*!< Internal High Speed clock Calibration */ +#define RCC_CR_HSEON ((uint32_t)0x00010000) /*!< External High Speed clock enable */ +#define RCC_CR_HSERDY ((uint32_t)0x00020000) /*!< External High Speed clock ready flag */ +#define RCC_CR_HSEBYP ((uint32_t)0x00040000) /*!< External High Speed clock Bypass */ +#define RCC_CR_CSSON ((uint32_t)0x00080000) /*!< Clock Security System enable */ +#define RCC_CR_PLLON ((uint32_t)0x01000000) /*!< PLL enable */ +#define RCC_CR_PLLRDY ((uint32_t)0x02000000) /*!< PLL clock ready flag */ + +#ifdef STM32F10X_CL + #define RCC_CR_PLL2ON ((uint32_t)0x04000000) /*!< PLL2 enable */ + #define RCC_CR_PLL2RDY ((uint32_t)0x08000000) /*!< PLL2 clock ready flag */ + #define RCC_CR_PLL3ON ((uint32_t)0x10000000) /*!< PLL3 enable */ + #define RCC_CR_PLL3RDY ((uint32_t)0x20000000) /*!< PLL3 clock ready flag */ +#endif /* STM32F10X_CL */ + +/******************* Bit definition for RCC_CFGR register *******************/ +/*!< SW configuration */ +#define RCC_CFGR_SW ((uint32_t)0x00000003) /*!< SW[1:0] bits (System clock Switch) */ +#define RCC_CFGR_SW_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define RCC_CFGR_SW_1 ((uint32_t)0x00000002) /*!< Bit 1 */ + +#define RCC_CFGR_SW_HSI ((uint32_t)0x00000000) /*!< HSI selected as system clock */ +#define RCC_CFGR_SW_HSE ((uint32_t)0x00000001) /*!< HSE selected as system clock */ +#define RCC_CFGR_SW_PLL ((uint32_t)0x00000002) /*!< PLL selected as system clock */ + +/*!< SWS configuration */ +#define RCC_CFGR_SWS ((uint32_t)0x0000000C) /*!< SWS[1:0] bits (System Clock Switch Status) */ +#define RCC_CFGR_SWS_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define RCC_CFGR_SWS_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define RCC_CFGR_SWS_HSI ((uint32_t)0x00000000) /*!< HSI oscillator used as system clock */ +#define RCC_CFGR_SWS_HSE ((uint32_t)0x00000004) /*!< HSE oscillator used as system clock */ +#define RCC_CFGR_SWS_PLL ((uint32_t)0x00000008) /*!< PLL used as system clock */ + +/*!< HPRE configuration */ +#define RCC_CFGR_HPRE ((uint32_t)0x000000F0) /*!< HPRE[3:0] bits (AHB prescaler) */ +#define RCC_CFGR_HPRE_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define RCC_CFGR_HPRE_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define RCC_CFGR_HPRE_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define RCC_CFGR_HPRE_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define RCC_CFGR_HPRE_DIV1 ((uint32_t)0x00000000) /*!< SYSCLK not divided */ +#define RCC_CFGR_HPRE_DIV2 ((uint32_t)0x00000080) /*!< SYSCLK divided by 2 */ +#define RCC_CFGR_HPRE_DIV4 ((uint32_t)0x00000090) /*!< SYSCLK divided by 4 */ +#define RCC_CFGR_HPRE_DIV8 ((uint32_t)0x000000A0) /*!< SYSCLK divided by 8 */ +#define RCC_CFGR_HPRE_DIV16 ((uint32_t)0x000000B0) /*!< SYSCLK divided by 16 */ +#define RCC_CFGR_HPRE_DIV64 ((uint32_t)0x000000C0) /*!< SYSCLK divided by 64 */ +#define RCC_CFGR_HPRE_DIV128 ((uint32_t)0x000000D0) /*!< SYSCLK divided by 128 */ +#define RCC_CFGR_HPRE_DIV256 ((uint32_t)0x000000E0) /*!< SYSCLK divided by 256 */ +#define RCC_CFGR_HPRE_DIV512 ((uint32_t)0x000000F0) /*!< SYSCLK divided by 512 */ + +/*!< PPRE1 configuration */ +#define RCC_CFGR_PPRE1 ((uint32_t)0x00000700) /*!< PRE1[2:0] bits (APB1 prescaler) */ +#define RCC_CFGR_PPRE1_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define RCC_CFGR_PPRE1_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define RCC_CFGR_PPRE1_2 ((uint32_t)0x00000400) /*!< Bit 2 */ + +#define RCC_CFGR_PPRE1_DIV1 ((uint32_t)0x00000000) /*!< HCLK not divided */ +#define RCC_CFGR_PPRE1_DIV2 ((uint32_t)0x00000400) /*!< HCLK divided by 2 */ +#define RCC_CFGR_PPRE1_DIV4 ((uint32_t)0x00000500) /*!< HCLK divided by 4 */ +#define RCC_CFGR_PPRE1_DIV8 ((uint32_t)0x00000600) /*!< HCLK divided by 8 */ +#define RCC_CFGR_PPRE1_DIV16 ((uint32_t)0x00000700) /*!< HCLK divided by 16 */ + +/*!< PPRE2 configuration */ +#define RCC_CFGR_PPRE2 ((uint32_t)0x00003800) /*!< PRE2[2:0] bits (APB2 prescaler) */ +#define RCC_CFGR_PPRE2_0 ((uint32_t)0x00000800) /*!< Bit 0 */ +#define RCC_CFGR_PPRE2_1 ((uint32_t)0x00001000) /*!< Bit 1 */ +#define RCC_CFGR_PPRE2_2 ((uint32_t)0x00002000) /*!< Bit 2 */ + +#define RCC_CFGR_PPRE2_DIV1 ((uint32_t)0x00000000) /*!< HCLK not divided */ +#define RCC_CFGR_PPRE2_DIV2 ((uint32_t)0x00002000) /*!< HCLK divided by 2 */ +#define RCC_CFGR_PPRE2_DIV4 ((uint32_t)0x00002800) /*!< HCLK divided by 4 */ +#define RCC_CFGR_PPRE2_DIV8 ((uint32_t)0x00003000) /*!< HCLK divided by 8 */ +#define RCC_CFGR_PPRE2_DIV16 ((uint32_t)0x00003800) /*!< HCLK divided by 16 */ + +/*!< ADCPPRE configuration */ +#define RCC_CFGR_ADCPRE ((uint32_t)0x0000C000) /*!< ADCPRE[1:0] bits (ADC prescaler) */ +#define RCC_CFGR_ADCPRE_0 ((uint32_t)0x00004000) /*!< Bit 0 */ +#define RCC_CFGR_ADCPRE_1 ((uint32_t)0x00008000) /*!< Bit 1 */ + +#define RCC_CFGR_ADCPRE_DIV2 ((uint32_t)0x00000000) /*!< PCLK2 divided by 2 */ +#define RCC_CFGR_ADCPRE_DIV4 ((uint32_t)0x00004000) /*!< PCLK2 divided by 4 */ +#define RCC_CFGR_ADCPRE_DIV6 ((uint32_t)0x00008000) /*!< PCLK2 divided by 6 */ +#define RCC_CFGR_ADCPRE_DIV8 ((uint32_t)0x0000C000) /*!< PCLK2 divided by 8 */ + +#define RCC_CFGR_PLLSRC ((uint32_t)0x00010000) /*!< PLL entry clock source */ + +#define RCC_CFGR_PLLXTPRE ((uint32_t)0x00020000) /*!< HSE divider for PLL entry */ + +/*!< PLLMUL configuration */ +#define RCC_CFGR_PLLMULL ((uint32_t)0x003C0000) /*!< PLLMUL[3:0] bits (PLL multiplication factor) */ +#define RCC_CFGR_PLLMULL_0 ((uint32_t)0x00040000) /*!< Bit 0 */ +#define RCC_CFGR_PLLMULL_1 ((uint32_t)0x00080000) /*!< Bit 1 */ +#define RCC_CFGR_PLLMULL_2 ((uint32_t)0x00100000) /*!< Bit 2 */ +#define RCC_CFGR_PLLMULL_3 ((uint32_t)0x00200000) /*!< Bit 3 */ + +#ifdef STM32F10X_CL + #define RCC_CFGR_PLLSRC_HSI_Div2 ((uint32_t)0x00000000) /*!< HSI clock divided by 2 selected as PLL entry clock source */ + #define RCC_CFGR_PLLSRC_PREDIV1 ((uint32_t)0x00010000) /*!< PREDIV1 clock selected as PLL entry clock source */ + + #define RCC_CFGR_PLLXTPRE_PREDIV1 ((uint32_t)0x00000000) /*!< PREDIV1 clock not divided for PLL entry */ + #define RCC_CFGR_PLLXTPRE_PREDIV1_Div2 ((uint32_t)0x00020000) /*!< PREDIV1 clock divided by 2 for PLL entry */ + + #define RCC_CFGR_PLLMULL4 ((uint32_t)0x00080000) /*!< PLL input clock * 4 */ + #define RCC_CFGR_PLLMULL5 ((uint32_t)0x000C0000) /*!< PLL input clock * 5 */ + #define RCC_CFGR_PLLMULL6 ((uint32_t)0x00100000) /*!< PLL input clock * 6 */ + #define RCC_CFGR_PLLMULL7 ((uint32_t)0x00140000) /*!< PLL input clock * 7 */ + #define RCC_CFGR_PLLMULL8 ((uint32_t)0x00180000) /*!< PLL input clock * 8 */ + #define RCC_CFGR_PLLMULL9 ((uint32_t)0x001C0000) /*!< PLL input clock * 9 */ + #define RCC_CFGR_PLLMULL6_5 ((uint32_t)0x00340000) /*!< PLL input clock * 6.5 */ + + #define RCC_CFGR_OTGFSPRE ((uint32_t)0x00400000) /*!< USB OTG FS prescaler */ + +/*!< MCO configuration */ + #define RCC_CFGR_MCO ((uint32_t)0x0F000000) /*!< MCO[3:0] bits (Microcontroller Clock Output) */ + #define RCC_CFGR_MCO_0 ((uint32_t)0x01000000) /*!< Bit 0 */ + #define RCC_CFGR_MCO_1 ((uint32_t)0x02000000) /*!< Bit 1 */ + #define RCC_CFGR_MCO_2 ((uint32_t)0x04000000) /*!< Bit 2 */ + #define RCC_CFGR_MCO_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + + #define RCC_CFGR_MCO_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ + #define RCC_CFGR_MCO_SYSCLK ((uint32_t)0x04000000) /*!< System clock selected as MCO source */ + #define RCC_CFGR_MCO_HSI ((uint32_t)0x05000000) /*!< HSI clock selected as MCO source */ + #define RCC_CFGR_MCO_HSE ((uint32_t)0x06000000) /*!< HSE clock selected as MCO source */ + #define RCC_CFGR_MCO_PLLCLK_Div2 ((uint32_t)0x07000000) /*!< PLL clock divided by 2 selected as MCO source */ + #define RCC_CFGR_MCO_PLL2CLK ((uint32_t)0x08000000) /*!< PLL2 clock selected as MCO source*/ + #define RCC_CFGR_MCO_PLL3CLK_Div2 ((uint32_t)0x09000000) /*!< PLL3 clock divided by 2 selected as MCO source*/ + #define RCC_CFGR_MCO_Ext_HSE ((uint32_t)0x0A000000) /*!< XT1 external 3-25 MHz oscillator clock selected as MCO source */ + #define RCC_CFGR_MCO_PLL3CLK ((uint32_t)0x0B000000) /*!< PLL3 clock selected as MCO source */ +#elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + #define RCC_CFGR_PLLSRC_HSI_Div2 ((uint32_t)0x00000000) /*!< HSI clock divided by 2 selected as PLL entry clock source */ + #define RCC_CFGR_PLLSRC_PREDIV1 ((uint32_t)0x00010000) /*!< PREDIV1 clock selected as PLL entry clock source */ + + #define RCC_CFGR_PLLXTPRE_PREDIV1 ((uint32_t)0x00000000) /*!< PREDIV1 clock not divided for PLL entry */ + #define RCC_CFGR_PLLXTPRE_PREDIV1_Div2 ((uint32_t)0x00020000) /*!< PREDIV1 clock divided by 2 for PLL entry */ + + #define RCC_CFGR_PLLMULL2 ((uint32_t)0x00000000) /*!< PLL input clock*2 */ + #define RCC_CFGR_PLLMULL3 ((uint32_t)0x00040000) /*!< PLL input clock*3 */ + #define RCC_CFGR_PLLMULL4 ((uint32_t)0x00080000) /*!< PLL input clock*4 */ + #define RCC_CFGR_PLLMULL5 ((uint32_t)0x000C0000) /*!< PLL input clock*5 */ + #define RCC_CFGR_PLLMULL6 ((uint32_t)0x00100000) /*!< PLL input clock*6 */ + #define RCC_CFGR_PLLMULL7 ((uint32_t)0x00140000) /*!< PLL input clock*7 */ + #define RCC_CFGR_PLLMULL8 ((uint32_t)0x00180000) /*!< PLL input clock*8 */ + #define RCC_CFGR_PLLMULL9 ((uint32_t)0x001C0000) /*!< PLL input clock*9 */ + #define RCC_CFGR_PLLMULL10 ((uint32_t)0x00200000) /*!< PLL input clock10 */ + #define RCC_CFGR_PLLMULL11 ((uint32_t)0x00240000) /*!< PLL input clock*11 */ + #define RCC_CFGR_PLLMULL12 ((uint32_t)0x00280000) /*!< PLL input clock*12 */ + #define RCC_CFGR_PLLMULL13 ((uint32_t)0x002C0000) /*!< PLL input clock*13 */ + #define RCC_CFGR_PLLMULL14 ((uint32_t)0x00300000) /*!< PLL input clock*14 */ + #define RCC_CFGR_PLLMULL15 ((uint32_t)0x00340000) /*!< PLL input clock*15 */ + #define RCC_CFGR_PLLMULL16 ((uint32_t)0x00380000) /*!< PLL input clock*16 */ + +/*!< MCO configuration */ + #define RCC_CFGR_MCO ((uint32_t)0x07000000) /*!< MCO[2:0] bits (Microcontroller Clock Output) */ + #define RCC_CFGR_MCO_0 ((uint32_t)0x01000000) /*!< Bit 0 */ + #define RCC_CFGR_MCO_1 ((uint32_t)0x02000000) /*!< Bit 1 */ + #define RCC_CFGR_MCO_2 ((uint32_t)0x04000000) /*!< Bit 2 */ + + #define RCC_CFGR_MCO_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ + #define RCC_CFGR_MCO_SYSCLK ((uint32_t)0x04000000) /*!< System clock selected as MCO source */ + #define RCC_CFGR_MCO_HSI ((uint32_t)0x05000000) /*!< HSI clock selected as MCO source */ + #define RCC_CFGR_MCO_HSE ((uint32_t)0x06000000) /*!< HSE clock selected as MCO source */ + #define RCC_CFGR_MCO_PLL ((uint32_t)0x07000000) /*!< PLL clock divided by 2 selected as MCO source */ +#else + #define RCC_CFGR_PLLSRC_HSI_Div2 ((uint32_t)0x00000000) /*!< HSI clock divided by 2 selected as PLL entry clock source */ + #define RCC_CFGR_PLLSRC_HSE ((uint32_t)0x00010000) /*!< HSE clock selected as PLL entry clock source */ + + #define RCC_CFGR_PLLXTPRE_HSE ((uint32_t)0x00000000) /*!< HSE clock not divided for PLL entry */ + #define RCC_CFGR_PLLXTPRE_HSE_Div2 ((uint32_t)0x00020000) /*!< HSE clock divided by 2 for PLL entry */ + + #define RCC_CFGR_PLLMULL2 ((uint32_t)0x00000000) /*!< PLL input clock*2 */ + #define RCC_CFGR_PLLMULL3 ((uint32_t)0x00040000) /*!< PLL input clock*3 */ + #define RCC_CFGR_PLLMULL4 ((uint32_t)0x00080000) /*!< PLL input clock*4 */ + #define RCC_CFGR_PLLMULL5 ((uint32_t)0x000C0000) /*!< PLL input clock*5 */ + #define RCC_CFGR_PLLMULL6 ((uint32_t)0x00100000) /*!< PLL input clock*6 */ + #define RCC_CFGR_PLLMULL7 ((uint32_t)0x00140000) /*!< PLL input clock*7 */ + #define RCC_CFGR_PLLMULL8 ((uint32_t)0x00180000) /*!< PLL input clock*8 */ + #define RCC_CFGR_PLLMULL9 ((uint32_t)0x001C0000) /*!< PLL input clock*9 */ + #define RCC_CFGR_PLLMULL10 ((uint32_t)0x00200000) /*!< PLL input clock10 */ + #define RCC_CFGR_PLLMULL11 ((uint32_t)0x00240000) /*!< PLL input clock*11 */ + #define RCC_CFGR_PLLMULL12 ((uint32_t)0x00280000) /*!< PLL input clock*12 */ + #define RCC_CFGR_PLLMULL13 ((uint32_t)0x002C0000) /*!< PLL input clock*13 */ + #define RCC_CFGR_PLLMULL14 ((uint32_t)0x00300000) /*!< PLL input clock*14 */ + #define RCC_CFGR_PLLMULL15 ((uint32_t)0x00340000) /*!< PLL input clock*15 */ + #define RCC_CFGR_PLLMULL16 ((uint32_t)0x00380000) /*!< PLL input clock*16 */ + #define RCC_CFGR_USBPRE ((uint32_t)0x00400000) /*!< USB Device prescaler */ + +/*!< MCO configuration */ + #define RCC_CFGR_MCO ((uint32_t)0x07000000) /*!< MCO[2:0] bits (Microcontroller Clock Output) */ + #define RCC_CFGR_MCO_0 ((uint32_t)0x01000000) /*!< Bit 0 */ + #define RCC_CFGR_MCO_1 ((uint32_t)0x02000000) /*!< Bit 1 */ + #define RCC_CFGR_MCO_2 ((uint32_t)0x04000000) /*!< Bit 2 */ + + #define RCC_CFGR_MCO_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ + #define RCC_CFGR_MCO_SYSCLK ((uint32_t)0x04000000) /*!< System clock selected as MCO source */ + #define RCC_CFGR_MCO_HSI ((uint32_t)0x05000000) /*!< HSI clock selected as MCO source */ + #define RCC_CFGR_MCO_HSE ((uint32_t)0x06000000) /*!< HSE clock selected as MCO source */ + #define RCC_CFGR_MCO_PLL ((uint32_t)0x07000000) /*!< PLL clock divided by 2 selected as MCO source */ +#endif /* STM32F10X_CL */ + +/*!<****************** Bit definition for RCC_CIR register ********************/ +#define RCC_CIR_LSIRDYF ((uint32_t)0x00000001) /*!< LSI Ready Interrupt flag */ +#define RCC_CIR_LSERDYF ((uint32_t)0x00000002) /*!< LSE Ready Interrupt flag */ +#define RCC_CIR_HSIRDYF ((uint32_t)0x00000004) /*!< HSI Ready Interrupt flag */ +#define RCC_CIR_HSERDYF ((uint32_t)0x00000008) /*!< HSE Ready Interrupt flag */ +#define RCC_CIR_PLLRDYF ((uint32_t)0x00000010) /*!< PLL Ready Interrupt flag */ +#define RCC_CIR_CSSF ((uint32_t)0x00000080) /*!< Clock Security System Interrupt flag */ +#define RCC_CIR_LSIRDYIE ((uint32_t)0x00000100) /*!< LSI Ready Interrupt Enable */ +#define RCC_CIR_LSERDYIE ((uint32_t)0x00000200) /*!< LSE Ready Interrupt Enable */ +#define RCC_CIR_HSIRDYIE ((uint32_t)0x00000400) /*!< HSI Ready Interrupt Enable */ +#define RCC_CIR_HSERDYIE ((uint32_t)0x00000800) /*!< HSE Ready Interrupt Enable */ +#define RCC_CIR_PLLRDYIE ((uint32_t)0x00001000) /*!< PLL Ready Interrupt Enable */ +#define RCC_CIR_LSIRDYC ((uint32_t)0x00010000) /*!< LSI Ready Interrupt Clear */ +#define RCC_CIR_LSERDYC ((uint32_t)0x00020000) /*!< LSE Ready Interrupt Clear */ +#define RCC_CIR_HSIRDYC ((uint32_t)0x00040000) /*!< HSI Ready Interrupt Clear */ +#define RCC_CIR_HSERDYC ((uint32_t)0x00080000) /*!< HSE Ready Interrupt Clear */ +#define RCC_CIR_PLLRDYC ((uint32_t)0x00100000) /*!< PLL Ready Interrupt Clear */ +#define RCC_CIR_CSSC ((uint32_t)0x00800000) /*!< Clock Security System Interrupt Clear */ + +#ifdef STM32F10X_CL + #define RCC_CIR_PLL2RDYF ((uint32_t)0x00000020) /*!< PLL2 Ready Interrupt flag */ + #define RCC_CIR_PLL3RDYF ((uint32_t)0x00000040) /*!< PLL3 Ready Interrupt flag */ + #define RCC_CIR_PLL2RDYIE ((uint32_t)0x00002000) /*!< PLL2 Ready Interrupt Enable */ + #define RCC_CIR_PLL3RDYIE ((uint32_t)0x00004000) /*!< PLL3 Ready Interrupt Enable */ + #define RCC_CIR_PLL2RDYC ((uint32_t)0x00200000) /*!< PLL2 Ready Interrupt Clear */ + #define RCC_CIR_PLL3RDYC ((uint32_t)0x00400000) /*!< PLL3 Ready Interrupt Clear */ +#endif /* STM32F10X_CL */ + +/***************** Bit definition for RCC_APB2RSTR register *****************/ +#define RCC_APB2RSTR_AFIORST ((uint32_t)0x00000001) /*!< Alternate Function I/O reset */ +#define RCC_APB2RSTR_IOPARST ((uint32_t)0x00000004) /*!< I/O port A reset */ +#define RCC_APB2RSTR_IOPBRST ((uint32_t)0x00000008) /*!< I/O port B reset */ +#define RCC_APB2RSTR_IOPCRST ((uint32_t)0x00000010) /*!< I/O port C reset */ +#define RCC_APB2RSTR_IOPDRST ((uint32_t)0x00000020) /*!< I/O port D reset */ +#define RCC_APB2RSTR_ADC1RST ((uint32_t)0x00000200) /*!< ADC 1 interface reset */ + +#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) +#define RCC_APB2RSTR_ADC2RST ((uint32_t)0x00000400) /*!< ADC 2 interface reset */ +#endif + +#define RCC_APB2RSTR_TIM1RST ((uint32_t)0x00000800) /*!< TIM1 Timer reset */ +#define RCC_APB2RSTR_SPI1RST ((uint32_t)0x00001000) /*!< SPI 1 reset */ +#define RCC_APB2RSTR_USART1RST ((uint32_t)0x00004000) /*!< USART1 reset */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +#define RCC_APB2RSTR_TIM15RST ((uint32_t)0x00010000) /*!< TIM15 Timer reset */ +#define RCC_APB2RSTR_TIM16RST ((uint32_t)0x00020000) /*!< TIM16 Timer reset */ +#define RCC_APB2RSTR_TIM17RST ((uint32_t)0x00040000) /*!< TIM17 Timer reset */ +#endif + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) + #define RCC_APB2RSTR_IOPERST ((uint32_t)0x00000040) /*!< I/O port E reset */ +#endif /* STM32F10X_LD && STM32F10X_LD_VL */ + +#if defined (STM32F10X_HD) || defined (STM32F10X_XL) + #define RCC_APB2RSTR_IOPFRST ((uint32_t)0x00000080) /*!< I/O port F reset */ + #define RCC_APB2RSTR_IOPGRST ((uint32_t)0x00000100) /*!< I/O port G reset */ + #define RCC_APB2RSTR_TIM8RST ((uint32_t)0x00002000) /*!< TIM8 Timer reset */ + #define RCC_APB2RSTR_ADC3RST ((uint32_t)0x00008000) /*!< ADC3 interface reset */ +#endif + +#if defined (STM32F10X_HD_VL) + #define RCC_APB2RSTR_IOPFRST ((uint32_t)0x00000080) /*!< I/O port F reset */ + #define RCC_APB2RSTR_IOPGRST ((uint32_t)0x00000100) /*!< I/O port G reset */ +#endif + +#ifdef STM32F10X_XL + #define RCC_APB2RSTR_TIM9RST ((uint32_t)0x00080000) /*!< TIM9 Timer reset */ + #define RCC_APB2RSTR_TIM10RST ((uint32_t)0x00100000) /*!< TIM10 Timer reset */ + #define RCC_APB2RSTR_TIM11RST ((uint32_t)0x00200000) /*!< TIM11 Timer reset */ +#endif /* STM32F10X_XL */ + +/***************** Bit definition for RCC_APB1RSTR register *****************/ +#define RCC_APB1RSTR_TIM2RST ((uint32_t)0x00000001) /*!< Timer 2 reset */ +#define RCC_APB1RSTR_TIM3RST ((uint32_t)0x00000002) /*!< Timer 3 reset */ +#define RCC_APB1RSTR_WWDGRST ((uint32_t)0x00000800) /*!< Window Watchdog reset */ +#define RCC_APB1RSTR_USART2RST ((uint32_t)0x00020000) /*!< USART 2 reset */ +#define RCC_APB1RSTR_I2C1RST ((uint32_t)0x00200000) /*!< I2C 1 reset */ + +#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) +#define RCC_APB1RSTR_CAN1RST ((uint32_t)0x02000000) /*!< CAN1 reset */ +#endif + +#define RCC_APB1RSTR_BKPRST ((uint32_t)0x08000000) /*!< Backup interface reset */ +#define RCC_APB1RSTR_PWRRST ((uint32_t)0x10000000) /*!< Power interface reset */ + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) + #define RCC_APB1RSTR_TIM4RST ((uint32_t)0x00000004) /*!< Timer 4 reset */ + #define RCC_APB1RSTR_SPI2RST ((uint32_t)0x00004000) /*!< SPI 2 reset */ + #define RCC_APB1RSTR_USART3RST ((uint32_t)0x00040000) /*!< USART 3 reset */ + #define RCC_APB1RSTR_I2C2RST ((uint32_t)0x00400000) /*!< I2C 2 reset */ +#endif /* STM32F10X_LD && STM32F10X_LD_VL */ + +#if defined (STM32F10X_HD) || defined (STM32F10X_MD) || defined (STM32F10X_LD) || defined (STM32F10X_XL) + #define RCC_APB1RSTR_USBRST ((uint32_t)0x00800000) /*!< USB Device reset */ +#endif + +#if defined (STM32F10X_HD) || defined (STM32F10X_CL) || defined (STM32F10X_XL) + #define RCC_APB1RSTR_TIM5RST ((uint32_t)0x00000008) /*!< Timer 5 reset */ + #define RCC_APB1RSTR_TIM6RST ((uint32_t)0x00000010) /*!< Timer 6 reset */ + #define RCC_APB1RSTR_TIM7RST ((uint32_t)0x00000020) /*!< Timer 7 reset */ + #define RCC_APB1RSTR_SPI3RST ((uint32_t)0x00008000) /*!< SPI 3 reset */ + #define RCC_APB1RSTR_UART4RST ((uint32_t)0x00080000) /*!< UART 4 reset */ + #define RCC_APB1RSTR_UART5RST ((uint32_t)0x00100000) /*!< UART 5 reset */ + #define RCC_APB1RSTR_DACRST ((uint32_t)0x20000000) /*!< DAC interface reset */ +#endif + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + #define RCC_APB1RSTR_TIM6RST ((uint32_t)0x00000010) /*!< Timer 6 reset */ + #define RCC_APB1RSTR_TIM7RST ((uint32_t)0x00000020) /*!< Timer 7 reset */ + #define RCC_APB1RSTR_DACRST ((uint32_t)0x20000000) /*!< DAC interface reset */ + #define RCC_APB1RSTR_CECRST ((uint32_t)0x40000000) /*!< CEC interface reset */ +#endif + +#if defined (STM32F10X_HD_VL) + #define RCC_APB1RSTR_TIM5RST ((uint32_t)0x00000008) /*!< Timer 5 reset */ + #define RCC_APB1RSTR_TIM12RST ((uint32_t)0x00000040) /*!< TIM12 Timer reset */ + #define RCC_APB1RSTR_TIM13RST ((uint32_t)0x00000080) /*!< TIM13 Timer reset */ + #define RCC_APB1RSTR_TIM14RST ((uint32_t)0x00000100) /*!< TIM14 Timer reset */ + #define RCC_APB1RSTR_SPI3RST ((uint32_t)0x00008000) /*!< SPI 3 reset */ + #define RCC_APB1RSTR_UART4RST ((uint32_t)0x00080000) /*!< UART 4 reset */ + #define RCC_APB1RSTR_UART5RST ((uint32_t)0x00100000) /*!< UART 5 reset */ +#endif + +#ifdef STM32F10X_CL + #define RCC_APB1RSTR_CAN2RST ((uint32_t)0x04000000) /*!< CAN2 reset */ +#endif /* STM32F10X_CL */ + +#ifdef STM32F10X_XL + #define RCC_APB1RSTR_TIM12RST ((uint32_t)0x00000040) /*!< TIM12 Timer reset */ + #define RCC_APB1RSTR_TIM13RST ((uint32_t)0x00000080) /*!< TIM13 Timer reset */ + #define RCC_APB1RSTR_TIM14RST ((uint32_t)0x00000100) /*!< TIM14 Timer reset */ +#endif /* STM32F10X_XL */ + +/****************** Bit definition for RCC_AHBENR register ******************/ +#define RCC_AHBENR_DMA1EN ((uint16_t)0x0001) /*!< DMA1 clock enable */ +#define RCC_AHBENR_SRAMEN ((uint16_t)0x0004) /*!< SRAM interface clock enable */ +#define RCC_AHBENR_FLITFEN ((uint16_t)0x0010) /*!< FLITF clock enable */ +#define RCC_AHBENR_CRCEN ((uint16_t)0x0040) /*!< CRC clock enable */ + +#if defined (STM32F10X_HD) || defined (STM32F10X_CL) || defined (STM32F10X_HD_VL) + #define RCC_AHBENR_DMA2EN ((uint16_t)0x0002) /*!< DMA2 clock enable */ +#endif + +#if defined (STM32F10X_HD) || defined (STM32F10X_XL) + #define RCC_AHBENR_FSMCEN ((uint16_t)0x0100) /*!< FSMC clock enable */ + #define RCC_AHBENR_SDIOEN ((uint16_t)0x0400) /*!< SDIO clock enable */ +#endif + +#if defined (STM32F10X_HD_VL) + #define RCC_AHBENR_FSMCEN ((uint16_t)0x0100) /*!< FSMC clock enable */ +#endif + +#ifdef STM32F10X_CL + #define RCC_AHBENR_OTGFSEN ((uint32_t)0x00001000) /*!< USB OTG FS clock enable */ + #define RCC_AHBENR_ETHMACEN ((uint32_t)0x00004000) /*!< ETHERNET MAC clock enable */ + #define RCC_AHBENR_ETHMACTXEN ((uint32_t)0x00008000) /*!< ETHERNET MAC Tx clock enable */ + #define RCC_AHBENR_ETHMACRXEN ((uint32_t)0x00010000) /*!< ETHERNET MAC Rx clock enable */ +#endif /* STM32F10X_CL */ + +/****************** Bit definition for RCC_APB2ENR register *****************/ +#define RCC_APB2ENR_AFIOEN ((uint32_t)0x00000001) /*!< Alternate Function I/O clock enable */ +#define RCC_APB2ENR_IOPAEN ((uint32_t)0x00000004) /*!< I/O port A clock enable */ +#define RCC_APB2ENR_IOPBEN ((uint32_t)0x00000008) /*!< I/O port B clock enable */ +#define RCC_APB2ENR_IOPCEN ((uint32_t)0x00000010) /*!< I/O port C clock enable */ +#define RCC_APB2ENR_IOPDEN ((uint32_t)0x00000020) /*!< I/O port D clock enable */ +#define RCC_APB2ENR_ADC1EN ((uint32_t)0x00000200) /*!< ADC 1 interface clock enable */ + +#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) +#define RCC_APB2ENR_ADC2EN ((uint32_t)0x00000400) /*!< ADC 2 interface clock enable */ +#endif + +#define RCC_APB2ENR_TIM1EN ((uint32_t)0x00000800) /*!< TIM1 Timer clock enable */ +#define RCC_APB2ENR_SPI1EN ((uint32_t)0x00001000) /*!< SPI 1 clock enable */ +#define RCC_APB2ENR_USART1EN ((uint32_t)0x00004000) /*!< USART1 clock enable */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +#define RCC_APB2ENR_TIM15EN ((uint32_t)0x00010000) /*!< TIM15 Timer clock enable */ +#define RCC_APB2ENR_TIM16EN ((uint32_t)0x00020000) /*!< TIM16 Timer clock enable */ +#define RCC_APB2ENR_TIM17EN ((uint32_t)0x00040000) /*!< TIM17 Timer clock enable */ +#endif + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) + #define RCC_APB2ENR_IOPEEN ((uint32_t)0x00000040) /*!< I/O port E clock enable */ +#endif /* STM32F10X_LD && STM32F10X_LD_VL */ + +#if defined (STM32F10X_HD) || defined (STM32F10X_XL) + #define RCC_APB2ENR_IOPFEN ((uint32_t)0x00000080) /*!< I/O port F clock enable */ + #define RCC_APB2ENR_IOPGEN ((uint32_t)0x00000100) /*!< I/O port G clock enable */ + #define RCC_APB2ENR_TIM8EN ((uint32_t)0x00002000) /*!< TIM8 Timer clock enable */ + #define RCC_APB2ENR_ADC3EN ((uint32_t)0x00008000) /*!< DMA1 clock enable */ +#endif + +#if defined (STM32F10X_HD_VL) + #define RCC_APB2ENR_IOPFEN ((uint32_t)0x00000080) /*!< I/O port F clock enable */ + #define RCC_APB2ENR_IOPGEN ((uint32_t)0x00000100) /*!< I/O port G clock enable */ +#endif + +#ifdef STM32F10X_XL + #define RCC_APB2ENR_TIM9EN ((uint32_t)0x00080000) /*!< TIM9 Timer clock enable */ + #define RCC_APB2ENR_TIM10EN ((uint32_t)0x00100000) /*!< TIM10 Timer clock enable */ + #define RCC_APB2ENR_TIM11EN ((uint32_t)0x00200000) /*!< TIM11 Timer clock enable */ +#endif + +/***************** Bit definition for RCC_APB1ENR register ******************/ +#define RCC_APB1ENR_TIM2EN ((uint32_t)0x00000001) /*!< Timer 2 clock enabled*/ +#define RCC_APB1ENR_TIM3EN ((uint32_t)0x00000002) /*!< Timer 3 clock enable */ +#define RCC_APB1ENR_WWDGEN ((uint32_t)0x00000800) /*!< Window Watchdog clock enable */ +#define RCC_APB1ENR_USART2EN ((uint32_t)0x00020000) /*!< USART 2 clock enable */ +#define RCC_APB1ENR_I2C1EN ((uint32_t)0x00200000) /*!< I2C 1 clock enable */ + +#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) +#define RCC_APB1ENR_CAN1EN ((uint32_t)0x02000000) /*!< CAN1 clock enable */ +#endif + +#define RCC_APB1ENR_BKPEN ((uint32_t)0x08000000) /*!< Backup interface clock enable */ +#define RCC_APB1ENR_PWREN ((uint32_t)0x10000000) /*!< Power interface clock enable */ + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) + #define RCC_APB1ENR_TIM4EN ((uint32_t)0x00000004) /*!< Timer 4 clock enable */ + #define RCC_APB1ENR_SPI2EN ((uint32_t)0x00004000) /*!< SPI 2 clock enable */ + #define RCC_APB1ENR_USART3EN ((uint32_t)0x00040000) /*!< USART 3 clock enable */ + #define RCC_APB1ENR_I2C2EN ((uint32_t)0x00400000) /*!< I2C 2 clock enable */ +#endif /* STM32F10X_LD && STM32F10X_LD_VL */ + +#if defined (STM32F10X_HD) || defined (STM32F10X_MD) || defined (STM32F10X_LD) + #define RCC_APB1ENR_USBEN ((uint32_t)0x00800000) /*!< USB Device clock enable */ +#endif + +#if defined (STM32F10X_HD) || defined (STM32F10X_CL) + #define RCC_APB1ENR_TIM5EN ((uint32_t)0x00000008) /*!< Timer 5 clock enable */ + #define RCC_APB1ENR_TIM6EN ((uint32_t)0x00000010) /*!< Timer 6 clock enable */ + #define RCC_APB1ENR_TIM7EN ((uint32_t)0x00000020) /*!< Timer 7 clock enable */ + #define RCC_APB1ENR_SPI3EN ((uint32_t)0x00008000) /*!< SPI 3 clock enable */ + #define RCC_APB1ENR_UART4EN ((uint32_t)0x00080000) /*!< UART 4 clock enable */ + #define RCC_APB1ENR_UART5EN ((uint32_t)0x00100000) /*!< UART 5 clock enable */ + #define RCC_APB1ENR_DACEN ((uint32_t)0x20000000) /*!< DAC interface clock enable */ +#endif + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + #define RCC_APB1ENR_TIM6EN ((uint32_t)0x00000010) /*!< Timer 6 clock enable */ + #define RCC_APB1ENR_TIM7EN ((uint32_t)0x00000020) /*!< Timer 7 clock enable */ + #define RCC_APB1ENR_DACEN ((uint32_t)0x20000000) /*!< DAC interface clock enable */ + #define RCC_APB1ENR_CECEN ((uint32_t)0x40000000) /*!< CEC interface clock enable */ +#endif + +#ifdef STM32F10X_HD_VL + #define RCC_APB1ENR_TIM5EN ((uint32_t)0x00000008) /*!< Timer 5 clock enable */ + #define RCC_APB1ENR_TIM12EN ((uint32_t)0x00000040) /*!< TIM12 Timer clock enable */ + #define RCC_APB1ENR_TIM13EN ((uint32_t)0x00000080) /*!< TIM13 Timer clock enable */ + #define RCC_APB1ENR_TIM14EN ((uint32_t)0x00000100) /*!< TIM14 Timer clock enable */ + #define RCC_APB1ENR_SPI3EN ((uint32_t)0x00008000) /*!< SPI 3 clock enable */ + #define RCC_APB1ENR_UART4EN ((uint32_t)0x00080000) /*!< UART 4 clock enable */ + #define RCC_APB1ENR_UART5EN ((uint32_t)0x00100000) /*!< UART 5 clock enable */ +#endif /* STM32F10X_HD_VL */ + +#ifdef STM32F10X_CL + #define RCC_APB1ENR_CAN2EN ((uint32_t)0x04000000) /*!< CAN2 clock enable */ +#endif /* STM32F10X_CL */ + +#ifdef STM32F10X_XL + #define RCC_APB1ENR_TIM12EN ((uint32_t)0x00000040) /*!< TIM12 Timer clock enable */ + #define RCC_APB1ENR_TIM13EN ((uint32_t)0x00000080) /*!< TIM13 Timer clock enable */ + #define RCC_APB1ENR_TIM14EN ((uint32_t)0x00000100) /*!< TIM14 Timer clock enable */ +#endif /* STM32F10X_XL */ + +/******************* Bit definition for RCC_BDCR register *******************/ +#define RCC_BDCR_LSEON ((uint32_t)0x00000001) /*!< External Low Speed oscillator enable */ +#define RCC_BDCR_LSERDY ((uint32_t)0x00000002) /*!< External Low Speed oscillator Ready */ +#define RCC_BDCR_LSEBYP ((uint32_t)0x00000004) /*!< External Low Speed oscillator Bypass */ + +#define RCC_BDCR_RTCSEL ((uint32_t)0x00000300) /*!< RTCSEL[1:0] bits (RTC clock source selection) */ +#define RCC_BDCR_RTCSEL_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define RCC_BDCR_RTCSEL_1 ((uint32_t)0x00000200) /*!< Bit 1 */ + +/*!< RTC congiguration */ +#define RCC_BDCR_RTCSEL_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ +#define RCC_BDCR_RTCSEL_LSE ((uint32_t)0x00000100) /*!< LSE oscillator clock used as RTC clock */ +#define RCC_BDCR_RTCSEL_LSI ((uint32_t)0x00000200) /*!< LSI oscillator clock used as RTC clock */ +#define RCC_BDCR_RTCSEL_HSE ((uint32_t)0x00000300) /*!< HSE oscillator clock divided by 128 used as RTC clock */ + +#define RCC_BDCR_RTCEN ((uint32_t)0x00008000) /*!< RTC clock enable */ +#define RCC_BDCR_BDRST ((uint32_t)0x00010000) /*!< Backup domain software reset */ + +/******************* Bit definition for RCC_CSR register ********************/ +#define RCC_CSR_LSION ((uint32_t)0x00000001) /*!< Internal Low Speed oscillator enable */ +#define RCC_CSR_LSIRDY ((uint32_t)0x00000002) /*!< Internal Low Speed oscillator Ready */ +#define RCC_CSR_RMVF ((uint32_t)0x01000000) /*!< Remove reset flag */ +#define RCC_CSR_PINRSTF ((uint32_t)0x04000000) /*!< PIN reset flag */ +#define RCC_CSR_PORRSTF ((uint32_t)0x08000000) /*!< POR/PDR reset flag */ +#define RCC_CSR_SFTRSTF ((uint32_t)0x10000000) /*!< Software Reset flag */ +#define RCC_CSR_IWDGRSTF ((uint32_t)0x20000000) /*!< Independent Watchdog reset flag */ +#define RCC_CSR_WWDGRSTF ((uint32_t)0x40000000) /*!< Window watchdog reset flag */ +#define RCC_CSR_LPWRRSTF ((uint32_t)0x80000000) /*!< Low-Power reset flag */ + +#ifdef STM32F10X_CL +/******************* Bit definition for RCC_AHBRSTR register ****************/ + #define RCC_AHBRSTR_OTGFSRST ((uint32_t)0x00001000) /*!< USB OTG FS reset */ + #define RCC_AHBRSTR_ETHMACRST ((uint32_t)0x00004000) /*!< ETHERNET MAC reset */ + +/******************* Bit definition for RCC_CFGR2 register ******************/ +/*!< PREDIV1 configuration */ + #define RCC_CFGR2_PREDIV1 ((uint32_t)0x0000000F) /*!< PREDIV1[3:0] bits */ + #define RCC_CFGR2_PREDIV1_0 ((uint32_t)0x00000001) /*!< Bit 0 */ + #define RCC_CFGR2_PREDIV1_1 ((uint32_t)0x00000002) /*!< Bit 1 */ + #define RCC_CFGR2_PREDIV1_2 ((uint32_t)0x00000004) /*!< Bit 2 */ + #define RCC_CFGR2_PREDIV1_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + + #define RCC_CFGR2_PREDIV1_DIV1 ((uint32_t)0x00000000) /*!< PREDIV1 input clock not divided */ + #define RCC_CFGR2_PREDIV1_DIV2 ((uint32_t)0x00000001) /*!< PREDIV1 input clock divided by 2 */ + #define RCC_CFGR2_PREDIV1_DIV3 ((uint32_t)0x00000002) /*!< PREDIV1 input clock divided by 3 */ + #define RCC_CFGR2_PREDIV1_DIV4 ((uint32_t)0x00000003) /*!< PREDIV1 input clock divided by 4 */ + #define RCC_CFGR2_PREDIV1_DIV5 ((uint32_t)0x00000004) /*!< PREDIV1 input clock divided by 5 */ + #define RCC_CFGR2_PREDIV1_DIV6 ((uint32_t)0x00000005) /*!< PREDIV1 input clock divided by 6 */ + #define RCC_CFGR2_PREDIV1_DIV7 ((uint32_t)0x00000006) /*!< PREDIV1 input clock divided by 7 */ + #define RCC_CFGR2_PREDIV1_DIV8 ((uint32_t)0x00000007) /*!< PREDIV1 input clock divided by 8 */ + #define RCC_CFGR2_PREDIV1_DIV9 ((uint32_t)0x00000008) /*!< PREDIV1 input clock divided by 9 */ + #define RCC_CFGR2_PREDIV1_DIV10 ((uint32_t)0x00000009) /*!< PREDIV1 input clock divided by 10 */ + #define RCC_CFGR2_PREDIV1_DIV11 ((uint32_t)0x0000000A) /*!< PREDIV1 input clock divided by 11 */ + #define RCC_CFGR2_PREDIV1_DIV12 ((uint32_t)0x0000000B) /*!< PREDIV1 input clock divided by 12 */ + #define RCC_CFGR2_PREDIV1_DIV13 ((uint32_t)0x0000000C) /*!< PREDIV1 input clock divided by 13 */ + #define RCC_CFGR2_PREDIV1_DIV14 ((uint32_t)0x0000000D) /*!< PREDIV1 input clock divided by 14 */ + #define RCC_CFGR2_PREDIV1_DIV15 ((uint32_t)0x0000000E) /*!< PREDIV1 input clock divided by 15 */ + #define RCC_CFGR2_PREDIV1_DIV16 ((uint32_t)0x0000000F) /*!< PREDIV1 input clock divided by 16 */ + +/*!< PREDIV2 configuration */ + #define RCC_CFGR2_PREDIV2 ((uint32_t)0x000000F0) /*!< PREDIV2[3:0] bits */ + #define RCC_CFGR2_PREDIV2_0 ((uint32_t)0x00000010) /*!< Bit 0 */ + #define RCC_CFGR2_PREDIV2_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + #define RCC_CFGR2_PREDIV2_2 ((uint32_t)0x00000040) /*!< Bit 2 */ + #define RCC_CFGR2_PREDIV2_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + + #define RCC_CFGR2_PREDIV2_DIV1 ((uint32_t)0x00000000) /*!< PREDIV2 input clock not divided */ + #define RCC_CFGR2_PREDIV2_DIV2 ((uint32_t)0x00000010) /*!< PREDIV2 input clock divided by 2 */ + #define RCC_CFGR2_PREDIV2_DIV3 ((uint32_t)0x00000020) /*!< PREDIV2 input clock divided by 3 */ + #define RCC_CFGR2_PREDIV2_DIV4 ((uint32_t)0x00000030) /*!< PREDIV2 input clock divided by 4 */ + #define RCC_CFGR2_PREDIV2_DIV5 ((uint32_t)0x00000040) /*!< PREDIV2 input clock divided by 5 */ + #define RCC_CFGR2_PREDIV2_DIV6 ((uint32_t)0x00000050) /*!< PREDIV2 input clock divided by 6 */ + #define RCC_CFGR2_PREDIV2_DIV7 ((uint32_t)0x00000060) /*!< PREDIV2 input clock divided by 7 */ + #define RCC_CFGR2_PREDIV2_DIV8 ((uint32_t)0x00000070) /*!< PREDIV2 input clock divided by 8 */ + #define RCC_CFGR2_PREDIV2_DIV9 ((uint32_t)0x00000080) /*!< PREDIV2 input clock divided by 9 */ + #define RCC_CFGR2_PREDIV2_DIV10 ((uint32_t)0x00000090) /*!< PREDIV2 input clock divided by 10 */ + #define RCC_CFGR2_PREDIV2_DIV11 ((uint32_t)0x000000A0) /*!< PREDIV2 input clock divided by 11 */ + #define RCC_CFGR2_PREDIV2_DIV12 ((uint32_t)0x000000B0) /*!< PREDIV2 input clock divided by 12 */ + #define RCC_CFGR2_PREDIV2_DIV13 ((uint32_t)0x000000C0) /*!< PREDIV2 input clock divided by 13 */ + #define RCC_CFGR2_PREDIV2_DIV14 ((uint32_t)0x000000D0) /*!< PREDIV2 input clock divided by 14 */ + #define RCC_CFGR2_PREDIV2_DIV15 ((uint32_t)0x000000E0) /*!< PREDIV2 input clock divided by 15 */ + #define RCC_CFGR2_PREDIV2_DIV16 ((uint32_t)0x000000F0) /*!< PREDIV2 input clock divided by 16 */ + +/*!< PLL2MUL configuration */ + #define RCC_CFGR2_PLL2MUL ((uint32_t)0x00000F00) /*!< PLL2MUL[3:0] bits */ + #define RCC_CFGR2_PLL2MUL_0 ((uint32_t)0x00000100) /*!< Bit 0 */ + #define RCC_CFGR2_PLL2MUL_1 ((uint32_t)0x00000200) /*!< Bit 1 */ + #define RCC_CFGR2_PLL2MUL_2 ((uint32_t)0x00000400) /*!< Bit 2 */ + #define RCC_CFGR2_PLL2MUL_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + + #define RCC_CFGR2_PLL2MUL8 ((uint32_t)0x00000600) /*!< PLL2 input clock * 8 */ + #define RCC_CFGR2_PLL2MUL9 ((uint32_t)0x00000700) /*!< PLL2 input clock * 9 */ + #define RCC_CFGR2_PLL2MUL10 ((uint32_t)0x00000800) /*!< PLL2 input clock * 10 */ + #define RCC_CFGR2_PLL2MUL11 ((uint32_t)0x00000900) /*!< PLL2 input clock * 11 */ + #define RCC_CFGR2_PLL2MUL12 ((uint32_t)0x00000A00) /*!< PLL2 input clock * 12 */ + #define RCC_CFGR2_PLL2MUL13 ((uint32_t)0x00000B00) /*!< PLL2 input clock * 13 */ + #define RCC_CFGR2_PLL2MUL14 ((uint32_t)0x00000C00) /*!< PLL2 input clock * 14 */ + #define RCC_CFGR2_PLL2MUL16 ((uint32_t)0x00000E00) /*!< PLL2 input clock * 16 */ + #define RCC_CFGR2_PLL2MUL20 ((uint32_t)0x00000F00) /*!< PLL2 input clock * 20 */ + +/*!< PLL3MUL configuration */ + #define RCC_CFGR2_PLL3MUL ((uint32_t)0x0000F000) /*!< PLL3MUL[3:0] bits */ + #define RCC_CFGR2_PLL3MUL_0 ((uint32_t)0x00001000) /*!< Bit 0 */ + #define RCC_CFGR2_PLL3MUL_1 ((uint32_t)0x00002000) /*!< Bit 1 */ + #define RCC_CFGR2_PLL3MUL_2 ((uint32_t)0x00004000) /*!< Bit 2 */ + #define RCC_CFGR2_PLL3MUL_3 ((uint32_t)0x00008000) /*!< Bit 3 */ + + #define RCC_CFGR2_PLL3MUL8 ((uint32_t)0x00006000) /*!< PLL3 input clock * 8 */ + #define RCC_CFGR2_PLL3MUL9 ((uint32_t)0x00007000) /*!< PLL3 input clock * 9 */ + #define RCC_CFGR2_PLL3MUL10 ((uint32_t)0x00008000) /*!< PLL3 input clock * 10 */ + #define RCC_CFGR2_PLL3MUL11 ((uint32_t)0x00009000) /*!< PLL3 input clock * 11 */ + #define RCC_CFGR2_PLL3MUL12 ((uint32_t)0x0000A000) /*!< PLL3 input clock * 12 */ + #define RCC_CFGR2_PLL3MUL13 ((uint32_t)0x0000B000) /*!< PLL3 input clock * 13 */ + #define RCC_CFGR2_PLL3MUL14 ((uint32_t)0x0000C000) /*!< PLL3 input clock * 14 */ + #define RCC_CFGR2_PLL3MUL16 ((uint32_t)0x0000E000) /*!< PLL3 input clock * 16 */ + #define RCC_CFGR2_PLL3MUL20 ((uint32_t)0x0000F000) /*!< PLL3 input clock * 20 */ + + #define RCC_CFGR2_PREDIV1SRC ((uint32_t)0x00010000) /*!< PREDIV1 entry clock source */ + #define RCC_CFGR2_PREDIV1SRC_PLL2 ((uint32_t)0x00010000) /*!< PLL2 selected as PREDIV1 entry clock source */ + #define RCC_CFGR2_PREDIV1SRC_HSE ((uint32_t)0x00000000) /*!< HSE selected as PREDIV1 entry clock source */ + #define RCC_CFGR2_I2S2SRC ((uint32_t)0x00020000) /*!< I2S2 entry clock source */ + #define RCC_CFGR2_I2S3SRC ((uint32_t)0x00040000) /*!< I2S3 clock source */ +#endif /* STM32F10X_CL */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/******************* Bit definition for RCC_CFGR2 register ******************/ +/*!< PREDIV1 configuration */ + #define RCC_CFGR2_PREDIV1 ((uint32_t)0x0000000F) /*!< PREDIV1[3:0] bits */ + #define RCC_CFGR2_PREDIV1_0 ((uint32_t)0x00000001) /*!< Bit 0 */ + #define RCC_CFGR2_PREDIV1_1 ((uint32_t)0x00000002) /*!< Bit 1 */ + #define RCC_CFGR2_PREDIV1_2 ((uint32_t)0x00000004) /*!< Bit 2 */ + #define RCC_CFGR2_PREDIV1_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + + #define RCC_CFGR2_PREDIV1_DIV1 ((uint32_t)0x00000000) /*!< PREDIV1 input clock not divided */ + #define RCC_CFGR2_PREDIV1_DIV2 ((uint32_t)0x00000001) /*!< PREDIV1 input clock divided by 2 */ + #define RCC_CFGR2_PREDIV1_DIV3 ((uint32_t)0x00000002) /*!< PREDIV1 input clock divided by 3 */ + #define RCC_CFGR2_PREDIV1_DIV4 ((uint32_t)0x00000003) /*!< PREDIV1 input clock divided by 4 */ + #define RCC_CFGR2_PREDIV1_DIV5 ((uint32_t)0x00000004) /*!< PREDIV1 input clock divided by 5 */ + #define RCC_CFGR2_PREDIV1_DIV6 ((uint32_t)0x00000005) /*!< PREDIV1 input clock divided by 6 */ + #define RCC_CFGR2_PREDIV1_DIV7 ((uint32_t)0x00000006) /*!< PREDIV1 input clock divided by 7 */ + #define RCC_CFGR2_PREDIV1_DIV8 ((uint32_t)0x00000007) /*!< PREDIV1 input clock divided by 8 */ + #define RCC_CFGR2_PREDIV1_DIV9 ((uint32_t)0x00000008) /*!< PREDIV1 input clock divided by 9 */ + #define RCC_CFGR2_PREDIV1_DIV10 ((uint32_t)0x00000009) /*!< PREDIV1 input clock divided by 10 */ + #define RCC_CFGR2_PREDIV1_DIV11 ((uint32_t)0x0000000A) /*!< PREDIV1 input clock divided by 11 */ + #define RCC_CFGR2_PREDIV1_DIV12 ((uint32_t)0x0000000B) /*!< PREDIV1 input clock divided by 12 */ + #define RCC_CFGR2_PREDIV1_DIV13 ((uint32_t)0x0000000C) /*!< PREDIV1 input clock divided by 13 */ + #define RCC_CFGR2_PREDIV1_DIV14 ((uint32_t)0x0000000D) /*!< PREDIV1 input clock divided by 14 */ + #define RCC_CFGR2_PREDIV1_DIV15 ((uint32_t)0x0000000E) /*!< PREDIV1 input clock divided by 15 */ + #define RCC_CFGR2_PREDIV1_DIV16 ((uint32_t)0x0000000F) /*!< PREDIV1 input clock divided by 16 */ +#endif + +/******************************************************************************/ +/* */ +/* General Purpose and Alternate Function I/O */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for GPIO_CRL register *******************/ +#define GPIO_CRL_MODE ((uint32_t)0x33333333) /*!< Port x mode bits */ + +#define GPIO_CRL_MODE0 ((uint32_t)0x00000003) /*!< MODE0[1:0] bits (Port x mode bits, pin 0) */ +#define GPIO_CRL_MODE0_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define GPIO_CRL_MODE0_1 ((uint32_t)0x00000002) /*!< Bit 1 */ + +#define GPIO_CRL_MODE1 ((uint32_t)0x00000030) /*!< MODE1[1:0] bits (Port x mode bits, pin 1) */ +#define GPIO_CRL_MODE1_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define GPIO_CRL_MODE1_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define GPIO_CRL_MODE2 ((uint32_t)0x00000300) /*!< MODE2[1:0] bits (Port x mode bits, pin 2) */ +#define GPIO_CRL_MODE2_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define GPIO_CRL_MODE2_1 ((uint32_t)0x00000200) /*!< Bit 1 */ + +#define GPIO_CRL_MODE3 ((uint32_t)0x00003000) /*!< MODE3[1:0] bits (Port x mode bits, pin 3) */ +#define GPIO_CRL_MODE3_0 ((uint32_t)0x00001000) /*!< Bit 0 */ +#define GPIO_CRL_MODE3_1 ((uint32_t)0x00002000) /*!< Bit 1 */ + +#define GPIO_CRL_MODE4 ((uint32_t)0x00030000) /*!< MODE4[1:0] bits (Port x mode bits, pin 4) */ +#define GPIO_CRL_MODE4_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define GPIO_CRL_MODE4_1 ((uint32_t)0x00020000) /*!< Bit 1 */ + +#define GPIO_CRL_MODE5 ((uint32_t)0x00300000) /*!< MODE5[1:0] bits (Port x mode bits, pin 5) */ +#define GPIO_CRL_MODE5_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define GPIO_CRL_MODE5_1 ((uint32_t)0x00200000) /*!< Bit 1 */ + +#define GPIO_CRL_MODE6 ((uint32_t)0x03000000) /*!< MODE6[1:0] bits (Port x mode bits, pin 6) */ +#define GPIO_CRL_MODE6_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define GPIO_CRL_MODE6_1 ((uint32_t)0x02000000) /*!< Bit 1 */ + +#define GPIO_CRL_MODE7 ((uint32_t)0x30000000) /*!< MODE7[1:0] bits (Port x mode bits, pin 7) */ +#define GPIO_CRL_MODE7_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define GPIO_CRL_MODE7_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +#define GPIO_CRL_CNF ((uint32_t)0xCCCCCCCC) /*!< Port x configuration bits */ + +#define GPIO_CRL_CNF0 ((uint32_t)0x0000000C) /*!< CNF0[1:0] bits (Port x configuration bits, pin 0) */ +#define GPIO_CRL_CNF0_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define GPIO_CRL_CNF0_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define GPIO_CRL_CNF1 ((uint32_t)0x000000C0) /*!< CNF1[1:0] bits (Port x configuration bits, pin 1) */ +#define GPIO_CRL_CNF1_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define GPIO_CRL_CNF1_1 ((uint32_t)0x00000080) /*!< Bit 1 */ + +#define GPIO_CRL_CNF2 ((uint32_t)0x00000C00) /*!< CNF2[1:0] bits (Port x configuration bits, pin 2) */ +#define GPIO_CRL_CNF2_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define GPIO_CRL_CNF2_1 ((uint32_t)0x00000800) /*!< Bit 1 */ + +#define GPIO_CRL_CNF3 ((uint32_t)0x0000C000) /*!< CNF3[1:0] bits (Port x configuration bits, pin 3) */ +#define GPIO_CRL_CNF3_0 ((uint32_t)0x00004000) /*!< Bit 0 */ +#define GPIO_CRL_CNF3_1 ((uint32_t)0x00008000) /*!< Bit 1 */ + +#define GPIO_CRL_CNF4 ((uint32_t)0x000C0000) /*!< CNF4[1:0] bits (Port x configuration bits, pin 4) */ +#define GPIO_CRL_CNF4_0 ((uint32_t)0x00040000) /*!< Bit 0 */ +#define GPIO_CRL_CNF4_1 ((uint32_t)0x00080000) /*!< Bit 1 */ + +#define GPIO_CRL_CNF5 ((uint32_t)0x00C00000) /*!< CNF5[1:0] bits (Port x configuration bits, pin 5) */ +#define GPIO_CRL_CNF5_0 ((uint32_t)0x00400000) /*!< Bit 0 */ +#define GPIO_CRL_CNF5_1 ((uint32_t)0x00800000) /*!< Bit 1 */ + +#define GPIO_CRL_CNF6 ((uint32_t)0x0C000000) /*!< CNF6[1:0] bits (Port x configuration bits, pin 6) */ +#define GPIO_CRL_CNF6_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define GPIO_CRL_CNF6_1 ((uint32_t)0x08000000) /*!< Bit 1 */ + +#define GPIO_CRL_CNF7 ((uint32_t)0xC0000000) /*!< CNF7[1:0] bits (Port x configuration bits, pin 7) */ +#define GPIO_CRL_CNF7_0 ((uint32_t)0x40000000) /*!< Bit 0 */ +#define GPIO_CRL_CNF7_1 ((uint32_t)0x80000000) /*!< Bit 1 */ + +/******************* Bit definition for GPIO_CRH register *******************/ +#define GPIO_CRH_MODE ((uint32_t)0x33333333) /*!< Port x mode bits */ + +#define GPIO_CRH_MODE8 ((uint32_t)0x00000003) /*!< MODE8[1:0] bits (Port x mode bits, pin 8) */ +#define GPIO_CRH_MODE8_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define GPIO_CRH_MODE8_1 ((uint32_t)0x00000002) /*!< Bit 1 */ + +#define GPIO_CRH_MODE9 ((uint32_t)0x00000030) /*!< MODE9[1:0] bits (Port x mode bits, pin 9) */ +#define GPIO_CRH_MODE9_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define GPIO_CRH_MODE9_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define GPIO_CRH_MODE10 ((uint32_t)0x00000300) /*!< MODE10[1:0] bits (Port x mode bits, pin 10) */ +#define GPIO_CRH_MODE10_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define GPIO_CRH_MODE10_1 ((uint32_t)0x00000200) /*!< Bit 1 */ + +#define GPIO_CRH_MODE11 ((uint32_t)0x00003000) /*!< MODE11[1:0] bits (Port x mode bits, pin 11) */ +#define GPIO_CRH_MODE11_0 ((uint32_t)0x00001000) /*!< Bit 0 */ +#define GPIO_CRH_MODE11_1 ((uint32_t)0x00002000) /*!< Bit 1 */ + +#define GPIO_CRH_MODE12 ((uint32_t)0x00030000) /*!< MODE12[1:0] bits (Port x mode bits, pin 12) */ +#define GPIO_CRH_MODE12_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define GPIO_CRH_MODE12_1 ((uint32_t)0x00020000) /*!< Bit 1 */ + +#define GPIO_CRH_MODE13 ((uint32_t)0x00300000) /*!< MODE13[1:0] bits (Port x mode bits, pin 13) */ +#define GPIO_CRH_MODE13_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define GPIO_CRH_MODE13_1 ((uint32_t)0x00200000) /*!< Bit 1 */ + +#define GPIO_CRH_MODE14 ((uint32_t)0x03000000) /*!< MODE14[1:0] bits (Port x mode bits, pin 14) */ +#define GPIO_CRH_MODE14_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define GPIO_CRH_MODE14_1 ((uint32_t)0x02000000) /*!< Bit 1 */ + +#define GPIO_CRH_MODE15 ((uint32_t)0x30000000) /*!< MODE15[1:0] bits (Port x mode bits, pin 15) */ +#define GPIO_CRH_MODE15_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define GPIO_CRH_MODE15_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +#define GPIO_CRH_CNF ((uint32_t)0xCCCCCCCC) /*!< Port x configuration bits */ + +#define GPIO_CRH_CNF8 ((uint32_t)0x0000000C) /*!< CNF8[1:0] bits (Port x configuration bits, pin 8) */ +#define GPIO_CRH_CNF8_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define GPIO_CRH_CNF8_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define GPIO_CRH_CNF9 ((uint32_t)0x000000C0) /*!< CNF9[1:0] bits (Port x configuration bits, pin 9) */ +#define GPIO_CRH_CNF9_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define GPIO_CRH_CNF9_1 ((uint32_t)0x00000080) /*!< Bit 1 */ + +#define GPIO_CRH_CNF10 ((uint32_t)0x00000C00) /*!< CNF10[1:0] bits (Port x configuration bits, pin 10) */ +#define GPIO_CRH_CNF10_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define GPIO_CRH_CNF10_1 ((uint32_t)0x00000800) /*!< Bit 1 */ + +#define GPIO_CRH_CNF11 ((uint32_t)0x0000C000) /*!< CNF11[1:0] bits (Port x configuration bits, pin 11) */ +#define GPIO_CRH_CNF11_0 ((uint32_t)0x00004000) /*!< Bit 0 */ +#define GPIO_CRH_CNF11_1 ((uint32_t)0x00008000) /*!< Bit 1 */ + +#define GPIO_CRH_CNF12 ((uint32_t)0x000C0000) /*!< CNF12[1:0] bits (Port x configuration bits, pin 12) */ +#define GPIO_CRH_CNF12_0 ((uint32_t)0x00040000) /*!< Bit 0 */ +#define GPIO_CRH_CNF12_1 ((uint32_t)0x00080000) /*!< Bit 1 */ + +#define GPIO_CRH_CNF13 ((uint32_t)0x00C00000) /*!< CNF13[1:0] bits (Port x configuration bits, pin 13) */ +#define GPIO_CRH_CNF13_0 ((uint32_t)0x00400000) /*!< Bit 0 */ +#define GPIO_CRH_CNF13_1 ((uint32_t)0x00800000) /*!< Bit 1 */ + +#define GPIO_CRH_CNF14 ((uint32_t)0x0C000000) /*!< CNF14[1:0] bits (Port x configuration bits, pin 14) */ +#define GPIO_CRH_CNF14_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define GPIO_CRH_CNF14_1 ((uint32_t)0x08000000) /*!< Bit 1 */ + +#define GPIO_CRH_CNF15 ((uint32_t)0xC0000000) /*!< CNF15[1:0] bits (Port x configuration bits, pin 15) */ +#define GPIO_CRH_CNF15_0 ((uint32_t)0x40000000) /*!< Bit 0 */ +#define GPIO_CRH_CNF15_1 ((uint32_t)0x80000000) /*!< Bit 1 */ + +/*!<****************** Bit definition for GPIO_IDR register *******************/ +#define GPIO_IDR_IDR0 ((uint16_t)0x0001) /*!< Port input data, bit 0 */ +#define GPIO_IDR_IDR1 ((uint16_t)0x0002) /*!< Port input data, bit 1 */ +#define GPIO_IDR_IDR2 ((uint16_t)0x0004) /*!< Port input data, bit 2 */ +#define GPIO_IDR_IDR3 ((uint16_t)0x0008) /*!< Port input data, bit 3 */ +#define GPIO_IDR_IDR4 ((uint16_t)0x0010) /*!< Port input data, bit 4 */ +#define GPIO_IDR_IDR5 ((uint16_t)0x0020) /*!< Port input data, bit 5 */ +#define GPIO_IDR_IDR6 ((uint16_t)0x0040) /*!< Port input data, bit 6 */ +#define GPIO_IDR_IDR7 ((uint16_t)0x0080) /*!< Port input data, bit 7 */ +#define GPIO_IDR_IDR8 ((uint16_t)0x0100) /*!< Port input data, bit 8 */ +#define GPIO_IDR_IDR9 ((uint16_t)0x0200) /*!< Port input data, bit 9 */ +#define GPIO_IDR_IDR10 ((uint16_t)0x0400) /*!< Port input data, bit 10 */ +#define GPIO_IDR_IDR11 ((uint16_t)0x0800) /*!< Port input data, bit 11 */ +#define GPIO_IDR_IDR12 ((uint16_t)0x1000) /*!< Port input data, bit 12 */ +#define GPIO_IDR_IDR13 ((uint16_t)0x2000) /*!< Port input data, bit 13 */ +#define GPIO_IDR_IDR14 ((uint16_t)0x4000) /*!< Port input data, bit 14 */ +#define GPIO_IDR_IDR15 ((uint16_t)0x8000) /*!< Port input data, bit 15 */ + +/******************* Bit definition for GPIO_ODR register *******************/ +#define GPIO_ODR_ODR0 ((uint16_t)0x0001) /*!< Port output data, bit 0 */ +#define GPIO_ODR_ODR1 ((uint16_t)0x0002) /*!< Port output data, bit 1 */ +#define GPIO_ODR_ODR2 ((uint16_t)0x0004) /*!< Port output data, bit 2 */ +#define GPIO_ODR_ODR3 ((uint16_t)0x0008) /*!< Port output data, bit 3 */ +#define GPIO_ODR_ODR4 ((uint16_t)0x0010) /*!< Port output data, bit 4 */ +#define GPIO_ODR_ODR5 ((uint16_t)0x0020) /*!< Port output data, bit 5 */ +#define GPIO_ODR_ODR6 ((uint16_t)0x0040) /*!< Port output data, bit 6 */ +#define GPIO_ODR_ODR7 ((uint16_t)0x0080) /*!< Port output data, bit 7 */ +#define GPIO_ODR_ODR8 ((uint16_t)0x0100) /*!< Port output data, bit 8 */ +#define GPIO_ODR_ODR9 ((uint16_t)0x0200) /*!< Port output data, bit 9 */ +#define GPIO_ODR_ODR10 ((uint16_t)0x0400) /*!< Port output data, bit 10 */ +#define GPIO_ODR_ODR11 ((uint16_t)0x0800) /*!< Port output data, bit 11 */ +#define GPIO_ODR_ODR12 ((uint16_t)0x1000) /*!< Port output data, bit 12 */ +#define GPIO_ODR_ODR13 ((uint16_t)0x2000) /*!< Port output data, bit 13 */ +#define GPIO_ODR_ODR14 ((uint16_t)0x4000) /*!< Port output data, bit 14 */ +#define GPIO_ODR_ODR15 ((uint16_t)0x8000) /*!< Port output data, bit 15 */ + +/****************** Bit definition for GPIO_BSRR register *******************/ +#define GPIO_BSRR_BS0 ((uint32_t)0x00000001) /*!< Port x Set bit 0 */ +#define GPIO_BSRR_BS1 ((uint32_t)0x00000002) /*!< Port x Set bit 1 */ +#define GPIO_BSRR_BS2 ((uint32_t)0x00000004) /*!< Port x Set bit 2 */ +#define GPIO_BSRR_BS3 ((uint32_t)0x00000008) /*!< Port x Set bit 3 */ +#define GPIO_BSRR_BS4 ((uint32_t)0x00000010) /*!< Port x Set bit 4 */ +#define GPIO_BSRR_BS5 ((uint32_t)0x00000020) /*!< Port x Set bit 5 */ +#define GPIO_BSRR_BS6 ((uint32_t)0x00000040) /*!< Port x Set bit 6 */ +#define GPIO_BSRR_BS7 ((uint32_t)0x00000080) /*!< Port x Set bit 7 */ +#define GPIO_BSRR_BS8 ((uint32_t)0x00000100) /*!< Port x Set bit 8 */ +#define GPIO_BSRR_BS9 ((uint32_t)0x00000200) /*!< Port x Set bit 9 */ +#define GPIO_BSRR_BS10 ((uint32_t)0x00000400) /*!< Port x Set bit 10 */ +#define GPIO_BSRR_BS11 ((uint32_t)0x00000800) /*!< Port x Set bit 11 */ +#define GPIO_BSRR_BS12 ((uint32_t)0x00001000) /*!< Port x Set bit 12 */ +#define GPIO_BSRR_BS13 ((uint32_t)0x00002000) /*!< Port x Set bit 13 */ +#define GPIO_BSRR_BS14 ((uint32_t)0x00004000) /*!< Port x Set bit 14 */ +#define GPIO_BSRR_BS15 ((uint32_t)0x00008000) /*!< Port x Set bit 15 */ + +#define GPIO_BSRR_BR0 ((uint32_t)0x00010000) /*!< Port x Reset bit 0 */ +#define GPIO_BSRR_BR1 ((uint32_t)0x00020000) /*!< Port x Reset bit 1 */ +#define GPIO_BSRR_BR2 ((uint32_t)0x00040000) /*!< Port x Reset bit 2 */ +#define GPIO_BSRR_BR3 ((uint32_t)0x00080000) /*!< Port x Reset bit 3 */ +#define GPIO_BSRR_BR4 ((uint32_t)0x00100000) /*!< Port x Reset bit 4 */ +#define GPIO_BSRR_BR5 ((uint32_t)0x00200000) /*!< Port x Reset bit 5 */ +#define GPIO_BSRR_BR6 ((uint32_t)0x00400000) /*!< Port x Reset bit 6 */ +#define GPIO_BSRR_BR7 ((uint32_t)0x00800000) /*!< Port x Reset bit 7 */ +#define GPIO_BSRR_BR8 ((uint32_t)0x01000000) /*!< Port x Reset bit 8 */ +#define GPIO_BSRR_BR9 ((uint32_t)0x02000000) /*!< Port x Reset bit 9 */ +#define GPIO_BSRR_BR10 ((uint32_t)0x04000000) /*!< Port x Reset bit 10 */ +#define GPIO_BSRR_BR11 ((uint32_t)0x08000000) /*!< Port x Reset bit 11 */ +#define GPIO_BSRR_BR12 ((uint32_t)0x10000000) /*!< Port x Reset bit 12 */ +#define GPIO_BSRR_BR13 ((uint32_t)0x20000000) /*!< Port x Reset bit 13 */ +#define GPIO_BSRR_BR14 ((uint32_t)0x40000000) /*!< Port x Reset bit 14 */ +#define GPIO_BSRR_BR15 ((uint32_t)0x80000000) /*!< Port x Reset bit 15 */ + +/******************* Bit definition for GPIO_BRR register *******************/ +#define GPIO_BRR_BR0 ((uint16_t)0x0001) /*!< Port x Reset bit 0 */ +#define GPIO_BRR_BR1 ((uint16_t)0x0002) /*!< Port x Reset bit 1 */ +#define GPIO_BRR_BR2 ((uint16_t)0x0004) /*!< Port x Reset bit 2 */ +#define GPIO_BRR_BR3 ((uint16_t)0x0008) /*!< Port x Reset bit 3 */ +#define GPIO_BRR_BR4 ((uint16_t)0x0010) /*!< Port x Reset bit 4 */ +#define GPIO_BRR_BR5 ((uint16_t)0x0020) /*!< Port x Reset bit 5 */ +#define GPIO_BRR_BR6 ((uint16_t)0x0040) /*!< Port x Reset bit 6 */ +#define GPIO_BRR_BR7 ((uint16_t)0x0080) /*!< Port x Reset bit 7 */ +#define GPIO_BRR_BR8 ((uint16_t)0x0100) /*!< Port x Reset bit 8 */ +#define GPIO_BRR_BR9 ((uint16_t)0x0200) /*!< Port x Reset bit 9 */ +#define GPIO_BRR_BR10 ((uint16_t)0x0400) /*!< Port x Reset bit 10 */ +#define GPIO_BRR_BR11 ((uint16_t)0x0800) /*!< Port x Reset bit 11 */ +#define GPIO_BRR_BR12 ((uint16_t)0x1000) /*!< Port x Reset bit 12 */ +#define GPIO_BRR_BR13 ((uint16_t)0x2000) /*!< Port x Reset bit 13 */ +#define GPIO_BRR_BR14 ((uint16_t)0x4000) /*!< Port x Reset bit 14 */ +#define GPIO_BRR_BR15 ((uint16_t)0x8000) /*!< Port x Reset bit 15 */ + +/****************** Bit definition for GPIO_LCKR register *******************/ +#define GPIO_LCKR_LCK0 ((uint32_t)0x00000001) /*!< Port x Lock bit 0 */ +#define GPIO_LCKR_LCK1 ((uint32_t)0x00000002) /*!< Port x Lock bit 1 */ +#define GPIO_LCKR_LCK2 ((uint32_t)0x00000004) /*!< Port x Lock bit 2 */ +#define GPIO_LCKR_LCK3 ((uint32_t)0x00000008) /*!< Port x Lock bit 3 */ +#define GPIO_LCKR_LCK4 ((uint32_t)0x00000010) /*!< Port x Lock bit 4 */ +#define GPIO_LCKR_LCK5 ((uint32_t)0x00000020) /*!< Port x Lock bit 5 */ +#define GPIO_LCKR_LCK6 ((uint32_t)0x00000040) /*!< Port x Lock bit 6 */ +#define GPIO_LCKR_LCK7 ((uint32_t)0x00000080) /*!< Port x Lock bit 7 */ +#define GPIO_LCKR_LCK8 ((uint32_t)0x00000100) /*!< Port x Lock bit 8 */ +#define GPIO_LCKR_LCK9 ((uint32_t)0x00000200) /*!< Port x Lock bit 9 */ +#define GPIO_LCKR_LCK10 ((uint32_t)0x00000400) /*!< Port x Lock bit 10 */ +#define GPIO_LCKR_LCK11 ((uint32_t)0x00000800) /*!< Port x Lock bit 11 */ +#define GPIO_LCKR_LCK12 ((uint32_t)0x00001000) /*!< Port x Lock bit 12 */ +#define GPIO_LCKR_LCK13 ((uint32_t)0x00002000) /*!< Port x Lock bit 13 */ +#define GPIO_LCKR_LCK14 ((uint32_t)0x00004000) /*!< Port x Lock bit 14 */ +#define GPIO_LCKR_LCK15 ((uint32_t)0x00008000) /*!< Port x Lock bit 15 */ +#define GPIO_LCKR_LCKK ((uint32_t)0x00010000) /*!< Lock key */ + +/*----------------------------------------------------------------------------*/ + +/****************** Bit definition for AFIO_EVCR register *******************/ +#define AFIO_EVCR_PIN ((uint8_t)0x0F) /*!< PIN[3:0] bits (Pin selection) */ +#define AFIO_EVCR_PIN_0 ((uint8_t)0x01) /*!< Bit 0 */ +#define AFIO_EVCR_PIN_1 ((uint8_t)0x02) /*!< Bit 1 */ +#define AFIO_EVCR_PIN_2 ((uint8_t)0x04) /*!< Bit 2 */ +#define AFIO_EVCR_PIN_3 ((uint8_t)0x08) /*!< Bit 3 */ + +/*!< PIN configuration */ +#define AFIO_EVCR_PIN_PX0 ((uint8_t)0x00) /*!< Pin 0 selected */ +#define AFIO_EVCR_PIN_PX1 ((uint8_t)0x01) /*!< Pin 1 selected */ +#define AFIO_EVCR_PIN_PX2 ((uint8_t)0x02) /*!< Pin 2 selected */ +#define AFIO_EVCR_PIN_PX3 ((uint8_t)0x03) /*!< Pin 3 selected */ +#define AFIO_EVCR_PIN_PX4 ((uint8_t)0x04) /*!< Pin 4 selected */ +#define AFIO_EVCR_PIN_PX5 ((uint8_t)0x05) /*!< Pin 5 selected */ +#define AFIO_EVCR_PIN_PX6 ((uint8_t)0x06) /*!< Pin 6 selected */ +#define AFIO_EVCR_PIN_PX7 ((uint8_t)0x07) /*!< Pin 7 selected */ +#define AFIO_EVCR_PIN_PX8 ((uint8_t)0x08) /*!< Pin 8 selected */ +#define AFIO_EVCR_PIN_PX9 ((uint8_t)0x09) /*!< Pin 9 selected */ +#define AFIO_EVCR_PIN_PX10 ((uint8_t)0x0A) /*!< Pin 10 selected */ +#define AFIO_EVCR_PIN_PX11 ((uint8_t)0x0B) /*!< Pin 11 selected */ +#define AFIO_EVCR_PIN_PX12 ((uint8_t)0x0C) /*!< Pin 12 selected */ +#define AFIO_EVCR_PIN_PX13 ((uint8_t)0x0D) /*!< Pin 13 selected */ +#define AFIO_EVCR_PIN_PX14 ((uint8_t)0x0E) /*!< Pin 14 selected */ +#define AFIO_EVCR_PIN_PX15 ((uint8_t)0x0F) /*!< Pin 15 selected */ + +#define AFIO_EVCR_PORT ((uint8_t)0x70) /*!< PORT[2:0] bits (Port selection) */ +#define AFIO_EVCR_PORT_0 ((uint8_t)0x10) /*!< Bit 0 */ +#define AFIO_EVCR_PORT_1 ((uint8_t)0x20) /*!< Bit 1 */ +#define AFIO_EVCR_PORT_2 ((uint8_t)0x40) /*!< Bit 2 */ + +/*!< PORT configuration */ +#define AFIO_EVCR_PORT_PA ((uint8_t)0x00) /*!< Port A selected */ +#define AFIO_EVCR_PORT_PB ((uint8_t)0x10) /*!< Port B selected */ +#define AFIO_EVCR_PORT_PC ((uint8_t)0x20) /*!< Port C selected */ +#define AFIO_EVCR_PORT_PD ((uint8_t)0x30) /*!< Port D selected */ +#define AFIO_EVCR_PORT_PE ((uint8_t)0x40) /*!< Port E selected */ + +#define AFIO_EVCR_EVOE ((uint8_t)0x80) /*!< Event Output Enable */ + +/****************** Bit definition for AFIO_MAPR register *******************/ +#define AFIO_MAPR_SPI1_REMAP ((uint32_t)0x00000001) /*!< SPI1 remapping */ +#define AFIO_MAPR_I2C1_REMAP ((uint32_t)0x00000002) /*!< I2C1 remapping */ +#define AFIO_MAPR_USART1_REMAP ((uint32_t)0x00000004) /*!< USART1 remapping */ +#define AFIO_MAPR_USART2_REMAP ((uint32_t)0x00000008) /*!< USART2 remapping */ + +#define AFIO_MAPR_USART3_REMAP ((uint32_t)0x00000030) /*!< USART3_REMAP[1:0] bits (USART3 remapping) */ +#define AFIO_MAPR_USART3_REMAP_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define AFIO_MAPR_USART3_REMAP_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +/* USART3_REMAP configuration */ +#define AFIO_MAPR_USART3_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (TX/PB10, RX/PB11, CK/PB12, CTS/PB13, RTS/PB14) */ +#define AFIO_MAPR_USART3_REMAP_PARTIALREMAP ((uint32_t)0x00000010) /*!< Partial remap (TX/PC10, RX/PC11, CK/PC12, CTS/PB13, RTS/PB14) */ +#define AFIO_MAPR_USART3_REMAP_FULLREMAP ((uint32_t)0x00000030) /*!< Full remap (TX/PD8, RX/PD9, CK/PD10, CTS/PD11, RTS/PD12) */ + +#define AFIO_MAPR_TIM1_REMAP ((uint32_t)0x000000C0) /*!< TIM1_REMAP[1:0] bits (TIM1 remapping) */ +#define AFIO_MAPR_TIM1_REMAP_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define AFIO_MAPR_TIM1_REMAP_1 ((uint32_t)0x00000080) /*!< Bit 1 */ + +/*!< TIM1_REMAP configuration */ +#define AFIO_MAPR_TIM1_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (ETR/PA12, CH1/PA8, CH2/PA9, CH3/PA10, CH4/PA11, BKIN/PB12, CH1N/PB13, CH2N/PB14, CH3N/PB15) */ +#define AFIO_MAPR_TIM1_REMAP_PARTIALREMAP ((uint32_t)0x00000040) /*!< Partial remap (ETR/PA12, CH1/PA8, CH2/PA9, CH3/PA10, CH4/PA11, BKIN/PA6, CH1N/PA7, CH2N/PB0, CH3N/PB1) */ +#define AFIO_MAPR_TIM1_REMAP_FULLREMAP ((uint32_t)0x000000C0) /*!< Full remap (ETR/PE7, CH1/PE9, CH2/PE11, CH3/PE13, CH4/PE14, BKIN/PE15, CH1N/PE8, CH2N/PE10, CH3N/PE12) */ + +#define AFIO_MAPR_TIM2_REMAP ((uint32_t)0x00000300) /*!< TIM2_REMAP[1:0] bits (TIM2 remapping) */ +#define AFIO_MAPR_TIM2_REMAP_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define AFIO_MAPR_TIM2_REMAP_1 ((uint32_t)0x00000200) /*!< Bit 1 */ + +/*!< TIM2_REMAP configuration */ +#define AFIO_MAPR_TIM2_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (CH1/ETR/PA0, CH2/PA1, CH3/PA2, CH4/PA3) */ +#define AFIO_MAPR_TIM2_REMAP_PARTIALREMAP1 ((uint32_t)0x00000100) /*!< Partial remap (CH1/ETR/PA15, CH2/PB3, CH3/PA2, CH4/PA3) */ +#define AFIO_MAPR_TIM2_REMAP_PARTIALREMAP2 ((uint32_t)0x00000200) /*!< Partial remap (CH1/ETR/PA0, CH2/PA1, CH3/PB10, CH4/PB11) */ +#define AFIO_MAPR_TIM2_REMAP_FULLREMAP ((uint32_t)0x00000300) /*!< Full remap (CH1/ETR/PA15, CH2/PB3, CH3/PB10, CH4/PB11) */ + +#define AFIO_MAPR_TIM3_REMAP ((uint32_t)0x00000C00) /*!< TIM3_REMAP[1:0] bits (TIM3 remapping) */ +#define AFIO_MAPR_TIM3_REMAP_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define AFIO_MAPR_TIM3_REMAP_1 ((uint32_t)0x00000800) /*!< Bit 1 */ + +/*!< TIM3_REMAP configuration */ +#define AFIO_MAPR_TIM3_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (CH1/PA6, CH2/PA7, CH3/PB0, CH4/PB1) */ +#define AFIO_MAPR_TIM3_REMAP_PARTIALREMAP ((uint32_t)0x00000800) /*!< Partial remap (CH1/PB4, CH2/PB5, CH3/PB0, CH4/PB1) */ +#define AFIO_MAPR_TIM3_REMAP_FULLREMAP ((uint32_t)0x00000C00) /*!< Full remap (CH1/PC6, CH2/PC7, CH3/PC8, CH4/PC9) */ + +#define AFIO_MAPR_TIM4_REMAP ((uint32_t)0x00001000) /*!< TIM4_REMAP bit (TIM4 remapping) */ + +#define AFIO_MAPR_CAN_REMAP ((uint32_t)0x00006000) /*!< CAN_REMAP[1:0] bits (CAN Alternate function remapping) */ +#define AFIO_MAPR_CAN_REMAP_0 ((uint32_t)0x00002000) /*!< Bit 0 */ +#define AFIO_MAPR_CAN_REMAP_1 ((uint32_t)0x00004000) /*!< Bit 1 */ + +/*!< CAN_REMAP configuration */ +#define AFIO_MAPR_CAN_REMAP_REMAP1 ((uint32_t)0x00000000) /*!< CANRX mapped to PA11, CANTX mapped to PA12 */ +#define AFIO_MAPR_CAN_REMAP_REMAP2 ((uint32_t)0x00004000) /*!< CANRX mapped to PB8, CANTX mapped to PB9 */ +#define AFIO_MAPR_CAN_REMAP_REMAP3 ((uint32_t)0x00006000) /*!< CANRX mapped to PD0, CANTX mapped to PD1 */ + +#define AFIO_MAPR_PD01_REMAP ((uint32_t)0x00008000) /*!< Port D0/Port D1 mapping on OSC_IN/OSC_OUT */ +#define AFIO_MAPR_TIM5CH4_IREMAP ((uint32_t)0x00010000) /*!< TIM5 Channel4 Internal Remap */ +#define AFIO_MAPR_ADC1_ETRGINJ_REMAP ((uint32_t)0x00020000) /*!< ADC 1 External Trigger Injected Conversion remapping */ +#define AFIO_MAPR_ADC1_ETRGREG_REMAP ((uint32_t)0x00040000) /*!< ADC 1 External Trigger Regular Conversion remapping */ +#define AFIO_MAPR_ADC2_ETRGINJ_REMAP ((uint32_t)0x00080000) /*!< ADC 2 External Trigger Injected Conversion remapping */ +#define AFIO_MAPR_ADC2_ETRGREG_REMAP ((uint32_t)0x00100000) /*!< ADC 2 External Trigger Regular Conversion remapping */ + +/*!< SWJ_CFG configuration */ +#define AFIO_MAPR_SWJ_CFG ((uint32_t)0x07000000) /*!< SWJ_CFG[2:0] bits (Serial Wire JTAG configuration) */ +#define AFIO_MAPR_SWJ_CFG_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define AFIO_MAPR_SWJ_CFG_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define AFIO_MAPR_SWJ_CFG_2 ((uint32_t)0x04000000) /*!< Bit 2 */ + +#define AFIO_MAPR_SWJ_CFG_RESET ((uint32_t)0x00000000) /*!< Full SWJ (JTAG-DP + SW-DP) : Reset State */ +#define AFIO_MAPR_SWJ_CFG_NOJNTRST ((uint32_t)0x01000000) /*!< Full SWJ (JTAG-DP + SW-DP) but without JNTRST */ +#define AFIO_MAPR_SWJ_CFG_JTAGDISABLE ((uint32_t)0x02000000) /*!< JTAG-DP Disabled and SW-DP Enabled */ +#define AFIO_MAPR_SWJ_CFG_DISABLE ((uint32_t)0x04000000) /*!< JTAG-DP Disabled and SW-DP Disabled */ + +#ifdef STM32F10X_CL +/*!< ETH_REMAP configuration */ + #define AFIO_MAPR_ETH_REMAP ((uint32_t)0x00200000) /*!< SPI3_REMAP bit (Ethernet MAC I/O remapping) */ + +/*!< CAN2_REMAP configuration */ + #define AFIO_MAPR_CAN2_REMAP ((uint32_t)0x00400000) /*!< CAN2_REMAP bit (CAN2 I/O remapping) */ + +/*!< MII_RMII_SEL configuration */ + #define AFIO_MAPR_MII_RMII_SEL ((uint32_t)0x00800000) /*!< MII_RMII_SEL bit (Ethernet MII or RMII selection) */ + +/*!< SPI3_REMAP configuration */ + #define AFIO_MAPR_SPI3_REMAP ((uint32_t)0x10000000) /*!< SPI3_REMAP bit (SPI3 remapping) */ + +/*!< TIM2ITR1_IREMAP configuration */ + #define AFIO_MAPR_TIM2ITR1_IREMAP ((uint32_t)0x20000000) /*!< TIM2ITR1_IREMAP bit (TIM2 internal trigger 1 remapping) */ + +/*!< PTP_PPS_REMAP configuration */ + #define AFIO_MAPR_PTP_PPS_REMAP ((uint32_t)0x40000000) /*!< PTP_PPS_REMAP bit (Ethernet PTP PPS remapping) */ +#endif + +/***************** Bit definition for AFIO_EXTICR1 register *****************/ +#define AFIO_EXTICR1_EXTI0 ((uint16_t)0x000F) /*!< EXTI 0 configuration */ +#define AFIO_EXTICR1_EXTI1 ((uint16_t)0x00F0) /*!< EXTI 1 configuration */ +#define AFIO_EXTICR1_EXTI2 ((uint16_t)0x0F00) /*!< EXTI 2 configuration */ +#define AFIO_EXTICR1_EXTI3 ((uint16_t)0xF000) /*!< EXTI 3 configuration */ + +/*!< EXTI0 configuration */ +#define AFIO_EXTICR1_EXTI0_PA ((uint16_t)0x0000) /*!< PA[0] pin */ +#define AFIO_EXTICR1_EXTI0_PB ((uint16_t)0x0001) /*!< PB[0] pin */ +#define AFIO_EXTICR1_EXTI0_PC ((uint16_t)0x0002) /*!< PC[0] pin */ +#define AFIO_EXTICR1_EXTI0_PD ((uint16_t)0x0003) /*!< PD[0] pin */ +#define AFIO_EXTICR1_EXTI0_PE ((uint16_t)0x0004) /*!< PE[0] pin */ +#define AFIO_EXTICR1_EXTI0_PF ((uint16_t)0x0005) /*!< PF[0] pin */ +#define AFIO_EXTICR1_EXTI0_PG ((uint16_t)0x0006) /*!< PG[0] pin */ + +/*!< EXTI1 configuration */ +#define AFIO_EXTICR1_EXTI1_PA ((uint16_t)0x0000) /*!< PA[1] pin */ +#define AFIO_EXTICR1_EXTI1_PB ((uint16_t)0x0010) /*!< PB[1] pin */ +#define AFIO_EXTICR1_EXTI1_PC ((uint16_t)0x0020) /*!< PC[1] pin */ +#define AFIO_EXTICR1_EXTI1_PD ((uint16_t)0x0030) /*!< PD[1] pin */ +#define AFIO_EXTICR1_EXTI1_PE ((uint16_t)0x0040) /*!< PE[1] pin */ +#define AFIO_EXTICR1_EXTI1_PF ((uint16_t)0x0050) /*!< PF[1] pin */ +#define AFIO_EXTICR1_EXTI1_PG ((uint16_t)0x0060) /*!< PG[1] pin */ + +/*!< EXTI2 configuration */ +#define AFIO_EXTICR1_EXTI2_PA ((uint16_t)0x0000) /*!< PA[2] pin */ +#define AFIO_EXTICR1_EXTI2_PB ((uint16_t)0x0100) /*!< PB[2] pin */ +#define AFIO_EXTICR1_EXTI2_PC ((uint16_t)0x0200) /*!< PC[2] pin */ +#define AFIO_EXTICR1_EXTI2_PD ((uint16_t)0x0300) /*!< PD[2] pin */ +#define AFIO_EXTICR1_EXTI2_PE ((uint16_t)0x0400) /*!< PE[2] pin */ +#define AFIO_EXTICR1_EXTI2_PF ((uint16_t)0x0500) /*!< PF[2] pin */ +#define AFIO_EXTICR1_EXTI2_PG ((uint16_t)0x0600) /*!< PG[2] pin */ + +/*!< EXTI3 configuration */ +#define AFIO_EXTICR1_EXTI3_PA ((uint16_t)0x0000) /*!< PA[3] pin */ +#define AFIO_EXTICR1_EXTI3_PB ((uint16_t)0x1000) /*!< PB[3] pin */ +#define AFIO_EXTICR1_EXTI3_PC ((uint16_t)0x2000) /*!< PC[3] pin */ +#define AFIO_EXTICR1_EXTI3_PD ((uint16_t)0x3000) /*!< PD[3] pin */ +#define AFIO_EXTICR1_EXTI3_PE ((uint16_t)0x4000) /*!< PE[3] pin */ +#define AFIO_EXTICR1_EXTI3_PF ((uint16_t)0x5000) /*!< PF[3] pin */ +#define AFIO_EXTICR1_EXTI3_PG ((uint16_t)0x6000) /*!< PG[3] pin */ + +/***************** Bit definition for AFIO_EXTICR2 register *****************/ +#define AFIO_EXTICR2_EXTI4 ((uint16_t)0x000F) /*!< EXTI 4 configuration */ +#define AFIO_EXTICR2_EXTI5 ((uint16_t)0x00F0) /*!< EXTI 5 configuration */ +#define AFIO_EXTICR2_EXTI6 ((uint16_t)0x0F00) /*!< EXTI 6 configuration */ +#define AFIO_EXTICR2_EXTI7 ((uint16_t)0xF000) /*!< EXTI 7 configuration */ + +/*!< EXTI4 configuration */ +#define AFIO_EXTICR2_EXTI4_PA ((uint16_t)0x0000) /*!< PA[4] pin */ +#define AFIO_EXTICR2_EXTI4_PB ((uint16_t)0x0001) /*!< PB[4] pin */ +#define AFIO_EXTICR2_EXTI4_PC ((uint16_t)0x0002) /*!< PC[4] pin */ +#define AFIO_EXTICR2_EXTI4_PD ((uint16_t)0x0003) /*!< PD[4] pin */ +#define AFIO_EXTICR2_EXTI4_PE ((uint16_t)0x0004) /*!< PE[4] pin */ +#define AFIO_EXTICR2_EXTI4_PF ((uint16_t)0x0005) /*!< PF[4] pin */ +#define AFIO_EXTICR2_EXTI4_PG ((uint16_t)0x0006) /*!< PG[4] pin */ + +/* EXTI5 configuration */ +#define AFIO_EXTICR2_EXTI5_PA ((uint16_t)0x0000) /*!< PA[5] pin */ +#define AFIO_EXTICR2_EXTI5_PB ((uint16_t)0x0010) /*!< PB[5] pin */ +#define AFIO_EXTICR2_EXTI5_PC ((uint16_t)0x0020) /*!< PC[5] pin */ +#define AFIO_EXTICR2_EXTI5_PD ((uint16_t)0x0030) /*!< PD[5] pin */ +#define AFIO_EXTICR2_EXTI5_PE ((uint16_t)0x0040) /*!< PE[5] pin */ +#define AFIO_EXTICR2_EXTI5_PF ((uint16_t)0x0050) /*!< PF[5] pin */ +#define AFIO_EXTICR2_EXTI5_PG ((uint16_t)0x0060) /*!< PG[5] pin */ + +/*!< EXTI6 configuration */ +#define AFIO_EXTICR2_EXTI6_PA ((uint16_t)0x0000) /*!< PA[6] pin */ +#define AFIO_EXTICR2_EXTI6_PB ((uint16_t)0x0100) /*!< PB[6] pin */ +#define AFIO_EXTICR2_EXTI6_PC ((uint16_t)0x0200) /*!< PC[6] pin */ +#define AFIO_EXTICR2_EXTI6_PD ((uint16_t)0x0300) /*!< PD[6] pin */ +#define AFIO_EXTICR2_EXTI6_PE ((uint16_t)0x0400) /*!< PE[6] pin */ +#define AFIO_EXTICR2_EXTI6_PF ((uint16_t)0x0500) /*!< PF[6] pin */ +#define AFIO_EXTICR2_EXTI6_PG ((uint16_t)0x0600) /*!< PG[6] pin */ + +/*!< EXTI7 configuration */ +#define AFIO_EXTICR2_EXTI7_PA ((uint16_t)0x0000) /*!< PA[7] pin */ +#define AFIO_EXTICR2_EXTI7_PB ((uint16_t)0x1000) /*!< PB[7] pin */ +#define AFIO_EXTICR2_EXTI7_PC ((uint16_t)0x2000) /*!< PC[7] pin */ +#define AFIO_EXTICR2_EXTI7_PD ((uint16_t)0x3000) /*!< PD[7] pin */ +#define AFIO_EXTICR2_EXTI7_PE ((uint16_t)0x4000) /*!< PE[7] pin */ +#define AFIO_EXTICR2_EXTI7_PF ((uint16_t)0x5000) /*!< PF[7] pin */ +#define AFIO_EXTICR2_EXTI7_PG ((uint16_t)0x6000) /*!< PG[7] pin */ + +/***************** Bit definition for AFIO_EXTICR3 register *****************/ +#define AFIO_EXTICR3_EXTI8 ((uint16_t)0x000F) /*!< EXTI 8 configuration */ +#define AFIO_EXTICR3_EXTI9 ((uint16_t)0x00F0) /*!< EXTI 9 configuration */ +#define AFIO_EXTICR3_EXTI10 ((uint16_t)0x0F00) /*!< EXTI 10 configuration */ +#define AFIO_EXTICR3_EXTI11 ((uint16_t)0xF000) /*!< EXTI 11 configuration */ + +/*!< EXTI8 configuration */ +#define AFIO_EXTICR3_EXTI8_PA ((uint16_t)0x0000) /*!< PA[8] pin */ +#define AFIO_EXTICR3_EXTI8_PB ((uint16_t)0x0001) /*!< PB[8] pin */ +#define AFIO_EXTICR3_EXTI8_PC ((uint16_t)0x0002) /*!< PC[8] pin */ +#define AFIO_EXTICR3_EXTI8_PD ((uint16_t)0x0003) /*!< PD[8] pin */ +#define AFIO_EXTICR3_EXTI8_PE ((uint16_t)0x0004) /*!< PE[8] pin */ +#define AFIO_EXTICR3_EXTI8_PF ((uint16_t)0x0005) /*!< PF[8] pin */ +#define AFIO_EXTICR3_EXTI8_PG ((uint16_t)0x0006) /*!< PG[8] pin */ + +/*!< EXTI9 configuration */ +#define AFIO_EXTICR3_EXTI9_PA ((uint16_t)0x0000) /*!< PA[9] pin */ +#define AFIO_EXTICR3_EXTI9_PB ((uint16_t)0x0010) /*!< PB[9] pin */ +#define AFIO_EXTICR3_EXTI9_PC ((uint16_t)0x0020) /*!< PC[9] pin */ +#define AFIO_EXTICR3_EXTI9_PD ((uint16_t)0x0030) /*!< PD[9] pin */ +#define AFIO_EXTICR3_EXTI9_PE ((uint16_t)0x0040) /*!< PE[9] pin */ +#define AFIO_EXTICR3_EXTI9_PF ((uint16_t)0x0050) /*!< PF[9] pin */ +#define AFIO_EXTICR3_EXTI9_PG ((uint16_t)0x0060) /*!< PG[9] pin */ + +/*!< EXTI10 configuration */ +#define AFIO_EXTICR3_EXTI10_PA ((uint16_t)0x0000) /*!< PA[10] pin */ +#define AFIO_EXTICR3_EXTI10_PB ((uint16_t)0x0100) /*!< PB[10] pin */ +#define AFIO_EXTICR3_EXTI10_PC ((uint16_t)0x0200) /*!< PC[10] pin */ +#define AFIO_EXTICR3_EXTI10_PD ((uint16_t)0x0300) /*!< PD[10] pin */ +#define AFIO_EXTICR3_EXTI10_PE ((uint16_t)0x0400) /*!< PE[10] pin */ +#define AFIO_EXTICR3_EXTI10_PF ((uint16_t)0x0500) /*!< PF[10] pin */ +#define AFIO_EXTICR3_EXTI10_PG ((uint16_t)0x0600) /*!< PG[10] pin */ + +/*!< EXTI11 configuration */ +#define AFIO_EXTICR3_EXTI11_PA ((uint16_t)0x0000) /*!< PA[11] pin */ +#define AFIO_EXTICR3_EXTI11_PB ((uint16_t)0x1000) /*!< PB[11] pin */ +#define AFIO_EXTICR3_EXTI11_PC ((uint16_t)0x2000) /*!< PC[11] pin */ +#define AFIO_EXTICR3_EXTI11_PD ((uint16_t)0x3000) /*!< PD[11] pin */ +#define AFIO_EXTICR3_EXTI11_PE ((uint16_t)0x4000) /*!< PE[11] pin */ +#define AFIO_EXTICR3_EXTI11_PF ((uint16_t)0x5000) /*!< PF[11] pin */ +#define AFIO_EXTICR3_EXTI11_PG ((uint16_t)0x6000) /*!< PG[11] pin */ + +/***************** Bit definition for AFIO_EXTICR4 register *****************/ +#define AFIO_EXTICR4_EXTI12 ((uint16_t)0x000F) /*!< EXTI 12 configuration */ +#define AFIO_EXTICR4_EXTI13 ((uint16_t)0x00F0) /*!< EXTI 13 configuration */ +#define AFIO_EXTICR4_EXTI14 ((uint16_t)0x0F00) /*!< EXTI 14 configuration */ +#define AFIO_EXTICR4_EXTI15 ((uint16_t)0xF000) /*!< EXTI 15 configuration */ + +/* EXTI12 configuration */ +#define AFIO_EXTICR4_EXTI12_PA ((uint16_t)0x0000) /*!< PA[12] pin */ +#define AFIO_EXTICR4_EXTI12_PB ((uint16_t)0x0001) /*!< PB[12] pin */ +#define AFIO_EXTICR4_EXTI12_PC ((uint16_t)0x0002) /*!< PC[12] pin */ +#define AFIO_EXTICR4_EXTI12_PD ((uint16_t)0x0003) /*!< PD[12] pin */ +#define AFIO_EXTICR4_EXTI12_PE ((uint16_t)0x0004) /*!< PE[12] pin */ +#define AFIO_EXTICR4_EXTI12_PF ((uint16_t)0x0005) /*!< PF[12] pin */ +#define AFIO_EXTICR4_EXTI12_PG ((uint16_t)0x0006) /*!< PG[12] pin */ + +/* EXTI13 configuration */ +#define AFIO_EXTICR4_EXTI13_PA ((uint16_t)0x0000) /*!< PA[13] pin */ +#define AFIO_EXTICR4_EXTI13_PB ((uint16_t)0x0010) /*!< PB[13] pin */ +#define AFIO_EXTICR4_EXTI13_PC ((uint16_t)0x0020) /*!< PC[13] pin */ +#define AFIO_EXTICR4_EXTI13_PD ((uint16_t)0x0030) /*!< PD[13] pin */ +#define AFIO_EXTICR4_EXTI13_PE ((uint16_t)0x0040) /*!< PE[13] pin */ +#define AFIO_EXTICR4_EXTI13_PF ((uint16_t)0x0050) /*!< PF[13] pin */ +#define AFIO_EXTICR4_EXTI13_PG ((uint16_t)0x0060) /*!< PG[13] pin */ + +/*!< EXTI14 configuration */ +#define AFIO_EXTICR4_EXTI14_PA ((uint16_t)0x0000) /*!< PA[14] pin */ +#define AFIO_EXTICR4_EXTI14_PB ((uint16_t)0x0100) /*!< PB[14] pin */ +#define AFIO_EXTICR4_EXTI14_PC ((uint16_t)0x0200) /*!< PC[14] pin */ +#define AFIO_EXTICR4_EXTI14_PD ((uint16_t)0x0300) /*!< PD[14] pin */ +#define AFIO_EXTICR4_EXTI14_PE ((uint16_t)0x0400) /*!< PE[14] pin */ +#define AFIO_EXTICR4_EXTI14_PF ((uint16_t)0x0500) /*!< PF[14] pin */ +#define AFIO_EXTICR4_EXTI14_PG ((uint16_t)0x0600) /*!< PG[14] pin */ + +/*!< EXTI15 configuration */ +#define AFIO_EXTICR4_EXTI15_PA ((uint16_t)0x0000) /*!< PA[15] pin */ +#define AFIO_EXTICR4_EXTI15_PB ((uint16_t)0x1000) /*!< PB[15] pin */ +#define AFIO_EXTICR4_EXTI15_PC ((uint16_t)0x2000) /*!< PC[15] pin */ +#define AFIO_EXTICR4_EXTI15_PD ((uint16_t)0x3000) /*!< PD[15] pin */ +#define AFIO_EXTICR4_EXTI15_PE ((uint16_t)0x4000) /*!< PE[15] pin */ +#define AFIO_EXTICR4_EXTI15_PF ((uint16_t)0x5000) /*!< PF[15] pin */ +#define AFIO_EXTICR4_EXTI15_PG ((uint16_t)0x6000) /*!< PG[15] pin */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/****************** Bit definition for AFIO_MAPR2 register ******************/ +#define AFIO_MAPR2_TIM15_REMAP ((uint32_t)0x00000001) /*!< TIM15 remapping */ +#define AFIO_MAPR2_TIM16_REMAP ((uint32_t)0x00000002) /*!< TIM16 remapping */ +#define AFIO_MAPR2_TIM17_REMAP ((uint32_t)0x00000004) /*!< TIM17 remapping */ +#define AFIO_MAPR2_CEC_REMAP ((uint32_t)0x00000008) /*!< CEC remapping */ +#define AFIO_MAPR2_TIM1_DMA_REMAP ((uint32_t)0x00000010) /*!< TIM1_DMA remapping */ +#endif + +#ifdef STM32F10X_HD_VL +#define AFIO_MAPR2_TIM13_REMAP ((uint32_t)0x00000100) /*!< TIM13 remapping */ +#define AFIO_MAPR2_TIM14_REMAP ((uint32_t)0x00000200) /*!< TIM14 remapping */ +#define AFIO_MAPR2_FSMC_NADV_REMAP ((uint32_t)0x00000400) /*!< FSMC NADV remapping */ +#define AFIO_MAPR2_TIM67_DAC_DMA_REMAP ((uint32_t)0x00000800) /*!< TIM6/TIM7 and DAC DMA remapping */ +#define AFIO_MAPR2_TIM12_REMAP ((uint32_t)0x00001000) /*!< TIM12 remapping */ +#define AFIO_MAPR2_MISC_REMAP ((uint32_t)0x00002000) /*!< Miscellaneous remapping */ +#endif + +#ifdef STM32F10X_XL +/****************** Bit definition for AFIO_MAPR2 register ******************/ +#define AFIO_MAPR2_TIM9_REMAP ((uint32_t)0x00000020) /*!< TIM9 remapping */ +#define AFIO_MAPR2_TIM10_REMAP ((uint32_t)0x00000040) /*!< TIM10 remapping */ +#define AFIO_MAPR2_TIM11_REMAP ((uint32_t)0x00000080) /*!< TIM11 remapping */ +#define AFIO_MAPR2_TIM13_REMAP ((uint32_t)0x00000100) /*!< TIM13 remapping */ +#define AFIO_MAPR2_TIM14_REMAP ((uint32_t)0x00000200) /*!< TIM14 remapping */ +#define AFIO_MAPR2_FSMC_NADV_REMAP ((uint32_t)0x00000400) /*!< FSMC NADV remapping */ +#endif + +/******************************************************************************/ +/* */ +/* SystemTick */ +/* */ +/******************************************************************************/ + +/***************** Bit definition for SysTick_CTRL register *****************/ +#define SysTick_CTRL_ENABLE ((uint32_t)0x00000001) /*!< Counter enable */ +#define SysTick_CTRL_TICKINT ((uint32_t)0x00000002) /*!< Counting down to 0 pends the SysTick handler */ +#define SysTick_CTRL_CLKSOURCE ((uint32_t)0x00000004) /*!< Clock source */ +#define SysTick_CTRL_COUNTFLAG ((uint32_t)0x00010000) /*!< Count Flag */ + +/***************** Bit definition for SysTick_LOAD register *****************/ +#define SysTick_LOAD_RELOAD ((uint32_t)0x00FFFFFF) /*!< Value to load into the SysTick Current Value Register when the counter reaches 0 */ + +/***************** Bit definition for SysTick_VAL register ******************/ +#define SysTick_VAL_CURRENT ((uint32_t)0x00FFFFFF) /*!< Current value at the time the register is accessed */ + +/***************** Bit definition for SysTick_CALIB register ****************/ +#define SysTick_CALIB_TENMS ((uint32_t)0x00FFFFFF) /*!< Reload value to use for 10ms timing */ +#define SysTick_CALIB_SKEW ((uint32_t)0x40000000) /*!< Calibration value is not exactly 10 ms */ +#define SysTick_CALIB_NOREF ((uint32_t)0x80000000) /*!< The reference clock is not provided */ + +/******************************************************************************/ +/* */ +/* Nested Vectored Interrupt Controller */ +/* */ +/******************************************************************************/ + +/****************** Bit definition for NVIC_ISER register *******************/ +#define NVIC_ISER_SETENA ((uint32_t)0xFFFFFFFF) /*!< Interrupt set enable bits */ +#define NVIC_ISER_SETENA_0 ((uint32_t)0x00000001) /*!< bit 0 */ +#define NVIC_ISER_SETENA_1 ((uint32_t)0x00000002) /*!< bit 1 */ +#define NVIC_ISER_SETENA_2 ((uint32_t)0x00000004) /*!< bit 2 */ +#define NVIC_ISER_SETENA_3 ((uint32_t)0x00000008) /*!< bit 3 */ +#define NVIC_ISER_SETENA_4 ((uint32_t)0x00000010) /*!< bit 4 */ +#define NVIC_ISER_SETENA_5 ((uint32_t)0x00000020) /*!< bit 5 */ +#define NVIC_ISER_SETENA_6 ((uint32_t)0x00000040) /*!< bit 6 */ +#define NVIC_ISER_SETENA_7 ((uint32_t)0x00000080) /*!< bit 7 */ +#define NVIC_ISER_SETENA_8 ((uint32_t)0x00000100) /*!< bit 8 */ +#define NVIC_ISER_SETENA_9 ((uint32_t)0x00000200) /*!< bit 9 */ +#define NVIC_ISER_SETENA_10 ((uint32_t)0x00000400) /*!< bit 10 */ +#define NVIC_ISER_SETENA_11 ((uint32_t)0x00000800) /*!< bit 11 */ +#define NVIC_ISER_SETENA_12 ((uint32_t)0x00001000) /*!< bit 12 */ +#define NVIC_ISER_SETENA_13 ((uint32_t)0x00002000) /*!< bit 13 */ +#define NVIC_ISER_SETENA_14 ((uint32_t)0x00004000) /*!< bit 14 */ +#define NVIC_ISER_SETENA_15 ((uint32_t)0x00008000) /*!< bit 15 */ +#define NVIC_ISER_SETENA_16 ((uint32_t)0x00010000) /*!< bit 16 */ +#define NVIC_ISER_SETENA_17 ((uint32_t)0x00020000) /*!< bit 17 */ +#define NVIC_ISER_SETENA_18 ((uint32_t)0x00040000) /*!< bit 18 */ +#define NVIC_ISER_SETENA_19 ((uint32_t)0x00080000) /*!< bit 19 */ +#define NVIC_ISER_SETENA_20 ((uint32_t)0x00100000) /*!< bit 20 */ +#define NVIC_ISER_SETENA_21 ((uint32_t)0x00200000) /*!< bit 21 */ +#define NVIC_ISER_SETENA_22 ((uint32_t)0x00400000) /*!< bit 22 */ +#define NVIC_ISER_SETENA_23 ((uint32_t)0x00800000) /*!< bit 23 */ +#define NVIC_ISER_SETENA_24 ((uint32_t)0x01000000) /*!< bit 24 */ +#define NVIC_ISER_SETENA_25 ((uint32_t)0x02000000) /*!< bit 25 */ +#define NVIC_ISER_SETENA_26 ((uint32_t)0x04000000) /*!< bit 26 */ +#define NVIC_ISER_SETENA_27 ((uint32_t)0x08000000) /*!< bit 27 */ +#define NVIC_ISER_SETENA_28 ((uint32_t)0x10000000) /*!< bit 28 */ +#define NVIC_ISER_SETENA_29 ((uint32_t)0x20000000) /*!< bit 29 */ +#define NVIC_ISER_SETENA_30 ((uint32_t)0x40000000) /*!< bit 30 */ +#define NVIC_ISER_SETENA_31 ((uint32_t)0x80000000) /*!< bit 31 */ + +/****************** Bit definition for NVIC_ICER register *******************/ +#define NVIC_ICER_CLRENA ((uint32_t)0xFFFFFFFF) /*!< Interrupt clear-enable bits */ +#define NVIC_ICER_CLRENA_0 ((uint32_t)0x00000001) /*!< bit 0 */ +#define NVIC_ICER_CLRENA_1 ((uint32_t)0x00000002) /*!< bit 1 */ +#define NVIC_ICER_CLRENA_2 ((uint32_t)0x00000004) /*!< bit 2 */ +#define NVIC_ICER_CLRENA_3 ((uint32_t)0x00000008) /*!< bit 3 */ +#define NVIC_ICER_CLRENA_4 ((uint32_t)0x00000010) /*!< bit 4 */ +#define NVIC_ICER_CLRENA_5 ((uint32_t)0x00000020) /*!< bit 5 */ +#define NVIC_ICER_CLRENA_6 ((uint32_t)0x00000040) /*!< bit 6 */ +#define NVIC_ICER_CLRENA_7 ((uint32_t)0x00000080) /*!< bit 7 */ +#define NVIC_ICER_CLRENA_8 ((uint32_t)0x00000100) /*!< bit 8 */ +#define NVIC_ICER_CLRENA_9 ((uint32_t)0x00000200) /*!< bit 9 */ +#define NVIC_ICER_CLRENA_10 ((uint32_t)0x00000400) /*!< bit 10 */ +#define NVIC_ICER_CLRENA_11 ((uint32_t)0x00000800) /*!< bit 11 */ +#define NVIC_ICER_CLRENA_12 ((uint32_t)0x00001000) /*!< bit 12 */ +#define NVIC_ICER_CLRENA_13 ((uint32_t)0x00002000) /*!< bit 13 */ +#define NVIC_ICER_CLRENA_14 ((uint32_t)0x00004000) /*!< bit 14 */ +#define NVIC_ICER_CLRENA_15 ((uint32_t)0x00008000) /*!< bit 15 */ +#define NVIC_ICER_CLRENA_16 ((uint32_t)0x00010000) /*!< bit 16 */ +#define NVIC_ICER_CLRENA_17 ((uint32_t)0x00020000) /*!< bit 17 */ +#define NVIC_ICER_CLRENA_18 ((uint32_t)0x00040000) /*!< bit 18 */ +#define NVIC_ICER_CLRENA_19 ((uint32_t)0x00080000) /*!< bit 19 */ +#define NVIC_ICER_CLRENA_20 ((uint32_t)0x00100000) /*!< bit 20 */ +#define NVIC_ICER_CLRENA_21 ((uint32_t)0x00200000) /*!< bit 21 */ +#define NVIC_ICER_CLRENA_22 ((uint32_t)0x00400000) /*!< bit 22 */ +#define NVIC_ICER_CLRENA_23 ((uint32_t)0x00800000) /*!< bit 23 */ +#define NVIC_ICER_CLRENA_24 ((uint32_t)0x01000000) /*!< bit 24 */ +#define NVIC_ICER_CLRENA_25 ((uint32_t)0x02000000) /*!< bit 25 */ +#define NVIC_ICER_CLRENA_26 ((uint32_t)0x04000000) /*!< bit 26 */ +#define NVIC_ICER_CLRENA_27 ((uint32_t)0x08000000) /*!< bit 27 */ +#define NVIC_ICER_CLRENA_28 ((uint32_t)0x10000000) /*!< bit 28 */ +#define NVIC_ICER_CLRENA_29 ((uint32_t)0x20000000) /*!< bit 29 */ +#define NVIC_ICER_CLRENA_30 ((uint32_t)0x40000000) /*!< bit 30 */ +#define NVIC_ICER_CLRENA_31 ((uint32_t)0x80000000) /*!< bit 31 */ + +/****************** Bit definition for NVIC_ISPR register *******************/ +#define NVIC_ISPR_SETPEND ((uint32_t)0xFFFFFFFF) /*!< Interrupt set-pending bits */ +#define NVIC_ISPR_SETPEND_0 ((uint32_t)0x00000001) /*!< bit 0 */ +#define NVIC_ISPR_SETPEND_1 ((uint32_t)0x00000002) /*!< bit 1 */ +#define NVIC_ISPR_SETPEND_2 ((uint32_t)0x00000004) /*!< bit 2 */ +#define NVIC_ISPR_SETPEND_3 ((uint32_t)0x00000008) /*!< bit 3 */ +#define NVIC_ISPR_SETPEND_4 ((uint32_t)0x00000010) /*!< bit 4 */ +#define NVIC_ISPR_SETPEND_5 ((uint32_t)0x00000020) /*!< bit 5 */ +#define NVIC_ISPR_SETPEND_6 ((uint32_t)0x00000040) /*!< bit 6 */ +#define NVIC_ISPR_SETPEND_7 ((uint32_t)0x00000080) /*!< bit 7 */ +#define NVIC_ISPR_SETPEND_8 ((uint32_t)0x00000100) /*!< bit 8 */ +#define NVIC_ISPR_SETPEND_9 ((uint32_t)0x00000200) /*!< bit 9 */ +#define NVIC_ISPR_SETPEND_10 ((uint32_t)0x00000400) /*!< bit 10 */ +#define NVIC_ISPR_SETPEND_11 ((uint32_t)0x00000800) /*!< bit 11 */ +#define NVIC_ISPR_SETPEND_12 ((uint32_t)0x00001000) /*!< bit 12 */ +#define NVIC_ISPR_SETPEND_13 ((uint32_t)0x00002000) /*!< bit 13 */ +#define NVIC_ISPR_SETPEND_14 ((uint32_t)0x00004000) /*!< bit 14 */ +#define NVIC_ISPR_SETPEND_15 ((uint32_t)0x00008000) /*!< bit 15 */ +#define NVIC_ISPR_SETPEND_16 ((uint32_t)0x00010000) /*!< bit 16 */ +#define NVIC_ISPR_SETPEND_17 ((uint32_t)0x00020000) /*!< bit 17 */ +#define NVIC_ISPR_SETPEND_18 ((uint32_t)0x00040000) /*!< bit 18 */ +#define NVIC_ISPR_SETPEND_19 ((uint32_t)0x00080000) /*!< bit 19 */ +#define NVIC_ISPR_SETPEND_20 ((uint32_t)0x00100000) /*!< bit 20 */ +#define NVIC_ISPR_SETPEND_21 ((uint32_t)0x00200000) /*!< bit 21 */ +#define NVIC_ISPR_SETPEND_22 ((uint32_t)0x00400000) /*!< bit 22 */ +#define NVIC_ISPR_SETPEND_23 ((uint32_t)0x00800000) /*!< bit 23 */ +#define NVIC_ISPR_SETPEND_24 ((uint32_t)0x01000000) /*!< bit 24 */ +#define NVIC_ISPR_SETPEND_25 ((uint32_t)0x02000000) /*!< bit 25 */ +#define NVIC_ISPR_SETPEND_26 ((uint32_t)0x04000000) /*!< bit 26 */ +#define NVIC_ISPR_SETPEND_27 ((uint32_t)0x08000000) /*!< bit 27 */ +#define NVIC_ISPR_SETPEND_28 ((uint32_t)0x10000000) /*!< bit 28 */ +#define NVIC_ISPR_SETPEND_29 ((uint32_t)0x20000000) /*!< bit 29 */ +#define NVIC_ISPR_SETPEND_30 ((uint32_t)0x40000000) /*!< bit 30 */ +#define NVIC_ISPR_SETPEND_31 ((uint32_t)0x80000000) /*!< bit 31 */ + +/****************** Bit definition for NVIC_ICPR register *******************/ +#define NVIC_ICPR_CLRPEND ((uint32_t)0xFFFFFFFF) /*!< Interrupt clear-pending bits */ +#define NVIC_ICPR_CLRPEND_0 ((uint32_t)0x00000001) /*!< bit 0 */ +#define NVIC_ICPR_CLRPEND_1 ((uint32_t)0x00000002) /*!< bit 1 */ +#define NVIC_ICPR_CLRPEND_2 ((uint32_t)0x00000004) /*!< bit 2 */ +#define NVIC_ICPR_CLRPEND_3 ((uint32_t)0x00000008) /*!< bit 3 */ +#define NVIC_ICPR_CLRPEND_4 ((uint32_t)0x00000010) /*!< bit 4 */ +#define NVIC_ICPR_CLRPEND_5 ((uint32_t)0x00000020) /*!< bit 5 */ +#define NVIC_ICPR_CLRPEND_6 ((uint32_t)0x00000040) /*!< bit 6 */ +#define NVIC_ICPR_CLRPEND_7 ((uint32_t)0x00000080) /*!< bit 7 */ +#define NVIC_ICPR_CLRPEND_8 ((uint32_t)0x00000100) /*!< bit 8 */ +#define NVIC_ICPR_CLRPEND_9 ((uint32_t)0x00000200) /*!< bit 9 */ +#define NVIC_ICPR_CLRPEND_10 ((uint32_t)0x00000400) /*!< bit 10 */ +#define NVIC_ICPR_CLRPEND_11 ((uint32_t)0x00000800) /*!< bit 11 */ +#define NVIC_ICPR_CLRPEND_12 ((uint32_t)0x00001000) /*!< bit 12 */ +#define NVIC_ICPR_CLRPEND_13 ((uint32_t)0x00002000) /*!< bit 13 */ +#define NVIC_ICPR_CLRPEND_14 ((uint32_t)0x00004000) /*!< bit 14 */ +#define NVIC_ICPR_CLRPEND_15 ((uint32_t)0x00008000) /*!< bit 15 */ +#define NVIC_ICPR_CLRPEND_16 ((uint32_t)0x00010000) /*!< bit 16 */ +#define NVIC_ICPR_CLRPEND_17 ((uint32_t)0x00020000) /*!< bit 17 */ +#define NVIC_ICPR_CLRPEND_18 ((uint32_t)0x00040000) /*!< bit 18 */ +#define NVIC_ICPR_CLRPEND_19 ((uint32_t)0x00080000) /*!< bit 19 */ +#define NVIC_ICPR_CLRPEND_20 ((uint32_t)0x00100000) /*!< bit 20 */ +#define NVIC_ICPR_CLRPEND_21 ((uint32_t)0x00200000) /*!< bit 21 */ +#define NVIC_ICPR_CLRPEND_22 ((uint32_t)0x00400000) /*!< bit 22 */ +#define NVIC_ICPR_CLRPEND_23 ((uint32_t)0x00800000) /*!< bit 23 */ +#define NVIC_ICPR_CLRPEND_24 ((uint32_t)0x01000000) /*!< bit 24 */ +#define NVIC_ICPR_CLRPEND_25 ((uint32_t)0x02000000) /*!< bit 25 */ +#define NVIC_ICPR_CLRPEND_26 ((uint32_t)0x04000000) /*!< bit 26 */ +#define NVIC_ICPR_CLRPEND_27 ((uint32_t)0x08000000) /*!< bit 27 */ +#define NVIC_ICPR_CLRPEND_28 ((uint32_t)0x10000000) /*!< bit 28 */ +#define NVIC_ICPR_CLRPEND_29 ((uint32_t)0x20000000) /*!< bit 29 */ +#define NVIC_ICPR_CLRPEND_30 ((uint32_t)0x40000000) /*!< bit 30 */ +#define NVIC_ICPR_CLRPEND_31 ((uint32_t)0x80000000) /*!< bit 31 */ + +/****************** Bit definition for NVIC_IABR register *******************/ +#define NVIC_IABR_ACTIVE ((uint32_t)0xFFFFFFFF) /*!< Interrupt active flags */ +#define NVIC_IABR_ACTIVE_0 ((uint32_t)0x00000001) /*!< bit 0 */ +#define NVIC_IABR_ACTIVE_1 ((uint32_t)0x00000002) /*!< bit 1 */ +#define NVIC_IABR_ACTIVE_2 ((uint32_t)0x00000004) /*!< bit 2 */ +#define NVIC_IABR_ACTIVE_3 ((uint32_t)0x00000008) /*!< bit 3 */ +#define NVIC_IABR_ACTIVE_4 ((uint32_t)0x00000010) /*!< bit 4 */ +#define NVIC_IABR_ACTIVE_5 ((uint32_t)0x00000020) /*!< bit 5 */ +#define NVIC_IABR_ACTIVE_6 ((uint32_t)0x00000040) /*!< bit 6 */ +#define NVIC_IABR_ACTIVE_7 ((uint32_t)0x00000080) /*!< bit 7 */ +#define NVIC_IABR_ACTIVE_8 ((uint32_t)0x00000100) /*!< bit 8 */ +#define NVIC_IABR_ACTIVE_9 ((uint32_t)0x00000200) /*!< bit 9 */ +#define NVIC_IABR_ACTIVE_10 ((uint32_t)0x00000400) /*!< bit 10 */ +#define NVIC_IABR_ACTIVE_11 ((uint32_t)0x00000800) /*!< bit 11 */ +#define NVIC_IABR_ACTIVE_12 ((uint32_t)0x00001000) /*!< bit 12 */ +#define NVIC_IABR_ACTIVE_13 ((uint32_t)0x00002000) /*!< bit 13 */ +#define NVIC_IABR_ACTIVE_14 ((uint32_t)0x00004000) /*!< bit 14 */ +#define NVIC_IABR_ACTIVE_15 ((uint32_t)0x00008000) /*!< bit 15 */ +#define NVIC_IABR_ACTIVE_16 ((uint32_t)0x00010000) /*!< bit 16 */ +#define NVIC_IABR_ACTIVE_17 ((uint32_t)0x00020000) /*!< bit 17 */ +#define NVIC_IABR_ACTIVE_18 ((uint32_t)0x00040000) /*!< bit 18 */ +#define NVIC_IABR_ACTIVE_19 ((uint32_t)0x00080000) /*!< bit 19 */ +#define NVIC_IABR_ACTIVE_20 ((uint32_t)0x00100000) /*!< bit 20 */ +#define NVIC_IABR_ACTIVE_21 ((uint32_t)0x00200000) /*!< bit 21 */ +#define NVIC_IABR_ACTIVE_22 ((uint32_t)0x00400000) /*!< bit 22 */ +#define NVIC_IABR_ACTIVE_23 ((uint32_t)0x00800000) /*!< bit 23 */ +#define NVIC_IABR_ACTIVE_24 ((uint32_t)0x01000000) /*!< bit 24 */ +#define NVIC_IABR_ACTIVE_25 ((uint32_t)0x02000000) /*!< bit 25 */ +#define NVIC_IABR_ACTIVE_26 ((uint32_t)0x04000000) /*!< bit 26 */ +#define NVIC_IABR_ACTIVE_27 ((uint32_t)0x08000000) /*!< bit 27 */ +#define NVIC_IABR_ACTIVE_28 ((uint32_t)0x10000000) /*!< bit 28 */ +#define NVIC_IABR_ACTIVE_29 ((uint32_t)0x20000000) /*!< bit 29 */ +#define NVIC_IABR_ACTIVE_30 ((uint32_t)0x40000000) /*!< bit 30 */ +#define NVIC_IABR_ACTIVE_31 ((uint32_t)0x80000000) /*!< bit 31 */ + +/****************** Bit definition for NVIC_PRI0 register *******************/ +#define NVIC_IPR0_PRI_0 ((uint32_t)0x000000FF) /*!< Priority of interrupt 0 */ +#define NVIC_IPR0_PRI_1 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 1 */ +#define NVIC_IPR0_PRI_2 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 2 */ +#define NVIC_IPR0_PRI_3 ((uint32_t)0xFF000000) /*!< Priority of interrupt 3 */ + +/****************** Bit definition for NVIC_PRI1 register *******************/ +#define NVIC_IPR1_PRI_4 ((uint32_t)0x000000FF) /*!< Priority of interrupt 4 */ +#define NVIC_IPR1_PRI_5 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 5 */ +#define NVIC_IPR1_PRI_6 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 6 */ +#define NVIC_IPR1_PRI_7 ((uint32_t)0xFF000000) /*!< Priority of interrupt 7 */ + +/****************** Bit definition for NVIC_PRI2 register *******************/ +#define NVIC_IPR2_PRI_8 ((uint32_t)0x000000FF) /*!< Priority of interrupt 8 */ +#define NVIC_IPR2_PRI_9 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 9 */ +#define NVIC_IPR2_PRI_10 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 10 */ +#define NVIC_IPR2_PRI_11 ((uint32_t)0xFF000000) /*!< Priority of interrupt 11 */ + +/****************** Bit definition for NVIC_PRI3 register *******************/ +#define NVIC_IPR3_PRI_12 ((uint32_t)0x000000FF) /*!< Priority of interrupt 12 */ +#define NVIC_IPR3_PRI_13 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 13 */ +#define NVIC_IPR3_PRI_14 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 14 */ +#define NVIC_IPR3_PRI_15 ((uint32_t)0xFF000000) /*!< Priority of interrupt 15 */ + +/****************** Bit definition for NVIC_PRI4 register *******************/ +#define NVIC_IPR4_PRI_16 ((uint32_t)0x000000FF) /*!< Priority of interrupt 16 */ +#define NVIC_IPR4_PRI_17 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 17 */ +#define NVIC_IPR4_PRI_18 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 18 */ +#define NVIC_IPR4_PRI_19 ((uint32_t)0xFF000000) /*!< Priority of interrupt 19 */ + +/****************** Bit definition for NVIC_PRI5 register *******************/ +#define NVIC_IPR5_PRI_20 ((uint32_t)0x000000FF) /*!< Priority of interrupt 20 */ +#define NVIC_IPR5_PRI_21 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 21 */ +#define NVIC_IPR5_PRI_22 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 22 */ +#define NVIC_IPR5_PRI_23 ((uint32_t)0xFF000000) /*!< Priority of interrupt 23 */ + +/****************** Bit definition for NVIC_PRI6 register *******************/ +#define NVIC_IPR6_PRI_24 ((uint32_t)0x000000FF) /*!< Priority of interrupt 24 */ +#define NVIC_IPR6_PRI_25 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 25 */ +#define NVIC_IPR6_PRI_26 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 26 */ +#define NVIC_IPR6_PRI_27 ((uint32_t)0xFF000000) /*!< Priority of interrupt 27 */ + +/****************** Bit definition for NVIC_PRI7 register *******************/ +#define NVIC_IPR7_PRI_28 ((uint32_t)0x000000FF) /*!< Priority of interrupt 28 */ +#define NVIC_IPR7_PRI_29 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 29 */ +#define NVIC_IPR7_PRI_30 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 30 */ +#define NVIC_IPR7_PRI_31 ((uint32_t)0xFF000000) /*!< Priority of interrupt 31 */ + +/****************** Bit definition for SCB_CPUID register *******************/ +#define SCB_CPUID_REVISION ((uint32_t)0x0000000F) /*!< Implementation defined revision number */ +#define SCB_CPUID_PARTNO ((uint32_t)0x0000FFF0) /*!< Number of processor within family */ +#define SCB_CPUID_Constant ((uint32_t)0x000F0000) /*!< Reads as 0x0F */ +#define SCB_CPUID_VARIANT ((uint32_t)0x00F00000) /*!< Implementation defined variant number */ +#define SCB_CPUID_IMPLEMENTER ((uint32_t)0xFF000000) /*!< Implementer code. ARM is 0x41 */ + +/******************* Bit definition for SCB_ICSR register *******************/ +#define SCB_ICSR_VECTACTIVE ((uint32_t)0x000001FF) /*!< Active ISR number field */ +#define SCB_ICSR_RETTOBASE ((uint32_t)0x00000800) /*!< All active exceptions minus the IPSR_current_exception yields the empty set */ +#define SCB_ICSR_VECTPENDING ((uint32_t)0x003FF000) /*!< Pending ISR number field */ +#define SCB_ICSR_ISRPENDING ((uint32_t)0x00400000) /*!< Interrupt pending flag */ +#define SCB_ICSR_ISRPREEMPT ((uint32_t)0x00800000) /*!< It indicates that a pending interrupt becomes active in the next running cycle */ +#define SCB_ICSR_PENDSTCLR ((uint32_t)0x02000000) /*!< Clear pending SysTick bit */ +#define SCB_ICSR_PENDSTSET ((uint32_t)0x04000000) /*!< Set pending SysTick bit */ +#define SCB_ICSR_PENDSVCLR ((uint32_t)0x08000000) /*!< Clear pending pendSV bit */ +#define SCB_ICSR_PENDSVSET ((uint32_t)0x10000000) /*!< Set pending pendSV bit */ +#define SCB_ICSR_NMIPENDSET ((uint32_t)0x80000000) /*!< Set pending NMI bit */ + +/******************* Bit definition for SCB_VTOR register *******************/ +#define SCB_VTOR_TBLOFF ((uint32_t)0x1FFFFF80) /*!< Vector table base offset field */ +#define SCB_VTOR_TBLBASE ((uint32_t)0x20000000) /*!< Table base in code(0) or RAM(1) */ + +/*!<***************** Bit definition for SCB_AIRCR register *******************/ +#define SCB_AIRCR_VECTRESET ((uint32_t)0x00000001) /*!< System Reset bit */ +#define SCB_AIRCR_VECTCLRACTIVE ((uint32_t)0x00000002) /*!< Clear active vector bit */ +#define SCB_AIRCR_SYSRESETREQ ((uint32_t)0x00000004) /*!< Requests chip control logic to generate a reset */ + +#define SCB_AIRCR_PRIGROUP ((uint32_t)0x00000700) /*!< PRIGROUP[2:0] bits (Priority group) */ +#define SCB_AIRCR_PRIGROUP_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define SCB_AIRCR_PRIGROUP_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define SCB_AIRCR_PRIGROUP_2 ((uint32_t)0x00000400) /*!< Bit 2 */ + +/* prority group configuration */ +#define SCB_AIRCR_PRIGROUP0 ((uint32_t)0x00000000) /*!< Priority group=0 (7 bits of pre-emption priority, 1 bit of subpriority) */ +#define SCB_AIRCR_PRIGROUP1 ((uint32_t)0x00000100) /*!< Priority group=1 (6 bits of pre-emption priority, 2 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP2 ((uint32_t)0x00000200) /*!< Priority group=2 (5 bits of pre-emption priority, 3 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP3 ((uint32_t)0x00000300) /*!< Priority group=3 (4 bits of pre-emption priority, 4 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP4 ((uint32_t)0x00000400) /*!< Priority group=4 (3 bits of pre-emption priority, 5 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP5 ((uint32_t)0x00000500) /*!< Priority group=5 (2 bits of pre-emption priority, 6 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP6 ((uint32_t)0x00000600) /*!< Priority group=6 (1 bit of pre-emption priority, 7 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP7 ((uint32_t)0x00000700) /*!< Priority group=7 (no pre-emption priority, 8 bits of subpriority) */ + +#define SCB_AIRCR_ENDIANESS ((uint32_t)0x00008000) /*!< Data endianness bit */ +#define SCB_AIRCR_VECTKEY ((uint32_t)0xFFFF0000) /*!< Register key (VECTKEY) - Reads as 0xFA05 (VECTKEYSTAT) */ + +/******************* Bit definition for SCB_SCR register ********************/ +#define SCB_SCR_SLEEPONEXIT ((uint8_t)0x02) /*!< Sleep on exit bit */ +#define SCB_SCR_SLEEPDEEP ((uint8_t)0x04) /*!< Sleep deep bit */ +#define SCB_SCR_SEVONPEND ((uint8_t)0x10) /*!< Wake up from WFE */ + +/******************** Bit definition for SCB_CCR register *******************/ +#define SCB_CCR_NONBASETHRDENA ((uint16_t)0x0001) /*!< Thread mode can be entered from any level in Handler mode by controlled return value */ +#define SCB_CCR_USERSETMPEND ((uint16_t)0x0002) /*!< Enables user code to write the Software Trigger Interrupt register to trigger (pend) a Main exception */ +#define SCB_CCR_UNALIGN_TRP ((uint16_t)0x0008) /*!< Trap for unaligned access */ +#define SCB_CCR_DIV_0_TRP ((uint16_t)0x0010) /*!< Trap on Divide by 0 */ +#define SCB_CCR_BFHFNMIGN ((uint16_t)0x0100) /*!< Handlers running at priority -1 and -2 */ +#define SCB_CCR_STKALIGN ((uint16_t)0x0200) /*!< On exception entry, the SP used prior to the exception is adjusted to be 8-byte aligned */ + +/******************* Bit definition for SCB_SHPR register ********************/ +#define SCB_SHPR_PRI_N ((uint32_t)0x000000FF) /*!< Priority of system handler 4,8, and 12. Mem Manage, reserved and Debug Monitor */ +#define SCB_SHPR_PRI_N1 ((uint32_t)0x0000FF00) /*!< Priority of system handler 5,9, and 13. Bus Fault, reserved and reserved */ +#define SCB_SHPR_PRI_N2 ((uint32_t)0x00FF0000) /*!< Priority of system handler 6,10, and 14. Usage Fault, reserved and PendSV */ +#define SCB_SHPR_PRI_N3 ((uint32_t)0xFF000000) /*!< Priority of system handler 7,11, and 15. Reserved, SVCall and SysTick */ + +/****************** Bit definition for SCB_SHCSR register *******************/ +#define SCB_SHCSR_MEMFAULTACT ((uint32_t)0x00000001) /*!< MemManage is active */ +#define SCB_SHCSR_BUSFAULTACT ((uint32_t)0x00000002) /*!< BusFault is active */ +#define SCB_SHCSR_USGFAULTACT ((uint32_t)0x00000008) /*!< UsageFault is active */ +#define SCB_SHCSR_SVCALLACT ((uint32_t)0x00000080) /*!< SVCall is active */ +#define SCB_SHCSR_MONITORACT ((uint32_t)0x00000100) /*!< Monitor is active */ +#define SCB_SHCSR_PENDSVACT ((uint32_t)0x00000400) /*!< PendSV is active */ +#define SCB_SHCSR_SYSTICKACT ((uint32_t)0x00000800) /*!< SysTick is active */ +#define SCB_SHCSR_USGFAULTPENDED ((uint32_t)0x00001000) /*!< Usage Fault is pended */ +#define SCB_SHCSR_MEMFAULTPENDED ((uint32_t)0x00002000) /*!< MemManage is pended */ +#define SCB_SHCSR_BUSFAULTPENDED ((uint32_t)0x00004000) /*!< Bus Fault is pended */ +#define SCB_SHCSR_SVCALLPENDED ((uint32_t)0x00008000) /*!< SVCall is pended */ +#define SCB_SHCSR_MEMFAULTENA ((uint32_t)0x00010000) /*!< MemManage enable */ +#define SCB_SHCSR_BUSFAULTENA ((uint32_t)0x00020000) /*!< Bus Fault enable */ +#define SCB_SHCSR_USGFAULTENA ((uint32_t)0x00040000) /*!< UsageFault enable */ + +/******************* Bit definition for SCB_CFSR register *******************/ +/*!< MFSR */ +#define SCB_CFSR_IACCVIOL ((uint32_t)0x00000001) /*!< Instruction access violation */ +#define SCB_CFSR_DACCVIOL ((uint32_t)0x00000002) /*!< Data access violation */ +#define SCB_CFSR_MUNSTKERR ((uint32_t)0x00000008) /*!< Unstacking error */ +#define SCB_CFSR_MSTKERR ((uint32_t)0x00000010) /*!< Stacking error */ +#define SCB_CFSR_MMARVALID ((uint32_t)0x00000080) /*!< Memory Manage Address Register address valid flag */ +/*!< BFSR */ +#define SCB_CFSR_IBUSERR ((uint32_t)0x00000100) /*!< Instruction bus error flag */ +#define SCB_CFSR_PRECISERR ((uint32_t)0x00000200) /*!< Precise data bus error */ +#define SCB_CFSR_IMPRECISERR ((uint32_t)0x00000400) /*!< Imprecise data bus error */ +#define SCB_CFSR_UNSTKERR ((uint32_t)0x00000800) /*!< Unstacking error */ +#define SCB_CFSR_STKERR ((uint32_t)0x00001000) /*!< Stacking error */ +#define SCB_CFSR_BFARVALID ((uint32_t)0x00008000) /*!< Bus Fault Address Register address valid flag */ +/*!< UFSR */ +#define SCB_CFSR_UNDEFINSTR ((uint32_t)0x00010000) /*!< The processor attempt to execute an undefined instruction */ +#define SCB_CFSR_INVSTATE ((uint32_t)0x00020000) /*!< Invalid combination of EPSR and instruction */ +#define SCB_CFSR_INVPC ((uint32_t)0x00040000) /*!< Attempt to load EXC_RETURN into pc illegally */ +#define SCB_CFSR_NOCP ((uint32_t)0x00080000) /*!< Attempt to use a coprocessor instruction */ +#define SCB_CFSR_UNALIGNED ((uint32_t)0x01000000) /*!< Fault occurs when there is an attempt to make an unaligned memory access */ +#define SCB_CFSR_DIVBYZERO ((uint32_t)0x02000000) /*!< Fault occurs when SDIV or DIV instruction is used with a divisor of 0 */ + +/******************* Bit definition for SCB_HFSR register *******************/ +#define SCB_HFSR_VECTTBL ((uint32_t)0x00000002) /*!< Fault occurs because of vector table read on exception processing */ +#define SCB_HFSR_FORCED ((uint32_t)0x40000000) /*!< Hard Fault activated when a configurable Fault was received and cannot activate */ +#define SCB_HFSR_DEBUGEVT ((uint32_t)0x80000000) /*!< Fault related to debug */ + +/******************* Bit definition for SCB_DFSR register *******************/ +#define SCB_DFSR_HALTED ((uint8_t)0x01) /*!< Halt request flag */ +#define SCB_DFSR_BKPT ((uint8_t)0x02) /*!< BKPT flag */ +#define SCB_DFSR_DWTTRAP ((uint8_t)0x04) /*!< Data Watchpoint and Trace (DWT) flag */ +#define SCB_DFSR_VCATCH ((uint8_t)0x08) /*!< Vector catch flag */ +#define SCB_DFSR_EXTERNAL ((uint8_t)0x10) /*!< External debug request flag */ + +/******************* Bit definition for SCB_MMFAR register ******************/ +#define SCB_MMFAR_ADDRESS ((uint32_t)0xFFFFFFFF) /*!< Mem Manage fault address field */ + +/******************* Bit definition for SCB_BFAR register *******************/ +#define SCB_BFAR_ADDRESS ((uint32_t)0xFFFFFFFF) /*!< Bus fault address field */ + +/******************* Bit definition for SCB_afsr register *******************/ +#define SCB_AFSR_IMPDEF ((uint32_t)0xFFFFFFFF) /*!< Implementation defined */ + +/******************************************************************************/ +/* */ +/* External Interrupt/Event Controller */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for EXTI_IMR register *******************/ +#define EXTI_IMR_MR0 ((uint32_t)0x00000001) /*!< Interrupt Mask on line 0 */ +#define EXTI_IMR_MR1 ((uint32_t)0x00000002) /*!< Interrupt Mask on line 1 */ +#define EXTI_IMR_MR2 ((uint32_t)0x00000004) /*!< Interrupt Mask on line 2 */ +#define EXTI_IMR_MR3 ((uint32_t)0x00000008) /*!< Interrupt Mask on line 3 */ +#define EXTI_IMR_MR4 ((uint32_t)0x00000010) /*!< Interrupt Mask on line 4 */ +#define EXTI_IMR_MR5 ((uint32_t)0x00000020) /*!< Interrupt Mask on line 5 */ +#define EXTI_IMR_MR6 ((uint32_t)0x00000040) /*!< Interrupt Mask on line 6 */ +#define EXTI_IMR_MR7 ((uint32_t)0x00000080) /*!< Interrupt Mask on line 7 */ +#define EXTI_IMR_MR8 ((uint32_t)0x00000100) /*!< Interrupt Mask on line 8 */ +#define EXTI_IMR_MR9 ((uint32_t)0x00000200) /*!< Interrupt Mask on line 9 */ +#define EXTI_IMR_MR10 ((uint32_t)0x00000400) /*!< Interrupt Mask on line 10 */ +#define EXTI_IMR_MR11 ((uint32_t)0x00000800) /*!< Interrupt Mask on line 11 */ +#define EXTI_IMR_MR12 ((uint32_t)0x00001000) /*!< Interrupt Mask on line 12 */ +#define EXTI_IMR_MR13 ((uint32_t)0x00002000) /*!< Interrupt Mask on line 13 */ +#define EXTI_IMR_MR14 ((uint32_t)0x00004000) /*!< Interrupt Mask on line 14 */ +#define EXTI_IMR_MR15 ((uint32_t)0x00008000) /*!< Interrupt Mask on line 15 */ +#define EXTI_IMR_MR16 ((uint32_t)0x00010000) /*!< Interrupt Mask on line 16 */ +#define EXTI_IMR_MR17 ((uint32_t)0x00020000) /*!< Interrupt Mask on line 17 */ +#define EXTI_IMR_MR18 ((uint32_t)0x00040000) /*!< Interrupt Mask on line 18 */ +#define EXTI_IMR_MR19 ((uint32_t)0x00080000) /*!< Interrupt Mask on line 19 */ + +/******************* Bit definition for EXTI_EMR register *******************/ +#define EXTI_EMR_MR0 ((uint32_t)0x00000001) /*!< Event Mask on line 0 */ +#define EXTI_EMR_MR1 ((uint32_t)0x00000002) /*!< Event Mask on line 1 */ +#define EXTI_EMR_MR2 ((uint32_t)0x00000004) /*!< Event Mask on line 2 */ +#define EXTI_EMR_MR3 ((uint32_t)0x00000008) /*!< Event Mask on line 3 */ +#define EXTI_EMR_MR4 ((uint32_t)0x00000010) /*!< Event Mask on line 4 */ +#define EXTI_EMR_MR5 ((uint32_t)0x00000020) /*!< Event Mask on line 5 */ +#define EXTI_EMR_MR6 ((uint32_t)0x00000040) /*!< Event Mask on line 6 */ +#define EXTI_EMR_MR7 ((uint32_t)0x00000080) /*!< Event Mask on line 7 */ +#define EXTI_EMR_MR8 ((uint32_t)0x00000100) /*!< Event Mask on line 8 */ +#define EXTI_EMR_MR9 ((uint32_t)0x00000200) /*!< Event Mask on line 9 */ +#define EXTI_EMR_MR10 ((uint32_t)0x00000400) /*!< Event Mask on line 10 */ +#define EXTI_EMR_MR11 ((uint32_t)0x00000800) /*!< Event Mask on line 11 */ +#define EXTI_EMR_MR12 ((uint32_t)0x00001000) /*!< Event Mask on line 12 */ +#define EXTI_EMR_MR13 ((uint32_t)0x00002000) /*!< Event Mask on line 13 */ +#define EXTI_EMR_MR14 ((uint32_t)0x00004000) /*!< Event Mask on line 14 */ +#define EXTI_EMR_MR15 ((uint32_t)0x00008000) /*!< Event Mask on line 15 */ +#define EXTI_EMR_MR16 ((uint32_t)0x00010000) /*!< Event Mask on line 16 */ +#define EXTI_EMR_MR17 ((uint32_t)0x00020000) /*!< Event Mask on line 17 */ +#define EXTI_EMR_MR18 ((uint32_t)0x00040000) /*!< Event Mask on line 18 */ +#define EXTI_EMR_MR19 ((uint32_t)0x00080000) /*!< Event Mask on line 19 */ + +/****************** Bit definition for EXTI_RTSR register *******************/ +#define EXTI_RTSR_TR0 ((uint32_t)0x00000001) /*!< Rising trigger event configuration bit of line 0 */ +#define EXTI_RTSR_TR1 ((uint32_t)0x00000002) /*!< Rising trigger event configuration bit of line 1 */ +#define EXTI_RTSR_TR2 ((uint32_t)0x00000004) /*!< Rising trigger event configuration bit of line 2 */ +#define EXTI_RTSR_TR3 ((uint32_t)0x00000008) /*!< Rising trigger event configuration bit of line 3 */ +#define EXTI_RTSR_TR4 ((uint32_t)0x00000010) /*!< Rising trigger event configuration bit of line 4 */ +#define EXTI_RTSR_TR5 ((uint32_t)0x00000020) /*!< Rising trigger event configuration bit of line 5 */ +#define EXTI_RTSR_TR6 ((uint32_t)0x00000040) /*!< Rising trigger event configuration bit of line 6 */ +#define EXTI_RTSR_TR7 ((uint32_t)0x00000080) /*!< Rising trigger event configuration bit of line 7 */ +#define EXTI_RTSR_TR8 ((uint32_t)0x00000100) /*!< Rising trigger event configuration bit of line 8 */ +#define EXTI_RTSR_TR9 ((uint32_t)0x00000200) /*!< Rising trigger event configuration bit of line 9 */ +#define EXTI_RTSR_TR10 ((uint32_t)0x00000400) /*!< Rising trigger event configuration bit of line 10 */ +#define EXTI_RTSR_TR11 ((uint32_t)0x00000800) /*!< Rising trigger event configuration bit of line 11 */ +#define EXTI_RTSR_TR12 ((uint32_t)0x00001000) /*!< Rising trigger event configuration bit of line 12 */ +#define EXTI_RTSR_TR13 ((uint32_t)0x00002000) /*!< Rising trigger event configuration bit of line 13 */ +#define EXTI_RTSR_TR14 ((uint32_t)0x00004000) /*!< Rising trigger event configuration bit of line 14 */ +#define EXTI_RTSR_TR15 ((uint32_t)0x00008000) /*!< Rising trigger event configuration bit of line 15 */ +#define EXTI_RTSR_TR16 ((uint32_t)0x00010000) /*!< Rising trigger event configuration bit of line 16 */ +#define EXTI_RTSR_TR17 ((uint32_t)0x00020000) /*!< Rising trigger event configuration bit of line 17 */ +#define EXTI_RTSR_TR18 ((uint32_t)0x00040000) /*!< Rising trigger event configuration bit of line 18 */ +#define EXTI_RTSR_TR19 ((uint32_t)0x00080000) /*!< Rising trigger event configuration bit of line 19 */ + +/****************** Bit definition for EXTI_FTSR register *******************/ +#define EXTI_FTSR_TR0 ((uint32_t)0x00000001) /*!< Falling trigger event configuration bit of line 0 */ +#define EXTI_FTSR_TR1 ((uint32_t)0x00000002) /*!< Falling trigger event configuration bit of line 1 */ +#define EXTI_FTSR_TR2 ((uint32_t)0x00000004) /*!< Falling trigger event configuration bit of line 2 */ +#define EXTI_FTSR_TR3 ((uint32_t)0x00000008) /*!< Falling trigger event configuration bit of line 3 */ +#define EXTI_FTSR_TR4 ((uint32_t)0x00000010) /*!< Falling trigger event configuration bit of line 4 */ +#define EXTI_FTSR_TR5 ((uint32_t)0x00000020) /*!< Falling trigger event configuration bit of line 5 */ +#define EXTI_FTSR_TR6 ((uint32_t)0x00000040) /*!< Falling trigger event configuration bit of line 6 */ +#define EXTI_FTSR_TR7 ((uint32_t)0x00000080) /*!< Falling trigger event configuration bit of line 7 */ +#define EXTI_FTSR_TR8 ((uint32_t)0x00000100) /*!< Falling trigger event configuration bit of line 8 */ +#define EXTI_FTSR_TR9 ((uint32_t)0x00000200) /*!< Falling trigger event configuration bit of line 9 */ +#define EXTI_FTSR_TR10 ((uint32_t)0x00000400) /*!< Falling trigger event configuration bit of line 10 */ +#define EXTI_FTSR_TR11 ((uint32_t)0x00000800) /*!< Falling trigger event configuration bit of line 11 */ +#define EXTI_FTSR_TR12 ((uint32_t)0x00001000) /*!< Falling trigger event configuration bit of line 12 */ +#define EXTI_FTSR_TR13 ((uint32_t)0x00002000) /*!< Falling trigger event configuration bit of line 13 */ +#define EXTI_FTSR_TR14 ((uint32_t)0x00004000) /*!< Falling trigger event configuration bit of line 14 */ +#define EXTI_FTSR_TR15 ((uint32_t)0x00008000) /*!< Falling trigger event configuration bit of line 15 */ +#define EXTI_FTSR_TR16 ((uint32_t)0x00010000) /*!< Falling trigger event configuration bit of line 16 */ +#define EXTI_FTSR_TR17 ((uint32_t)0x00020000) /*!< Falling trigger event configuration bit of line 17 */ +#define EXTI_FTSR_TR18 ((uint32_t)0x00040000) /*!< Falling trigger event configuration bit of line 18 */ +#define EXTI_FTSR_TR19 ((uint32_t)0x00080000) /*!< Falling trigger event configuration bit of line 19 */ + +/****************** Bit definition for EXTI_SWIER register ******************/ +#define EXTI_SWIER_SWIER0 ((uint32_t)0x00000001) /*!< Software Interrupt on line 0 */ +#define EXTI_SWIER_SWIER1 ((uint32_t)0x00000002) /*!< Software Interrupt on line 1 */ +#define EXTI_SWIER_SWIER2 ((uint32_t)0x00000004) /*!< Software Interrupt on line 2 */ +#define EXTI_SWIER_SWIER3 ((uint32_t)0x00000008) /*!< Software Interrupt on line 3 */ +#define EXTI_SWIER_SWIER4 ((uint32_t)0x00000010) /*!< Software Interrupt on line 4 */ +#define EXTI_SWIER_SWIER5 ((uint32_t)0x00000020) /*!< Software Interrupt on line 5 */ +#define EXTI_SWIER_SWIER6 ((uint32_t)0x00000040) /*!< Software Interrupt on line 6 */ +#define EXTI_SWIER_SWIER7 ((uint32_t)0x00000080) /*!< Software Interrupt on line 7 */ +#define EXTI_SWIER_SWIER8 ((uint32_t)0x00000100) /*!< Software Interrupt on line 8 */ +#define EXTI_SWIER_SWIER9 ((uint32_t)0x00000200) /*!< Software Interrupt on line 9 */ +#define EXTI_SWIER_SWIER10 ((uint32_t)0x00000400) /*!< Software Interrupt on line 10 */ +#define EXTI_SWIER_SWIER11 ((uint32_t)0x00000800) /*!< Software Interrupt on line 11 */ +#define EXTI_SWIER_SWIER12 ((uint32_t)0x00001000) /*!< Software Interrupt on line 12 */ +#define EXTI_SWIER_SWIER13 ((uint32_t)0x00002000) /*!< Software Interrupt on line 13 */ +#define EXTI_SWIER_SWIER14 ((uint32_t)0x00004000) /*!< Software Interrupt on line 14 */ +#define EXTI_SWIER_SWIER15 ((uint32_t)0x00008000) /*!< Software Interrupt on line 15 */ +#define EXTI_SWIER_SWIER16 ((uint32_t)0x00010000) /*!< Software Interrupt on line 16 */ +#define EXTI_SWIER_SWIER17 ((uint32_t)0x00020000) /*!< Software Interrupt on line 17 */ +#define EXTI_SWIER_SWIER18 ((uint32_t)0x00040000) /*!< Software Interrupt on line 18 */ +#define EXTI_SWIER_SWIER19 ((uint32_t)0x00080000) /*!< Software Interrupt on line 19 */ + +/******************* Bit definition for EXTI_PR register ********************/ +#define EXTI_PR_PR0 ((uint32_t)0x00000001) /*!< Pending bit for line 0 */ +#define EXTI_PR_PR1 ((uint32_t)0x00000002) /*!< Pending bit for line 1 */ +#define EXTI_PR_PR2 ((uint32_t)0x00000004) /*!< Pending bit for line 2 */ +#define EXTI_PR_PR3 ((uint32_t)0x00000008) /*!< Pending bit for line 3 */ +#define EXTI_PR_PR4 ((uint32_t)0x00000010) /*!< Pending bit for line 4 */ +#define EXTI_PR_PR5 ((uint32_t)0x00000020) /*!< Pending bit for line 5 */ +#define EXTI_PR_PR6 ((uint32_t)0x00000040) /*!< Pending bit for line 6 */ +#define EXTI_PR_PR7 ((uint32_t)0x00000080) /*!< Pending bit for line 7 */ +#define EXTI_PR_PR8 ((uint32_t)0x00000100) /*!< Pending bit for line 8 */ +#define EXTI_PR_PR9 ((uint32_t)0x00000200) /*!< Pending bit for line 9 */ +#define EXTI_PR_PR10 ((uint32_t)0x00000400) /*!< Pending bit for line 10 */ +#define EXTI_PR_PR11 ((uint32_t)0x00000800) /*!< Pending bit for line 11 */ +#define EXTI_PR_PR12 ((uint32_t)0x00001000) /*!< Pending bit for line 12 */ +#define EXTI_PR_PR13 ((uint32_t)0x00002000) /*!< Pending bit for line 13 */ +#define EXTI_PR_PR14 ((uint32_t)0x00004000) /*!< Pending bit for line 14 */ +#define EXTI_PR_PR15 ((uint32_t)0x00008000) /*!< Pending bit for line 15 */ +#define EXTI_PR_PR16 ((uint32_t)0x00010000) /*!< Pending bit for line 16 */ +#define EXTI_PR_PR17 ((uint32_t)0x00020000) /*!< Pending bit for line 17 */ +#define EXTI_PR_PR18 ((uint32_t)0x00040000) /*!< Pending bit for line 18 */ +#define EXTI_PR_PR19 ((uint32_t)0x00080000) /*!< Pending bit for line 19 */ + +/******************************************************************************/ +/* */ +/* DMA Controller */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for DMA_ISR register ********************/ +#define DMA_ISR_GIF1 ((uint32_t)0x00000001) /*!< Channel 1 Global interrupt flag */ +#define DMA_ISR_TCIF1 ((uint32_t)0x00000002) /*!< Channel 1 Transfer Complete flag */ +#define DMA_ISR_HTIF1 ((uint32_t)0x00000004) /*!< Channel 1 Half Transfer flag */ +#define DMA_ISR_TEIF1 ((uint32_t)0x00000008) /*!< Channel 1 Transfer Error flag */ +#define DMA_ISR_GIF2 ((uint32_t)0x00000010) /*!< Channel 2 Global interrupt flag */ +#define DMA_ISR_TCIF2 ((uint32_t)0x00000020) /*!< Channel 2 Transfer Complete flag */ +#define DMA_ISR_HTIF2 ((uint32_t)0x00000040) /*!< Channel 2 Half Transfer flag */ +#define DMA_ISR_TEIF2 ((uint32_t)0x00000080) /*!< Channel 2 Transfer Error flag */ +#define DMA_ISR_GIF3 ((uint32_t)0x00000100) /*!< Channel 3 Global interrupt flag */ +#define DMA_ISR_TCIF3 ((uint32_t)0x00000200) /*!< Channel 3 Transfer Complete flag */ +#define DMA_ISR_HTIF3 ((uint32_t)0x00000400) /*!< Channel 3 Half Transfer flag */ +#define DMA_ISR_TEIF3 ((uint32_t)0x00000800) /*!< Channel 3 Transfer Error flag */ +#define DMA_ISR_GIF4 ((uint32_t)0x00001000) /*!< Channel 4 Global interrupt flag */ +#define DMA_ISR_TCIF4 ((uint32_t)0x00002000) /*!< Channel 4 Transfer Complete flag */ +#define DMA_ISR_HTIF4 ((uint32_t)0x00004000) /*!< Channel 4 Half Transfer flag */ +#define DMA_ISR_TEIF4 ((uint32_t)0x00008000) /*!< Channel 4 Transfer Error flag */ +#define DMA_ISR_GIF5 ((uint32_t)0x00010000) /*!< Channel 5 Global interrupt flag */ +#define DMA_ISR_TCIF5 ((uint32_t)0x00020000) /*!< Channel 5 Transfer Complete flag */ +#define DMA_ISR_HTIF5 ((uint32_t)0x00040000) /*!< Channel 5 Half Transfer flag */ +#define DMA_ISR_TEIF5 ((uint32_t)0x00080000) /*!< Channel 5 Transfer Error flag */ +#define DMA_ISR_GIF6 ((uint32_t)0x00100000) /*!< Channel 6 Global interrupt flag */ +#define DMA_ISR_TCIF6 ((uint32_t)0x00200000) /*!< Channel 6 Transfer Complete flag */ +#define DMA_ISR_HTIF6 ((uint32_t)0x00400000) /*!< Channel 6 Half Transfer flag */ +#define DMA_ISR_TEIF6 ((uint32_t)0x00800000) /*!< Channel 6 Transfer Error flag */ +#define DMA_ISR_GIF7 ((uint32_t)0x01000000) /*!< Channel 7 Global interrupt flag */ +#define DMA_ISR_TCIF7 ((uint32_t)0x02000000) /*!< Channel 7 Transfer Complete flag */ +#define DMA_ISR_HTIF7 ((uint32_t)0x04000000) /*!< Channel 7 Half Transfer flag */ +#define DMA_ISR_TEIF7 ((uint32_t)0x08000000) /*!< Channel 7 Transfer Error flag */ + +/******************* Bit definition for DMA_IFCR register *******************/ +#define DMA_IFCR_CGIF1 ((uint32_t)0x00000001) /*!< Channel 1 Global interrupt clear */ +#define DMA_IFCR_CTCIF1 ((uint32_t)0x00000002) /*!< Channel 1 Transfer Complete clear */ +#define DMA_IFCR_CHTIF1 ((uint32_t)0x00000004) /*!< Channel 1 Half Transfer clear */ +#define DMA_IFCR_CTEIF1 ((uint32_t)0x00000008) /*!< Channel 1 Transfer Error clear */ +#define DMA_IFCR_CGIF2 ((uint32_t)0x00000010) /*!< Channel 2 Global interrupt clear */ +#define DMA_IFCR_CTCIF2 ((uint32_t)0x00000020) /*!< Channel 2 Transfer Complete clear */ +#define DMA_IFCR_CHTIF2 ((uint32_t)0x00000040) /*!< Channel 2 Half Transfer clear */ +#define DMA_IFCR_CTEIF2 ((uint32_t)0x00000080) /*!< Channel 2 Transfer Error clear */ +#define DMA_IFCR_CGIF3 ((uint32_t)0x00000100) /*!< Channel 3 Global interrupt clear */ +#define DMA_IFCR_CTCIF3 ((uint32_t)0x00000200) /*!< Channel 3 Transfer Complete clear */ +#define DMA_IFCR_CHTIF3 ((uint32_t)0x00000400) /*!< Channel 3 Half Transfer clear */ +#define DMA_IFCR_CTEIF3 ((uint32_t)0x00000800) /*!< Channel 3 Transfer Error clear */ +#define DMA_IFCR_CGIF4 ((uint32_t)0x00001000) /*!< Channel 4 Global interrupt clear */ +#define DMA_IFCR_CTCIF4 ((uint32_t)0x00002000) /*!< Channel 4 Transfer Complete clear */ +#define DMA_IFCR_CHTIF4 ((uint32_t)0x00004000) /*!< Channel 4 Half Transfer clear */ +#define DMA_IFCR_CTEIF4 ((uint32_t)0x00008000) /*!< Channel 4 Transfer Error clear */ +#define DMA_IFCR_CGIF5 ((uint32_t)0x00010000) /*!< Channel 5 Global interrupt clear */ +#define DMA_IFCR_CTCIF5 ((uint32_t)0x00020000) /*!< Channel 5 Transfer Complete clear */ +#define DMA_IFCR_CHTIF5 ((uint32_t)0x00040000) /*!< Channel 5 Half Transfer clear */ +#define DMA_IFCR_CTEIF5 ((uint32_t)0x00080000) /*!< Channel 5 Transfer Error clear */ +#define DMA_IFCR_CGIF6 ((uint32_t)0x00100000) /*!< Channel 6 Global interrupt clear */ +#define DMA_IFCR_CTCIF6 ((uint32_t)0x00200000) /*!< Channel 6 Transfer Complete clear */ +#define DMA_IFCR_CHTIF6 ((uint32_t)0x00400000) /*!< Channel 6 Half Transfer clear */ +#define DMA_IFCR_CTEIF6 ((uint32_t)0x00800000) /*!< Channel 6 Transfer Error clear */ +#define DMA_IFCR_CGIF7 ((uint32_t)0x01000000) /*!< Channel 7 Global interrupt clear */ +#define DMA_IFCR_CTCIF7 ((uint32_t)0x02000000) /*!< Channel 7 Transfer Complete clear */ +#define DMA_IFCR_CHTIF7 ((uint32_t)0x04000000) /*!< Channel 7 Half Transfer clear */ +#define DMA_IFCR_CTEIF7 ((uint32_t)0x08000000) /*!< Channel 7 Transfer Error clear */ + +/******************* Bit definition for DMA_CCR1 register *******************/ +#define DMA_CCR1_EN ((uint16_t)0x0001) /*!< Channel enable*/ +#define DMA_CCR1_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR1_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR1_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR1_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR1_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR1_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR1_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR1_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR1_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR1_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR1_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR1_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR1_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR1_PL ((uint16_t)0x3000) /*!< PL[1:0] bits(Channel Priority level) */ +#define DMA_CCR1_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR1_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR1_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ + +/******************* Bit definition for DMA_CCR2 register *******************/ +#define DMA_CCR2_EN ((uint16_t)0x0001) /*!< Channel enable */ +#define DMA_CCR2_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR2_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR2_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR2_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR2_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR2_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR2_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR2_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR2_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR2_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR2_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR2_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR2_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR2_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ +#define DMA_CCR2_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR2_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR2_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ + +/******************* Bit definition for DMA_CCR3 register *******************/ +#define DMA_CCR3_EN ((uint16_t)0x0001) /*!< Channel enable */ +#define DMA_CCR3_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR3_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR3_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR3_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR3_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR3_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR3_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR3_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR3_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR3_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR3_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR3_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR3_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR3_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ +#define DMA_CCR3_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR3_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR3_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ + +/*!<****************** Bit definition for DMA_CCR4 register *******************/ +#define DMA_CCR4_EN ((uint16_t)0x0001) /*!< Channel enable */ +#define DMA_CCR4_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR4_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR4_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR4_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR4_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR4_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR4_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR4_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR4_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR4_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR4_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR4_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR4_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR4_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ +#define DMA_CCR4_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR4_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR4_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ + +/****************** Bit definition for DMA_CCR5 register *******************/ +#define DMA_CCR5_EN ((uint16_t)0x0001) /*!< Channel enable */ +#define DMA_CCR5_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR5_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR5_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR5_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR5_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR5_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR5_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR5_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR5_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR5_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR5_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR5_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR5_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR5_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ +#define DMA_CCR5_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR5_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR5_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode enable */ + +/******************* Bit definition for DMA_CCR6 register *******************/ +#define DMA_CCR6_EN ((uint16_t)0x0001) /*!< Channel enable */ +#define DMA_CCR6_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR6_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR6_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR6_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR6_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR6_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR6_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR6_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR6_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR6_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR6_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR6_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR6_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR6_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ +#define DMA_CCR6_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR6_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR6_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ + +/******************* Bit definition for DMA_CCR7 register *******************/ +#define DMA_CCR7_EN ((uint16_t)0x0001) /*!< Channel enable */ +#define DMA_CCR7_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR7_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR7_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR7_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR7_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR7_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR7_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR7_PSIZE , ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR7_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR7_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR7_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR7_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR7_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR7_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ +#define DMA_CCR7_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR7_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR7_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode enable */ + +/****************** Bit definition for DMA_CNDTR1 register ******************/ +#define DMA_CNDTR1_NDT ((uint16_t)0xFFFF) /*!< Number of data to Transfer */ + +/****************** Bit definition for DMA_CNDTR2 register ******************/ +#define DMA_CNDTR2_NDT ((uint16_t)0xFFFF) /*!< Number of data to Transfer */ + +/****************** Bit definition for DMA_CNDTR3 register ******************/ +#define DMA_CNDTR3_NDT ((uint16_t)0xFFFF) /*!< Number of data to Transfer */ + +/****************** Bit definition for DMA_CNDTR4 register ******************/ +#define DMA_CNDTR4_NDT ((uint16_t)0xFFFF) /*!< Number of data to Transfer */ + +/****************** Bit definition for DMA_CNDTR5 register ******************/ +#define DMA_CNDTR5_NDT ((uint16_t)0xFFFF) /*!< Number of data to Transfer */ + +/****************** Bit definition for DMA_CNDTR6 register ******************/ +#define DMA_CNDTR6_NDT ((uint16_t)0xFFFF) /*!< Number of data to Transfer */ + +/****************** Bit definition for DMA_CNDTR7 register ******************/ +#define DMA_CNDTR7_NDT ((uint16_t)0xFFFF) /*!< Number of data to Transfer */ + +/****************** Bit definition for DMA_CPAR1 register *******************/ +#define DMA_CPAR1_PA ((uint32_t)0xFFFFFFFF) /*!< Peripheral Address */ + +/****************** Bit definition for DMA_CPAR2 register *******************/ +#define DMA_CPAR2_PA ((uint32_t)0xFFFFFFFF) /*!< Peripheral Address */ + +/****************** Bit definition for DMA_CPAR3 register *******************/ +#define DMA_CPAR3_PA ((uint32_t)0xFFFFFFFF) /*!< Peripheral Address */ + + +/****************** Bit definition for DMA_CPAR4 register *******************/ +#define DMA_CPAR4_PA ((uint32_t)0xFFFFFFFF) /*!< Peripheral Address */ + +/****************** Bit definition for DMA_CPAR5 register *******************/ +#define DMA_CPAR5_PA ((uint32_t)0xFFFFFFFF) /*!< Peripheral Address */ + +/****************** Bit definition for DMA_CPAR6 register *******************/ +#define DMA_CPAR6_PA ((uint32_t)0xFFFFFFFF) /*!< Peripheral Address */ + + +/****************** Bit definition for DMA_CPAR7 register *******************/ +#define DMA_CPAR7_PA ((uint32_t)0xFFFFFFFF) /*!< Peripheral Address */ + +/****************** Bit definition for DMA_CMAR1 register *******************/ +#define DMA_CMAR1_MA ((uint32_t)0xFFFFFFFF) /*!< Memory Address */ + +/****************** Bit definition for DMA_CMAR2 register *******************/ +#define DMA_CMAR2_MA ((uint32_t)0xFFFFFFFF) /*!< Memory Address */ + +/****************** Bit definition for DMA_CMAR3 register *******************/ +#define DMA_CMAR3_MA ((uint32_t)0xFFFFFFFF) /*!< Memory Address */ + + +/****************** Bit definition for DMA_CMAR4 register *******************/ +#define DMA_CMAR4_MA ((uint32_t)0xFFFFFFFF) /*!< Memory Address */ + +/****************** Bit definition for DMA_CMAR5 register *******************/ +#define DMA_CMAR5_MA ((uint32_t)0xFFFFFFFF) /*!< Memory Address */ + +/****************** Bit definition for DMA_CMAR6 register *******************/ +#define DMA_CMAR6_MA ((uint32_t)0xFFFFFFFF) /*!< Memory Address */ + +/****************** Bit definition for DMA_CMAR7 register *******************/ +#define DMA_CMAR7_MA ((uint32_t)0xFFFFFFFF) /*!< Memory Address */ + +/******************************************************************************/ +/* */ +/* Analog to Digital Converter */ +/* */ +/******************************************************************************/ + +/******************** Bit definition for ADC_SR register ********************/ +#define ADC_SR_AWD ((uint8_t)0x01) /*!< Analog watchdog flag */ +#define ADC_SR_EOC ((uint8_t)0x02) /*!< End of conversion */ +#define ADC_SR_JEOC ((uint8_t)0x04) /*!< Injected channel end of conversion */ +#define ADC_SR_JSTRT ((uint8_t)0x08) /*!< Injected channel Start flag */ +#define ADC_SR_STRT ((uint8_t)0x10) /*!< Regular channel Start flag */ + +/******************* Bit definition for ADC_CR1 register ********************/ +#define ADC_CR1_AWDCH ((uint32_t)0x0000001F) /*!< AWDCH[4:0] bits (Analog watchdog channel select bits) */ +#define ADC_CR1_AWDCH_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define ADC_CR1_AWDCH_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define ADC_CR1_AWDCH_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define ADC_CR1_AWDCH_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define ADC_CR1_AWDCH_4 ((uint32_t)0x00000010) /*!< Bit 4 */ + +#define ADC_CR1_EOCIE ((uint32_t)0x00000020) /*!< Interrupt enable for EOC */ +#define ADC_CR1_AWDIE ((uint32_t)0x00000040) /*!< Analog Watchdog interrupt enable */ +#define ADC_CR1_JEOCIE ((uint32_t)0x00000080) /*!< Interrupt enable for injected channels */ +#define ADC_CR1_SCAN ((uint32_t)0x00000100) /*!< Scan mode */ +#define ADC_CR1_AWDSGL ((uint32_t)0x00000200) /*!< Enable the watchdog on a single channel in scan mode */ +#define ADC_CR1_JAUTO ((uint32_t)0x00000400) /*!< Automatic injected group conversion */ +#define ADC_CR1_DISCEN ((uint32_t)0x00000800) /*!< Discontinuous mode on regular channels */ +#define ADC_CR1_JDISCEN ((uint32_t)0x00001000) /*!< Discontinuous mode on injected channels */ + +#define ADC_CR1_DISCNUM ((uint32_t)0x0000E000) /*!< DISCNUM[2:0] bits (Discontinuous mode channel count) */ +#define ADC_CR1_DISCNUM_0 ((uint32_t)0x00002000) /*!< Bit 0 */ +#define ADC_CR1_DISCNUM_1 ((uint32_t)0x00004000) /*!< Bit 1 */ +#define ADC_CR1_DISCNUM_2 ((uint32_t)0x00008000) /*!< Bit 2 */ + +#define ADC_CR1_DUALMOD ((uint32_t)0x000F0000) /*!< DUALMOD[3:0] bits (Dual mode selection) */ +#define ADC_CR1_DUALMOD_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define ADC_CR1_DUALMOD_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define ADC_CR1_DUALMOD_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define ADC_CR1_DUALMOD_3 ((uint32_t)0x00080000) /*!< Bit 3 */ + +#define ADC_CR1_JAWDEN ((uint32_t)0x00400000) /*!< Analog watchdog enable on injected channels */ +#define ADC_CR1_AWDEN ((uint32_t)0x00800000) /*!< Analog watchdog enable on regular channels */ + + +/******************* Bit definition for ADC_CR2 register ********************/ +#define ADC_CR2_ADON ((uint32_t)0x00000001) /*!< A/D Converter ON / OFF */ +#define ADC_CR2_CONT ((uint32_t)0x00000002) /*!< Continuous Conversion */ +#define ADC_CR2_CAL ((uint32_t)0x00000004) /*!< A/D Calibration */ +#define ADC_CR2_RSTCAL ((uint32_t)0x00000008) /*!< Reset Calibration */ +#define ADC_CR2_DMA ((uint32_t)0x00000100) /*!< Direct Memory access mode */ +#define ADC_CR2_ALIGN ((uint32_t)0x00000800) /*!< Data Alignment */ + +#define ADC_CR2_JEXTSEL ((uint32_t)0x00007000) /*!< JEXTSEL[2:0] bits (External event select for injected group) */ +#define ADC_CR2_JEXTSEL_0 ((uint32_t)0x00001000) /*!< Bit 0 */ +#define ADC_CR2_JEXTSEL_1 ((uint32_t)0x00002000) /*!< Bit 1 */ +#define ADC_CR2_JEXTSEL_2 ((uint32_t)0x00004000) /*!< Bit 2 */ + +#define ADC_CR2_JEXTTRIG ((uint32_t)0x00008000) /*!< External Trigger Conversion mode for injected channels */ + +#define ADC_CR2_EXTSEL ((uint32_t)0x000E0000) /*!< EXTSEL[2:0] bits (External Event Select for regular group) */ +#define ADC_CR2_EXTSEL_0 ((uint32_t)0x00020000) /*!< Bit 0 */ +#define ADC_CR2_EXTSEL_1 ((uint32_t)0x00040000) /*!< Bit 1 */ +#define ADC_CR2_EXTSEL_2 ((uint32_t)0x00080000) /*!< Bit 2 */ + +#define ADC_CR2_EXTTRIG ((uint32_t)0x00100000) /*!< External Trigger Conversion mode for regular channels */ +#define ADC_CR2_JSWSTART ((uint32_t)0x00200000) /*!< Start Conversion of injected channels */ +#define ADC_CR2_SWSTART ((uint32_t)0x00400000) /*!< Start Conversion of regular channels */ +#define ADC_CR2_TSVREFE ((uint32_t)0x00800000) /*!< Temperature Sensor and VREFINT Enable */ + +/****************** Bit definition for ADC_SMPR1 register *******************/ +#define ADC_SMPR1_SMP10 ((uint32_t)0x00000007) /*!< SMP10[2:0] bits (Channel 10 Sample time selection) */ +#define ADC_SMPR1_SMP10_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define ADC_SMPR1_SMP10_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define ADC_SMPR1_SMP10_2 ((uint32_t)0x00000004) /*!< Bit 2 */ + +#define ADC_SMPR1_SMP11 ((uint32_t)0x00000038) /*!< SMP11[2:0] bits (Channel 11 Sample time selection) */ +#define ADC_SMPR1_SMP11_0 ((uint32_t)0x00000008) /*!< Bit 0 */ +#define ADC_SMPR1_SMP11_1 ((uint32_t)0x00000010) /*!< Bit 1 */ +#define ADC_SMPR1_SMP11_2 ((uint32_t)0x00000020) /*!< Bit 2 */ + +#define ADC_SMPR1_SMP12 ((uint32_t)0x000001C0) /*!< SMP12[2:0] bits (Channel 12 Sample time selection) */ +#define ADC_SMPR1_SMP12_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define ADC_SMPR1_SMP12_1 ((uint32_t)0x00000080) /*!< Bit 1 */ +#define ADC_SMPR1_SMP12_2 ((uint32_t)0x00000100) /*!< Bit 2 */ + +#define ADC_SMPR1_SMP13 ((uint32_t)0x00000E00) /*!< SMP13[2:0] bits (Channel 13 Sample time selection) */ +#define ADC_SMPR1_SMP13_0 ((uint32_t)0x00000200) /*!< Bit 0 */ +#define ADC_SMPR1_SMP13_1 ((uint32_t)0x00000400) /*!< Bit 1 */ +#define ADC_SMPR1_SMP13_2 ((uint32_t)0x00000800) /*!< Bit 2 */ + +#define ADC_SMPR1_SMP14 ((uint32_t)0x00007000) /*!< SMP14[2:0] bits (Channel 14 Sample time selection) */ +#define ADC_SMPR1_SMP14_0 ((uint32_t)0x00001000) /*!< Bit 0 */ +#define ADC_SMPR1_SMP14_1 ((uint32_t)0x00002000) /*!< Bit 1 */ +#define ADC_SMPR1_SMP14_2 ((uint32_t)0x00004000) /*!< Bit 2 */ + +#define ADC_SMPR1_SMP15 ((uint32_t)0x00038000) /*!< SMP15[2:0] bits (Channel 15 Sample time selection) */ +#define ADC_SMPR1_SMP15_0 ((uint32_t)0x00008000) /*!< Bit 0 */ +#define ADC_SMPR1_SMP15_1 ((uint32_t)0x00010000) /*!< Bit 1 */ +#define ADC_SMPR1_SMP15_2 ((uint32_t)0x00020000) /*!< Bit 2 */ + +#define ADC_SMPR1_SMP16 ((uint32_t)0x001C0000) /*!< SMP16[2:0] bits (Channel 16 Sample time selection) */ +#define ADC_SMPR1_SMP16_0 ((uint32_t)0x00040000) /*!< Bit 0 */ +#define ADC_SMPR1_SMP16_1 ((uint32_t)0x00080000) /*!< Bit 1 */ +#define ADC_SMPR1_SMP16_2 ((uint32_t)0x00100000) /*!< Bit 2 */ + +#define ADC_SMPR1_SMP17 ((uint32_t)0x00E00000) /*!< SMP17[2:0] bits (Channel 17 Sample time selection) */ +#define ADC_SMPR1_SMP17_0 ((uint32_t)0x00200000) /*!< Bit 0 */ +#define ADC_SMPR1_SMP17_1 ((uint32_t)0x00400000) /*!< Bit 1 */ +#define ADC_SMPR1_SMP17_2 ((uint32_t)0x00800000) /*!< Bit 2 */ + +/****************** Bit definition for ADC_SMPR2 register *******************/ +#define ADC_SMPR2_SMP0 ((uint32_t)0x00000007) /*!< SMP0[2:0] bits (Channel 0 Sample time selection) */ +#define ADC_SMPR2_SMP0_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define ADC_SMPR2_SMP0_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define ADC_SMPR2_SMP0_2 ((uint32_t)0x00000004) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP1 ((uint32_t)0x00000038) /*!< SMP1[2:0] bits (Channel 1 Sample time selection) */ +#define ADC_SMPR2_SMP1_0 ((uint32_t)0x00000008) /*!< Bit 0 */ +#define ADC_SMPR2_SMP1_1 ((uint32_t)0x00000010) /*!< Bit 1 */ +#define ADC_SMPR2_SMP1_2 ((uint32_t)0x00000020) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP2 ((uint32_t)0x000001C0) /*!< SMP2[2:0] bits (Channel 2 Sample time selection) */ +#define ADC_SMPR2_SMP2_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define ADC_SMPR2_SMP2_1 ((uint32_t)0x00000080) /*!< Bit 1 */ +#define ADC_SMPR2_SMP2_2 ((uint32_t)0x00000100) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP3 ((uint32_t)0x00000E00) /*!< SMP3[2:0] bits (Channel 3 Sample time selection) */ +#define ADC_SMPR2_SMP3_0 ((uint32_t)0x00000200) /*!< Bit 0 */ +#define ADC_SMPR2_SMP3_1 ((uint32_t)0x00000400) /*!< Bit 1 */ +#define ADC_SMPR2_SMP3_2 ((uint32_t)0x00000800) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP4 ((uint32_t)0x00007000) /*!< SMP4[2:0] bits (Channel 4 Sample time selection) */ +#define ADC_SMPR2_SMP4_0 ((uint32_t)0x00001000) /*!< Bit 0 */ +#define ADC_SMPR2_SMP4_1 ((uint32_t)0x00002000) /*!< Bit 1 */ +#define ADC_SMPR2_SMP4_2 ((uint32_t)0x00004000) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP5 ((uint32_t)0x00038000) /*!< SMP5[2:0] bits (Channel 5 Sample time selection) */ +#define ADC_SMPR2_SMP5_0 ((uint32_t)0x00008000) /*!< Bit 0 */ +#define ADC_SMPR2_SMP5_1 ((uint32_t)0x00010000) /*!< Bit 1 */ +#define ADC_SMPR2_SMP5_2 ((uint32_t)0x00020000) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP6 ((uint32_t)0x001C0000) /*!< SMP6[2:0] bits (Channel 6 Sample time selection) */ +#define ADC_SMPR2_SMP6_0 ((uint32_t)0x00040000) /*!< Bit 0 */ +#define ADC_SMPR2_SMP6_1 ((uint32_t)0x00080000) /*!< Bit 1 */ +#define ADC_SMPR2_SMP6_2 ((uint32_t)0x00100000) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP7 ((uint32_t)0x00E00000) /*!< SMP7[2:0] bits (Channel 7 Sample time selection) */ +#define ADC_SMPR2_SMP7_0 ((uint32_t)0x00200000) /*!< Bit 0 */ +#define ADC_SMPR2_SMP7_1 ((uint32_t)0x00400000) /*!< Bit 1 */ +#define ADC_SMPR2_SMP7_2 ((uint32_t)0x00800000) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP8 ((uint32_t)0x07000000) /*!< SMP8[2:0] bits (Channel 8 Sample time selection) */ +#define ADC_SMPR2_SMP8_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define ADC_SMPR2_SMP8_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define ADC_SMPR2_SMP8_2 ((uint32_t)0x04000000) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP9 ((uint32_t)0x38000000) /*!< SMP9[2:0] bits (Channel 9 Sample time selection) */ +#define ADC_SMPR2_SMP9_0 ((uint32_t)0x08000000) /*!< Bit 0 */ +#define ADC_SMPR2_SMP9_1 ((uint32_t)0x10000000) /*!< Bit 1 */ +#define ADC_SMPR2_SMP9_2 ((uint32_t)0x20000000) /*!< Bit 2 */ + +/****************** Bit definition for ADC_JOFR1 register *******************/ +#define ADC_JOFR1_JOFFSET1 ((uint16_t)0x0FFF) /*!< Data offset for injected channel 1 */ + +/****************** Bit definition for ADC_JOFR2 register *******************/ +#define ADC_JOFR2_JOFFSET2 ((uint16_t)0x0FFF) /*!< Data offset for injected channel 2 */ + +/****************** Bit definition for ADC_JOFR3 register *******************/ +#define ADC_JOFR3_JOFFSET3 ((uint16_t)0x0FFF) /*!< Data offset for injected channel 3 */ + +/****************** Bit definition for ADC_JOFR4 register *******************/ +#define ADC_JOFR4_JOFFSET4 ((uint16_t)0x0FFF) /*!< Data offset for injected channel 4 */ + +/******************* Bit definition for ADC_HTR register ********************/ +#define ADC_HTR_HT ((uint16_t)0x0FFF) /*!< Analog watchdog high threshold */ + +/******************* Bit definition for ADC_LTR register ********************/ +#define ADC_LTR_LT ((uint16_t)0x0FFF) /*!< Analog watchdog low threshold */ + +/******************* Bit definition for ADC_SQR1 register *******************/ +#define ADC_SQR1_SQ13 ((uint32_t)0x0000001F) /*!< SQ13[4:0] bits (13th conversion in regular sequence) */ +#define ADC_SQR1_SQ13_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define ADC_SQR1_SQ13_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define ADC_SQR1_SQ13_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define ADC_SQR1_SQ13_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define ADC_SQR1_SQ13_4 ((uint32_t)0x00000010) /*!< Bit 4 */ + +#define ADC_SQR1_SQ14 ((uint32_t)0x000003E0) /*!< SQ14[4:0] bits (14th conversion in regular sequence) */ +#define ADC_SQR1_SQ14_0 ((uint32_t)0x00000020) /*!< Bit 0 */ +#define ADC_SQR1_SQ14_1 ((uint32_t)0x00000040) /*!< Bit 1 */ +#define ADC_SQR1_SQ14_2 ((uint32_t)0x00000080) /*!< Bit 2 */ +#define ADC_SQR1_SQ14_3 ((uint32_t)0x00000100) /*!< Bit 3 */ +#define ADC_SQR1_SQ14_4 ((uint32_t)0x00000200) /*!< Bit 4 */ + +#define ADC_SQR1_SQ15 ((uint32_t)0x00007C00) /*!< SQ15[4:0] bits (15th conversion in regular sequence) */ +#define ADC_SQR1_SQ15_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define ADC_SQR1_SQ15_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define ADC_SQR1_SQ15_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define ADC_SQR1_SQ15_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define ADC_SQR1_SQ15_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define ADC_SQR1_SQ16 ((uint32_t)0x000F8000) /*!< SQ16[4:0] bits (16th conversion in regular sequence) */ +#define ADC_SQR1_SQ16_0 ((uint32_t)0x00008000) /*!< Bit 0 */ +#define ADC_SQR1_SQ16_1 ((uint32_t)0x00010000) /*!< Bit 1 */ +#define ADC_SQR1_SQ16_2 ((uint32_t)0x00020000) /*!< Bit 2 */ +#define ADC_SQR1_SQ16_3 ((uint32_t)0x00040000) /*!< Bit 3 */ +#define ADC_SQR1_SQ16_4 ((uint32_t)0x00080000) /*!< Bit 4 */ + +#define ADC_SQR1_L ((uint32_t)0x00F00000) /*!< L[3:0] bits (Regular channel sequence length) */ +#define ADC_SQR1_L_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define ADC_SQR1_L_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define ADC_SQR1_L_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define ADC_SQR1_L_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +/******************* Bit definition for ADC_SQR2 register *******************/ +#define ADC_SQR2_SQ7 ((uint32_t)0x0000001F) /*!< SQ7[4:0] bits (7th conversion in regular sequence) */ +#define ADC_SQR2_SQ7_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define ADC_SQR2_SQ7_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define ADC_SQR2_SQ7_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define ADC_SQR2_SQ7_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define ADC_SQR2_SQ7_4 ((uint32_t)0x00000010) /*!< Bit 4 */ + +#define ADC_SQR2_SQ8 ((uint32_t)0x000003E0) /*!< SQ8[4:0] bits (8th conversion in regular sequence) */ +#define ADC_SQR2_SQ8_0 ((uint32_t)0x00000020) /*!< Bit 0 */ +#define ADC_SQR2_SQ8_1 ((uint32_t)0x00000040) /*!< Bit 1 */ +#define ADC_SQR2_SQ8_2 ((uint32_t)0x00000080) /*!< Bit 2 */ +#define ADC_SQR2_SQ8_3 ((uint32_t)0x00000100) /*!< Bit 3 */ +#define ADC_SQR2_SQ8_4 ((uint32_t)0x00000200) /*!< Bit 4 */ + +#define ADC_SQR2_SQ9 ((uint32_t)0x00007C00) /*!< SQ9[4:0] bits (9th conversion in regular sequence) */ +#define ADC_SQR2_SQ9_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define ADC_SQR2_SQ9_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define ADC_SQR2_SQ9_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define ADC_SQR2_SQ9_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define ADC_SQR2_SQ9_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define ADC_SQR2_SQ10 ((uint32_t)0x000F8000) /*!< SQ10[4:0] bits (10th conversion in regular sequence) */ +#define ADC_SQR2_SQ10_0 ((uint32_t)0x00008000) /*!< Bit 0 */ +#define ADC_SQR2_SQ10_1 ((uint32_t)0x00010000) /*!< Bit 1 */ +#define ADC_SQR2_SQ10_2 ((uint32_t)0x00020000) /*!< Bit 2 */ +#define ADC_SQR2_SQ10_3 ((uint32_t)0x00040000) /*!< Bit 3 */ +#define ADC_SQR2_SQ10_4 ((uint32_t)0x00080000) /*!< Bit 4 */ + +#define ADC_SQR2_SQ11 ((uint32_t)0x01F00000) /*!< SQ11[4:0] bits (11th conversion in regular sequence) */ +#define ADC_SQR2_SQ11_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define ADC_SQR2_SQ11_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define ADC_SQR2_SQ11_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define ADC_SQR2_SQ11_3 ((uint32_t)0x00800000) /*!< Bit 3 */ +#define ADC_SQR2_SQ11_4 ((uint32_t)0x01000000) /*!< Bit 4 */ + +#define ADC_SQR2_SQ12 ((uint32_t)0x3E000000) /*!< SQ12[4:0] bits (12th conversion in regular sequence) */ +#define ADC_SQR2_SQ12_0 ((uint32_t)0x02000000) /*!< Bit 0 */ +#define ADC_SQR2_SQ12_1 ((uint32_t)0x04000000) /*!< Bit 1 */ +#define ADC_SQR2_SQ12_2 ((uint32_t)0x08000000) /*!< Bit 2 */ +#define ADC_SQR2_SQ12_3 ((uint32_t)0x10000000) /*!< Bit 3 */ +#define ADC_SQR2_SQ12_4 ((uint32_t)0x20000000) /*!< Bit 4 */ + +/******************* Bit definition for ADC_SQR3 register *******************/ +#define ADC_SQR3_SQ1 ((uint32_t)0x0000001F) /*!< SQ1[4:0] bits (1st conversion in regular sequence) */ +#define ADC_SQR3_SQ1_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define ADC_SQR3_SQ1_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define ADC_SQR3_SQ1_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define ADC_SQR3_SQ1_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define ADC_SQR3_SQ1_4 ((uint32_t)0x00000010) /*!< Bit 4 */ + +#define ADC_SQR3_SQ2 ((uint32_t)0x000003E0) /*!< SQ2[4:0] bits (2nd conversion in regular sequence) */ +#define ADC_SQR3_SQ2_0 ((uint32_t)0x00000020) /*!< Bit 0 */ +#define ADC_SQR3_SQ2_1 ((uint32_t)0x00000040) /*!< Bit 1 */ +#define ADC_SQR3_SQ2_2 ((uint32_t)0x00000080) /*!< Bit 2 */ +#define ADC_SQR3_SQ2_3 ((uint32_t)0x00000100) /*!< Bit 3 */ +#define ADC_SQR3_SQ2_4 ((uint32_t)0x00000200) /*!< Bit 4 */ + +#define ADC_SQR3_SQ3 ((uint32_t)0x00007C00) /*!< SQ3[4:0] bits (3rd conversion in regular sequence) */ +#define ADC_SQR3_SQ3_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define ADC_SQR3_SQ3_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define ADC_SQR3_SQ3_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define ADC_SQR3_SQ3_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define ADC_SQR3_SQ3_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define ADC_SQR3_SQ4 ((uint32_t)0x000F8000) /*!< SQ4[4:0] bits (4th conversion in regular sequence) */ +#define ADC_SQR3_SQ4_0 ((uint32_t)0x00008000) /*!< Bit 0 */ +#define ADC_SQR3_SQ4_1 ((uint32_t)0x00010000) /*!< Bit 1 */ +#define ADC_SQR3_SQ4_2 ((uint32_t)0x00020000) /*!< Bit 2 */ +#define ADC_SQR3_SQ4_3 ((uint32_t)0x00040000) /*!< Bit 3 */ +#define ADC_SQR3_SQ4_4 ((uint32_t)0x00080000) /*!< Bit 4 */ + +#define ADC_SQR3_SQ5 ((uint32_t)0x01F00000) /*!< SQ5[4:0] bits (5th conversion in regular sequence) */ +#define ADC_SQR3_SQ5_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define ADC_SQR3_SQ5_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define ADC_SQR3_SQ5_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define ADC_SQR3_SQ5_3 ((uint32_t)0x00800000) /*!< Bit 3 */ +#define ADC_SQR3_SQ5_4 ((uint32_t)0x01000000) /*!< Bit 4 */ + +#define ADC_SQR3_SQ6 ((uint32_t)0x3E000000) /*!< SQ6[4:0] bits (6th conversion in regular sequence) */ +#define ADC_SQR3_SQ6_0 ((uint32_t)0x02000000) /*!< Bit 0 */ +#define ADC_SQR3_SQ6_1 ((uint32_t)0x04000000) /*!< Bit 1 */ +#define ADC_SQR3_SQ6_2 ((uint32_t)0x08000000) /*!< Bit 2 */ +#define ADC_SQR3_SQ6_3 ((uint32_t)0x10000000) /*!< Bit 3 */ +#define ADC_SQR3_SQ6_4 ((uint32_t)0x20000000) /*!< Bit 4 */ + +/******************* Bit definition for ADC_JSQR register *******************/ +#define ADC_JSQR_JSQ1 ((uint32_t)0x0000001F) /*!< JSQ1[4:0] bits (1st conversion in injected sequence) */ +#define ADC_JSQR_JSQ1_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define ADC_JSQR_JSQ1_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define ADC_JSQR_JSQ1_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define ADC_JSQR_JSQ1_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define ADC_JSQR_JSQ1_4 ((uint32_t)0x00000010) /*!< Bit 4 */ + +#define ADC_JSQR_JSQ2 ((uint32_t)0x000003E0) /*!< JSQ2[4:0] bits (2nd conversion in injected sequence) */ +#define ADC_JSQR_JSQ2_0 ((uint32_t)0x00000020) /*!< Bit 0 */ +#define ADC_JSQR_JSQ2_1 ((uint32_t)0x00000040) /*!< Bit 1 */ +#define ADC_JSQR_JSQ2_2 ((uint32_t)0x00000080) /*!< Bit 2 */ +#define ADC_JSQR_JSQ2_3 ((uint32_t)0x00000100) /*!< Bit 3 */ +#define ADC_JSQR_JSQ2_4 ((uint32_t)0x00000200) /*!< Bit 4 */ + +#define ADC_JSQR_JSQ3 ((uint32_t)0x00007C00) /*!< JSQ3[4:0] bits (3rd conversion in injected sequence) */ +#define ADC_JSQR_JSQ3_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define ADC_JSQR_JSQ3_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define ADC_JSQR_JSQ3_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define ADC_JSQR_JSQ3_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define ADC_JSQR_JSQ3_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define ADC_JSQR_JSQ4 ((uint32_t)0x000F8000) /*!< JSQ4[4:0] bits (4th conversion in injected sequence) */ +#define ADC_JSQR_JSQ4_0 ((uint32_t)0x00008000) /*!< Bit 0 */ +#define ADC_JSQR_JSQ4_1 ((uint32_t)0x00010000) /*!< Bit 1 */ +#define ADC_JSQR_JSQ4_2 ((uint32_t)0x00020000) /*!< Bit 2 */ +#define ADC_JSQR_JSQ4_3 ((uint32_t)0x00040000) /*!< Bit 3 */ +#define ADC_JSQR_JSQ4_4 ((uint32_t)0x00080000) /*!< Bit 4 */ + +#define ADC_JSQR_JL ((uint32_t)0x00300000) /*!< JL[1:0] bits (Injected Sequence length) */ +#define ADC_JSQR_JL_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define ADC_JSQR_JL_1 ((uint32_t)0x00200000) /*!< Bit 1 */ + +/******************* Bit definition for ADC_JDR1 register *******************/ +#define ADC_JDR1_JDATA ((uint16_t)0xFFFF) /*!< Injected data */ + +/******************* Bit definition for ADC_JDR2 register *******************/ +#define ADC_JDR2_JDATA ((uint16_t)0xFFFF) /*!< Injected data */ + +/******************* Bit definition for ADC_JDR3 register *******************/ +#define ADC_JDR3_JDATA ((uint16_t)0xFFFF) /*!< Injected data */ + +/******************* Bit definition for ADC_JDR4 register *******************/ +#define ADC_JDR4_JDATA ((uint16_t)0xFFFF) /*!< Injected data */ + +/******************** Bit definition for ADC_DR register ********************/ +#define ADC_DR_DATA ((uint32_t)0x0000FFFF) /*!< Regular data */ +#define ADC_DR_ADC2DATA ((uint32_t)0xFFFF0000) /*!< ADC2 data */ + +/******************************************************************************/ +/* */ +/* Digital to Analog Converter */ +/* */ +/******************************************************************************/ + +/******************** Bit definition for DAC_CR register ********************/ +#define DAC_CR_EN1 ((uint32_t)0x00000001) /*!< DAC channel1 enable */ +#define DAC_CR_BOFF1 ((uint32_t)0x00000002) /*!< DAC channel1 output buffer disable */ +#define DAC_CR_TEN1 ((uint32_t)0x00000004) /*!< DAC channel1 Trigger enable */ + +#define DAC_CR_TSEL1 ((uint32_t)0x00000038) /*!< TSEL1[2:0] (DAC channel1 Trigger selection) */ +#define DAC_CR_TSEL1_0 ((uint32_t)0x00000008) /*!< Bit 0 */ +#define DAC_CR_TSEL1_1 ((uint32_t)0x00000010) /*!< Bit 1 */ +#define DAC_CR_TSEL1_2 ((uint32_t)0x00000020) /*!< Bit 2 */ + +#define DAC_CR_WAVE1 ((uint32_t)0x000000C0) /*!< WAVE1[1:0] (DAC channel1 noise/triangle wave generation enable) */ +#define DAC_CR_WAVE1_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define DAC_CR_WAVE1_1 ((uint32_t)0x00000080) /*!< Bit 1 */ + +#define DAC_CR_MAMP1 ((uint32_t)0x00000F00) /*!< MAMP1[3:0] (DAC channel1 Mask/Amplitude selector) */ +#define DAC_CR_MAMP1_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define DAC_CR_MAMP1_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define DAC_CR_MAMP1_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define DAC_CR_MAMP1_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define DAC_CR_DMAEN1 ((uint32_t)0x00001000) /*!< DAC channel1 DMA enable */ +#define DAC_CR_EN2 ((uint32_t)0x00010000) /*!< DAC channel2 enable */ +#define DAC_CR_BOFF2 ((uint32_t)0x00020000) /*!< DAC channel2 output buffer disable */ +#define DAC_CR_TEN2 ((uint32_t)0x00040000) /*!< DAC channel2 Trigger enable */ + +#define DAC_CR_TSEL2 ((uint32_t)0x00380000) /*!< TSEL2[2:0] (DAC channel2 Trigger selection) */ +#define DAC_CR_TSEL2_0 ((uint32_t)0x00080000) /*!< Bit 0 */ +#define DAC_CR_TSEL2_1 ((uint32_t)0x00100000) /*!< Bit 1 */ +#define DAC_CR_TSEL2_2 ((uint32_t)0x00200000) /*!< Bit 2 */ + +#define DAC_CR_WAVE2 ((uint32_t)0x00C00000) /*!< WAVE2[1:0] (DAC channel2 noise/triangle wave generation enable) */ +#define DAC_CR_WAVE2_0 ((uint32_t)0x00400000) /*!< Bit 0 */ +#define DAC_CR_WAVE2_1 ((uint32_t)0x00800000) /*!< Bit 1 */ + +#define DAC_CR_MAMP2 ((uint32_t)0x0F000000) /*!< MAMP2[3:0] (DAC channel2 Mask/Amplitude selector) */ +#define DAC_CR_MAMP2_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define DAC_CR_MAMP2_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define DAC_CR_MAMP2_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define DAC_CR_MAMP2_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define DAC_CR_DMAEN2 ((uint32_t)0x10000000) /*!< DAC channel2 DMA enabled */ + +/***************** Bit definition for DAC_SWTRIGR register ******************/ +#define DAC_SWTRIGR_SWTRIG1 ((uint8_t)0x01) /*!< DAC channel1 software trigger */ +#define DAC_SWTRIGR_SWTRIG2 ((uint8_t)0x02) /*!< DAC channel2 software trigger */ + +/***************** Bit definition for DAC_DHR12R1 register ******************/ +#define DAC_DHR12R1_DACC1DHR ((uint16_t)0x0FFF) /*!< DAC channel1 12-bit Right aligned data */ + +/***************** Bit definition for DAC_DHR12L1 register ******************/ +#define DAC_DHR12L1_DACC1DHR ((uint16_t)0xFFF0) /*!< DAC channel1 12-bit Left aligned data */ + +/****************** Bit definition for DAC_DHR8R1 register ******************/ +#define DAC_DHR8R1_DACC1DHR ((uint8_t)0xFF) /*!< DAC channel1 8-bit Right aligned data */ + +/***************** Bit definition for DAC_DHR12R2 register ******************/ +#define DAC_DHR12R2_DACC2DHR ((uint16_t)0x0FFF) /*!< DAC channel2 12-bit Right aligned data */ + +/***************** Bit definition for DAC_DHR12L2 register ******************/ +#define DAC_DHR12L2_DACC2DHR ((uint16_t)0xFFF0) /*!< DAC channel2 12-bit Left aligned data */ + +/****************** Bit definition for DAC_DHR8R2 register ******************/ +#define DAC_DHR8R2_DACC2DHR ((uint8_t)0xFF) /*!< DAC channel2 8-bit Right aligned data */ + +/***************** Bit definition for DAC_DHR12RD register ******************/ +#define DAC_DHR12RD_DACC1DHR ((uint32_t)0x00000FFF) /*!< DAC channel1 12-bit Right aligned data */ +#define DAC_DHR12RD_DACC2DHR ((uint32_t)0x0FFF0000) /*!< DAC channel2 12-bit Right aligned data */ + +/***************** Bit definition for DAC_DHR12LD register ******************/ +#define DAC_DHR12LD_DACC1DHR ((uint32_t)0x0000FFF0) /*!< DAC channel1 12-bit Left aligned data */ +#define DAC_DHR12LD_DACC2DHR ((uint32_t)0xFFF00000) /*!< DAC channel2 12-bit Left aligned data */ + +/****************** Bit definition for DAC_DHR8RD register ******************/ +#define DAC_DHR8RD_DACC1DHR ((uint16_t)0x00FF) /*!< DAC channel1 8-bit Right aligned data */ +#define DAC_DHR8RD_DACC2DHR ((uint16_t)0xFF00) /*!< DAC channel2 8-bit Right aligned data */ + +/******************* Bit definition for DAC_DOR1 register *******************/ +#define DAC_DOR1_DACC1DOR ((uint16_t)0x0FFF) /*!< DAC channel1 data output */ + +/******************* Bit definition for DAC_DOR2 register *******************/ +#define DAC_DOR2_DACC2DOR ((uint16_t)0x0FFF) /*!< DAC channel2 data output */ + +/******************** Bit definition for DAC_SR register ********************/ +#define DAC_SR_DMAUDR1 ((uint32_t)0x00002000) /*!< DAC channel1 DMA underrun flag */ +#define DAC_SR_DMAUDR2 ((uint32_t)0x20000000) /*!< DAC channel2 DMA underrun flag */ + +/******************************************************************************/ +/* */ +/* CEC */ +/* */ +/******************************************************************************/ +/******************** Bit definition for CEC_CFGR register ******************/ +#define CEC_CFGR_PE ((uint16_t)0x0001) /*!< Peripheral Enable */ +#define CEC_CFGR_IE ((uint16_t)0x0002) /*!< Interrupt Enable */ +#define CEC_CFGR_BTEM ((uint16_t)0x0004) /*!< Bit Timing Error Mode */ +#define CEC_CFGR_BPEM ((uint16_t)0x0008) /*!< Bit Period Error Mode */ + +/******************** Bit definition for CEC_OAR register ******************/ +#define CEC_OAR_OA ((uint16_t)0x000F) /*!< OA[3:0]: Own Address */ +#define CEC_OAR_OA_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define CEC_OAR_OA_1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define CEC_OAR_OA_2 ((uint16_t)0x0004) /*!< Bit 2 */ +#define CEC_OAR_OA_3 ((uint16_t)0x0008) /*!< Bit 3 */ + +/******************** Bit definition for CEC_PRES register ******************/ +#define CEC_PRES_PRES ((uint16_t)0x3FFF) /*!< Prescaler Counter Value */ + +/******************** Bit definition for CEC_ESR register ******************/ +#define CEC_ESR_BTE ((uint16_t)0x0001) /*!< Bit Timing Error */ +#define CEC_ESR_BPE ((uint16_t)0x0002) /*!< Bit Period Error */ +#define CEC_ESR_RBTFE ((uint16_t)0x0004) /*!< Rx Block Transfer Finished Error */ +#define CEC_ESR_SBE ((uint16_t)0x0008) /*!< Start Bit Error */ +#define CEC_ESR_ACKE ((uint16_t)0x0010) /*!< Block Acknowledge Error */ +#define CEC_ESR_LINE ((uint16_t)0x0020) /*!< Line Error */ +#define CEC_ESR_TBTFE ((uint16_t)0x0040) /*!< Tx Block Transfer Finished Error */ + +/******************** Bit definition for CEC_CSR register ******************/ +#define CEC_CSR_TSOM ((uint16_t)0x0001) /*!< Tx Start Of Message */ +#define CEC_CSR_TEOM ((uint16_t)0x0002) /*!< Tx End Of Message */ +#define CEC_CSR_TERR ((uint16_t)0x0004) /*!< Tx Error */ +#define CEC_CSR_TBTRF ((uint16_t)0x0008) /*!< Tx Byte Transfer Request or Block Transfer Finished */ +#define CEC_CSR_RSOM ((uint16_t)0x0010) /*!< Rx Start Of Message */ +#define CEC_CSR_REOM ((uint16_t)0x0020) /*!< Rx End Of Message */ +#define CEC_CSR_RERR ((uint16_t)0x0040) /*!< Rx Error */ +#define CEC_CSR_RBTF ((uint16_t)0x0080) /*!< Rx Block Transfer Finished */ + +/******************** Bit definition for CEC_TXD register ******************/ +#define CEC_TXD_TXD ((uint16_t)0x00FF) /*!< Tx Data register */ + +/******************** Bit definition for CEC_RXD register ******************/ +#define CEC_RXD_RXD ((uint16_t)0x00FF) /*!< Rx Data register */ + +/******************************************************************************/ +/* */ +/* TIM */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for TIM_CR1 register ********************/ +#define TIM_CR1_CEN ((uint16_t)0x0001) /*!< Counter enable */ +#define TIM_CR1_UDIS ((uint16_t)0x0002) /*!< Update disable */ +#define TIM_CR1_URS ((uint16_t)0x0004) /*!< Update request source */ +#define TIM_CR1_OPM ((uint16_t)0x0008) /*!< One pulse mode */ +#define TIM_CR1_DIR ((uint16_t)0x0010) /*!< Direction */ + +#define TIM_CR1_CMS ((uint16_t)0x0060) /*!< CMS[1:0] bits (Center-aligned mode selection) */ +#define TIM_CR1_CMS_0 ((uint16_t)0x0020) /*!< Bit 0 */ +#define TIM_CR1_CMS_1 ((uint16_t)0x0040) /*!< Bit 1 */ + +#define TIM_CR1_ARPE ((uint16_t)0x0080) /*!< Auto-reload preload enable */ + +#define TIM_CR1_CKD ((uint16_t)0x0300) /*!< CKD[1:0] bits (clock division) */ +#define TIM_CR1_CKD_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define TIM_CR1_CKD_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +/******************* Bit definition for TIM_CR2 register ********************/ +#define TIM_CR2_CCPC ((uint16_t)0x0001) /*!< Capture/Compare Preloaded Control */ +#define TIM_CR2_CCUS ((uint16_t)0x0004) /*!< Capture/Compare Control Update Selection */ +#define TIM_CR2_CCDS ((uint16_t)0x0008) /*!< Capture/Compare DMA Selection */ + +#define TIM_CR2_MMS ((uint16_t)0x0070) /*!< MMS[2:0] bits (Master Mode Selection) */ +#define TIM_CR2_MMS_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define TIM_CR2_MMS_1 ((uint16_t)0x0020) /*!< Bit 1 */ +#define TIM_CR2_MMS_2 ((uint16_t)0x0040) /*!< Bit 2 */ + +#define TIM_CR2_TI1S ((uint16_t)0x0080) /*!< TI1 Selection */ +#define TIM_CR2_OIS1 ((uint16_t)0x0100) /*!< Output Idle state 1 (OC1 output) */ +#define TIM_CR2_OIS1N ((uint16_t)0x0200) /*!< Output Idle state 1 (OC1N output) */ +#define TIM_CR2_OIS2 ((uint16_t)0x0400) /*!< Output Idle state 2 (OC2 output) */ +#define TIM_CR2_OIS2N ((uint16_t)0x0800) /*!< Output Idle state 2 (OC2N output) */ +#define TIM_CR2_OIS3 ((uint16_t)0x1000) /*!< Output Idle state 3 (OC3 output) */ +#define TIM_CR2_OIS3N ((uint16_t)0x2000) /*!< Output Idle state 3 (OC3N output) */ +#define TIM_CR2_OIS4 ((uint16_t)0x4000) /*!< Output Idle state 4 (OC4 output) */ + +/******************* Bit definition for TIM_SMCR register *******************/ +#define TIM_SMCR_SMS ((uint16_t)0x0007) /*!< SMS[2:0] bits (Slave mode selection) */ +#define TIM_SMCR_SMS_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define TIM_SMCR_SMS_1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define TIM_SMCR_SMS_2 ((uint16_t)0x0004) /*!< Bit 2 */ + +#define TIM_SMCR_TS ((uint16_t)0x0070) /*!< TS[2:0] bits (Trigger selection) */ +#define TIM_SMCR_TS_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define TIM_SMCR_TS_1 ((uint16_t)0x0020) /*!< Bit 1 */ +#define TIM_SMCR_TS_2 ((uint16_t)0x0040) /*!< Bit 2 */ + +#define TIM_SMCR_MSM ((uint16_t)0x0080) /*!< Master/slave mode */ + +#define TIM_SMCR_ETF ((uint16_t)0x0F00) /*!< ETF[3:0] bits (External trigger filter) */ +#define TIM_SMCR_ETF_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define TIM_SMCR_ETF_1 ((uint16_t)0x0200) /*!< Bit 1 */ +#define TIM_SMCR_ETF_2 ((uint16_t)0x0400) /*!< Bit 2 */ +#define TIM_SMCR_ETF_3 ((uint16_t)0x0800) /*!< Bit 3 */ + +#define TIM_SMCR_ETPS ((uint16_t)0x3000) /*!< ETPS[1:0] bits (External trigger prescaler) */ +#define TIM_SMCR_ETPS_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define TIM_SMCR_ETPS_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define TIM_SMCR_ECE ((uint16_t)0x4000) /*!< External clock enable */ +#define TIM_SMCR_ETP ((uint16_t)0x8000) /*!< External trigger polarity */ + +/******************* Bit definition for TIM_DIER register *******************/ +#define TIM_DIER_UIE ((uint16_t)0x0001) /*!< Update interrupt enable */ +#define TIM_DIER_CC1IE ((uint16_t)0x0002) /*!< Capture/Compare 1 interrupt enable */ +#define TIM_DIER_CC2IE ((uint16_t)0x0004) /*!< Capture/Compare 2 interrupt enable */ +#define TIM_DIER_CC3IE ((uint16_t)0x0008) /*!< Capture/Compare 3 interrupt enable */ +#define TIM_DIER_CC4IE ((uint16_t)0x0010) /*!< Capture/Compare 4 interrupt enable */ +#define TIM_DIER_COMIE ((uint16_t)0x0020) /*!< COM interrupt enable */ +#define TIM_DIER_TIE ((uint16_t)0x0040) /*!< Trigger interrupt enable */ +#define TIM_DIER_BIE ((uint16_t)0x0080) /*!< Break interrupt enable */ +#define TIM_DIER_UDE ((uint16_t)0x0100) /*!< Update DMA request enable */ +#define TIM_DIER_CC1DE ((uint16_t)0x0200) /*!< Capture/Compare 1 DMA request enable */ +#define TIM_DIER_CC2DE ((uint16_t)0x0400) /*!< Capture/Compare 2 DMA request enable */ +#define TIM_DIER_CC3DE ((uint16_t)0x0800) /*!< Capture/Compare 3 DMA request enable */ +#define TIM_DIER_CC4DE ((uint16_t)0x1000) /*!< Capture/Compare 4 DMA request enable */ +#define TIM_DIER_COMDE ((uint16_t)0x2000) /*!< COM DMA request enable */ +#define TIM_DIER_TDE ((uint16_t)0x4000) /*!< Trigger DMA request enable */ + +/******************** Bit definition for TIM_SR register ********************/ +#define TIM_SR_UIF ((uint16_t)0x0001) /*!< Update interrupt Flag */ +#define TIM_SR_CC1IF ((uint16_t)0x0002) /*!< Capture/Compare 1 interrupt Flag */ +#define TIM_SR_CC2IF ((uint16_t)0x0004) /*!< Capture/Compare 2 interrupt Flag */ +#define TIM_SR_CC3IF ((uint16_t)0x0008) /*!< Capture/Compare 3 interrupt Flag */ +#define TIM_SR_CC4IF ((uint16_t)0x0010) /*!< Capture/Compare 4 interrupt Flag */ +#define TIM_SR_COMIF ((uint16_t)0x0020) /*!< COM interrupt Flag */ +#define TIM_SR_TIF ((uint16_t)0x0040) /*!< Trigger interrupt Flag */ +#define TIM_SR_BIF ((uint16_t)0x0080) /*!< Break interrupt Flag */ +#define TIM_SR_CC1OF ((uint16_t)0x0200) /*!< Capture/Compare 1 Overcapture Flag */ +#define TIM_SR_CC2OF ((uint16_t)0x0400) /*!< Capture/Compare 2 Overcapture Flag */ +#define TIM_SR_CC3OF ((uint16_t)0x0800) /*!< Capture/Compare 3 Overcapture Flag */ +#define TIM_SR_CC4OF ((uint16_t)0x1000) /*!< Capture/Compare 4 Overcapture Flag */ + +/******************* Bit definition for TIM_EGR register ********************/ +#define TIM_EGR_UG ((uint8_t)0x01) /*!< Update Generation */ +#define TIM_EGR_CC1G ((uint8_t)0x02) /*!< Capture/Compare 1 Generation */ +#define TIM_EGR_CC2G ((uint8_t)0x04) /*!< Capture/Compare 2 Generation */ +#define TIM_EGR_CC3G ((uint8_t)0x08) /*!< Capture/Compare 3 Generation */ +#define TIM_EGR_CC4G ((uint8_t)0x10) /*!< Capture/Compare 4 Generation */ +#define TIM_EGR_COMG ((uint8_t)0x20) /*!< Capture/Compare Control Update Generation */ +#define TIM_EGR_TG ((uint8_t)0x40) /*!< Trigger Generation */ +#define TIM_EGR_BG ((uint8_t)0x80) /*!< Break Generation */ + +/****************** Bit definition for TIM_CCMR1 register *******************/ +#define TIM_CCMR1_CC1S ((uint16_t)0x0003) /*!< CC1S[1:0] bits (Capture/Compare 1 Selection) */ +#define TIM_CCMR1_CC1S_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define TIM_CCMR1_CC1S_1 ((uint16_t)0x0002) /*!< Bit 1 */ + +#define TIM_CCMR1_OC1FE ((uint16_t)0x0004) /*!< Output Compare 1 Fast enable */ +#define TIM_CCMR1_OC1PE ((uint16_t)0x0008) /*!< Output Compare 1 Preload enable */ + +#define TIM_CCMR1_OC1M ((uint16_t)0x0070) /*!< OC1M[2:0] bits (Output Compare 1 Mode) */ +#define TIM_CCMR1_OC1M_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define TIM_CCMR1_OC1M_1 ((uint16_t)0x0020) /*!< Bit 1 */ +#define TIM_CCMR1_OC1M_2 ((uint16_t)0x0040) /*!< Bit 2 */ + +#define TIM_CCMR1_OC1CE ((uint16_t)0x0080) /*!< Output Compare 1Clear Enable */ + +#define TIM_CCMR1_CC2S ((uint16_t)0x0300) /*!< CC2S[1:0] bits (Capture/Compare 2 Selection) */ +#define TIM_CCMR1_CC2S_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define TIM_CCMR1_CC2S_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define TIM_CCMR1_OC2FE ((uint16_t)0x0400) /*!< Output Compare 2 Fast enable */ +#define TIM_CCMR1_OC2PE ((uint16_t)0x0800) /*!< Output Compare 2 Preload enable */ + +#define TIM_CCMR1_OC2M ((uint16_t)0x7000) /*!< OC2M[2:0] bits (Output Compare 2 Mode) */ +#define TIM_CCMR1_OC2M_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define TIM_CCMR1_OC2M_1 ((uint16_t)0x2000) /*!< Bit 1 */ +#define TIM_CCMR1_OC2M_2 ((uint16_t)0x4000) /*!< Bit 2 */ + +#define TIM_CCMR1_OC2CE ((uint16_t)0x8000) /*!< Output Compare 2 Clear Enable */ + +/*----------------------------------------------------------------------------*/ + +#define TIM_CCMR1_IC1PSC ((uint16_t)0x000C) /*!< IC1PSC[1:0] bits (Input Capture 1 Prescaler) */ +#define TIM_CCMR1_IC1PSC_0 ((uint16_t)0x0004) /*!< Bit 0 */ +#define TIM_CCMR1_IC1PSC_1 ((uint16_t)0x0008) /*!< Bit 1 */ + +#define TIM_CCMR1_IC1F ((uint16_t)0x00F0) /*!< IC1F[3:0] bits (Input Capture 1 Filter) */ +#define TIM_CCMR1_IC1F_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define TIM_CCMR1_IC1F_1 ((uint16_t)0x0020) /*!< Bit 1 */ +#define TIM_CCMR1_IC1F_2 ((uint16_t)0x0040) /*!< Bit 2 */ +#define TIM_CCMR1_IC1F_3 ((uint16_t)0x0080) /*!< Bit 3 */ + +#define TIM_CCMR1_IC2PSC ((uint16_t)0x0C00) /*!< IC2PSC[1:0] bits (Input Capture 2 Prescaler) */ +#define TIM_CCMR1_IC2PSC_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define TIM_CCMR1_IC2PSC_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define TIM_CCMR1_IC2F ((uint16_t)0xF000) /*!< IC2F[3:0] bits (Input Capture 2 Filter) */ +#define TIM_CCMR1_IC2F_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define TIM_CCMR1_IC2F_1 ((uint16_t)0x2000) /*!< Bit 1 */ +#define TIM_CCMR1_IC2F_2 ((uint16_t)0x4000) /*!< Bit 2 */ +#define TIM_CCMR1_IC2F_3 ((uint16_t)0x8000) /*!< Bit 3 */ + +/****************** Bit definition for TIM_CCMR2 register *******************/ +#define TIM_CCMR2_CC3S ((uint16_t)0x0003) /*!< CC3S[1:0] bits (Capture/Compare 3 Selection) */ +#define TIM_CCMR2_CC3S_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define TIM_CCMR2_CC3S_1 ((uint16_t)0x0002) /*!< Bit 1 */ + +#define TIM_CCMR2_OC3FE ((uint16_t)0x0004) /*!< Output Compare 3 Fast enable */ +#define TIM_CCMR2_OC3PE ((uint16_t)0x0008) /*!< Output Compare 3 Preload enable */ + +#define TIM_CCMR2_OC3M ((uint16_t)0x0070) /*!< OC3M[2:0] bits (Output Compare 3 Mode) */ +#define TIM_CCMR2_OC3M_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define TIM_CCMR2_OC3M_1 ((uint16_t)0x0020) /*!< Bit 1 */ +#define TIM_CCMR2_OC3M_2 ((uint16_t)0x0040) /*!< Bit 2 */ + +#define TIM_CCMR2_OC3CE ((uint16_t)0x0080) /*!< Output Compare 3 Clear Enable */ + +#define TIM_CCMR2_CC4S ((uint16_t)0x0300) /*!< CC4S[1:0] bits (Capture/Compare 4 Selection) */ +#define TIM_CCMR2_CC4S_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define TIM_CCMR2_CC4S_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define TIM_CCMR2_OC4FE ((uint16_t)0x0400) /*!< Output Compare 4 Fast enable */ +#define TIM_CCMR2_OC4PE ((uint16_t)0x0800) /*!< Output Compare 4 Preload enable */ + +#define TIM_CCMR2_OC4M ((uint16_t)0x7000) /*!< OC4M[2:0] bits (Output Compare 4 Mode) */ +#define TIM_CCMR2_OC4M_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define TIM_CCMR2_OC4M_1 ((uint16_t)0x2000) /*!< Bit 1 */ +#define TIM_CCMR2_OC4M_2 ((uint16_t)0x4000) /*!< Bit 2 */ + +#define TIM_CCMR2_OC4CE ((uint16_t)0x8000) /*!< Output Compare 4 Clear Enable */ + +/*----------------------------------------------------------------------------*/ + +#define TIM_CCMR2_IC3PSC ((uint16_t)0x000C) /*!< IC3PSC[1:0] bits (Input Capture 3 Prescaler) */ +#define TIM_CCMR2_IC3PSC_0 ((uint16_t)0x0004) /*!< Bit 0 */ +#define TIM_CCMR2_IC3PSC_1 ((uint16_t)0x0008) /*!< Bit 1 */ + +#define TIM_CCMR2_IC3F ((uint16_t)0x00F0) /*!< IC3F[3:0] bits (Input Capture 3 Filter) */ +#define TIM_CCMR2_IC3F_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define TIM_CCMR2_IC3F_1 ((uint16_t)0x0020) /*!< Bit 1 */ +#define TIM_CCMR2_IC3F_2 ((uint16_t)0x0040) /*!< Bit 2 */ +#define TIM_CCMR2_IC3F_3 ((uint16_t)0x0080) /*!< Bit 3 */ + +#define TIM_CCMR2_IC4PSC ((uint16_t)0x0C00) /*!< IC4PSC[1:0] bits (Input Capture 4 Prescaler) */ +#define TIM_CCMR2_IC4PSC_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define TIM_CCMR2_IC4PSC_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define TIM_CCMR2_IC4F ((uint16_t)0xF000) /*!< IC4F[3:0] bits (Input Capture 4 Filter) */ +#define TIM_CCMR2_IC4F_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define TIM_CCMR2_IC4F_1 ((uint16_t)0x2000) /*!< Bit 1 */ +#define TIM_CCMR2_IC4F_2 ((uint16_t)0x4000) /*!< Bit 2 */ +#define TIM_CCMR2_IC4F_3 ((uint16_t)0x8000) /*!< Bit 3 */ + +/******************* Bit definition for TIM_CCER register *******************/ +#define TIM_CCER_CC1E ((uint16_t)0x0001) /*!< Capture/Compare 1 output enable */ +#define TIM_CCER_CC1P ((uint16_t)0x0002) /*!< Capture/Compare 1 output Polarity */ +#define TIM_CCER_CC1NE ((uint16_t)0x0004) /*!< Capture/Compare 1 Complementary output enable */ +#define TIM_CCER_CC1NP ((uint16_t)0x0008) /*!< Capture/Compare 1 Complementary output Polarity */ +#define TIM_CCER_CC2E ((uint16_t)0x0010) /*!< Capture/Compare 2 output enable */ +#define TIM_CCER_CC2P ((uint16_t)0x0020) /*!< Capture/Compare 2 output Polarity */ +#define TIM_CCER_CC2NE ((uint16_t)0x0040) /*!< Capture/Compare 2 Complementary output enable */ +#define TIM_CCER_CC2NP ((uint16_t)0x0080) /*!< Capture/Compare 2 Complementary output Polarity */ +#define TIM_CCER_CC3E ((uint16_t)0x0100) /*!< Capture/Compare 3 output enable */ +#define TIM_CCER_CC3P ((uint16_t)0x0200) /*!< Capture/Compare 3 output Polarity */ +#define TIM_CCER_CC3NE ((uint16_t)0x0400) /*!< Capture/Compare 3 Complementary output enable */ +#define TIM_CCER_CC3NP ((uint16_t)0x0800) /*!< Capture/Compare 3 Complementary output Polarity */ +#define TIM_CCER_CC4E ((uint16_t)0x1000) /*!< Capture/Compare 4 output enable */ +#define TIM_CCER_CC4P ((uint16_t)0x2000) /*!< Capture/Compare 4 output Polarity */ +#define TIM_CCER_CC4NP ((uint16_t)0x8000) /*!< Capture/Compare 4 Complementary output Polarity */ + +/******************* Bit definition for TIM_CNT register ********************/ +#define TIM_CNT_CNT ((uint16_t)0xFFFF) /*!< Counter Value */ + +/******************* Bit definition for TIM_PSC register ********************/ +#define TIM_PSC_PSC ((uint16_t)0xFFFF) /*!< Prescaler Value */ + +/******************* Bit definition for TIM_ARR register ********************/ +#define TIM_ARR_ARR ((uint16_t)0xFFFF) /*!< actual auto-reload Value */ + +/******************* Bit definition for TIM_RCR register ********************/ +#define TIM_RCR_REP ((uint8_t)0xFF) /*!< Repetition Counter Value */ + +/******************* Bit definition for TIM_CCR1 register *******************/ +#define TIM_CCR1_CCR1 ((uint16_t)0xFFFF) /*!< Capture/Compare 1 Value */ + +/******************* Bit definition for TIM_CCR2 register *******************/ +#define TIM_CCR2_CCR2 ((uint16_t)0xFFFF) /*!< Capture/Compare 2 Value */ + +/******************* Bit definition for TIM_CCR3 register *******************/ +#define TIM_CCR3_CCR3 ((uint16_t)0xFFFF) /*!< Capture/Compare 3 Value */ + +/******************* Bit definition for TIM_CCR4 register *******************/ +#define TIM_CCR4_CCR4 ((uint16_t)0xFFFF) /*!< Capture/Compare 4 Value */ + +/******************* Bit definition for TIM_BDTR register *******************/ +#define TIM_BDTR_DTG ((uint16_t)0x00FF) /*!< DTG[0:7] bits (Dead-Time Generator set-up) */ +#define TIM_BDTR_DTG_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define TIM_BDTR_DTG_1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define TIM_BDTR_DTG_2 ((uint16_t)0x0004) /*!< Bit 2 */ +#define TIM_BDTR_DTG_3 ((uint16_t)0x0008) /*!< Bit 3 */ +#define TIM_BDTR_DTG_4 ((uint16_t)0x0010) /*!< Bit 4 */ +#define TIM_BDTR_DTG_5 ((uint16_t)0x0020) /*!< Bit 5 */ +#define TIM_BDTR_DTG_6 ((uint16_t)0x0040) /*!< Bit 6 */ +#define TIM_BDTR_DTG_7 ((uint16_t)0x0080) /*!< Bit 7 */ + +#define TIM_BDTR_LOCK ((uint16_t)0x0300) /*!< LOCK[1:0] bits (Lock Configuration) */ +#define TIM_BDTR_LOCK_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define TIM_BDTR_LOCK_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define TIM_BDTR_OSSI ((uint16_t)0x0400) /*!< Off-State Selection for Idle mode */ +#define TIM_BDTR_OSSR ((uint16_t)0x0800) /*!< Off-State Selection for Run mode */ +#define TIM_BDTR_BKE ((uint16_t)0x1000) /*!< Break enable */ +#define TIM_BDTR_BKP ((uint16_t)0x2000) /*!< Break Polarity */ +#define TIM_BDTR_AOE ((uint16_t)0x4000) /*!< Automatic Output enable */ +#define TIM_BDTR_MOE ((uint16_t)0x8000) /*!< Main Output enable */ + +/******************* Bit definition for TIM_DCR register ********************/ +#define TIM_DCR_DBA ((uint16_t)0x001F) /*!< DBA[4:0] bits (DMA Base Address) */ +#define TIM_DCR_DBA_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define TIM_DCR_DBA_1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define TIM_DCR_DBA_2 ((uint16_t)0x0004) /*!< Bit 2 */ +#define TIM_DCR_DBA_3 ((uint16_t)0x0008) /*!< Bit 3 */ +#define TIM_DCR_DBA_4 ((uint16_t)0x0010) /*!< Bit 4 */ + +#define TIM_DCR_DBL ((uint16_t)0x1F00) /*!< DBL[4:0] bits (DMA Burst Length) */ +#define TIM_DCR_DBL_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define TIM_DCR_DBL_1 ((uint16_t)0x0200) /*!< Bit 1 */ +#define TIM_DCR_DBL_2 ((uint16_t)0x0400) /*!< Bit 2 */ +#define TIM_DCR_DBL_3 ((uint16_t)0x0800) /*!< Bit 3 */ +#define TIM_DCR_DBL_4 ((uint16_t)0x1000) /*!< Bit 4 */ + +/******************* Bit definition for TIM_DMAR register *******************/ +#define TIM_DMAR_DMAB ((uint16_t)0xFFFF) /*!< DMA register for burst accesses */ + +/******************************************************************************/ +/* */ +/* Real-Time Clock */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for RTC_CRH register ********************/ +#define RTC_CRH_SECIE ((uint8_t)0x01) /*!< Second Interrupt Enable */ +#define RTC_CRH_ALRIE ((uint8_t)0x02) /*!< Alarm Interrupt Enable */ +#define RTC_CRH_OWIE ((uint8_t)0x04) /*!< OverfloW Interrupt Enable */ + +/******************* Bit definition for RTC_CRL register ********************/ +#define RTC_CRL_SECF ((uint8_t)0x01) /*!< Second Flag */ +#define RTC_CRL_ALRF ((uint8_t)0x02) /*!< Alarm Flag */ +#define RTC_CRL_OWF ((uint8_t)0x04) /*!< OverfloW Flag */ +#define RTC_CRL_RSF ((uint8_t)0x08) /*!< Registers Synchronized Flag */ +#define RTC_CRL_CNF ((uint8_t)0x10) /*!< Configuration Flag */ +#define RTC_CRL_RTOFF ((uint8_t)0x20) /*!< RTC operation OFF */ + +/******************* Bit definition for RTC_PRLH register *******************/ +#define RTC_PRLH_PRL ((uint16_t)0x000F) /*!< RTC Prescaler Reload Value High */ + +/******************* Bit definition for RTC_PRLL register *******************/ +#define RTC_PRLL_PRL ((uint16_t)0xFFFF) /*!< RTC Prescaler Reload Value Low */ + +/******************* Bit definition for RTC_DIVH register *******************/ +#define RTC_DIVH_RTC_DIV ((uint16_t)0x000F) /*!< RTC Clock Divider High */ + +/******************* Bit definition for RTC_DIVL register *******************/ +#define RTC_DIVL_RTC_DIV ((uint16_t)0xFFFF) /*!< RTC Clock Divider Low */ + +/******************* Bit definition for RTC_CNTH register *******************/ +#define RTC_CNTH_RTC_CNT ((uint16_t)0xFFFF) /*!< RTC Counter High */ + +/******************* Bit definition for RTC_CNTL register *******************/ +#define RTC_CNTL_RTC_CNT ((uint16_t)0xFFFF) /*!< RTC Counter Low */ + +/******************* Bit definition for RTC_ALRH register *******************/ +#define RTC_ALRH_RTC_ALR ((uint16_t)0xFFFF) /*!< RTC Alarm High */ + +/******************* Bit definition for RTC_ALRL register *******************/ +#define RTC_ALRL_RTC_ALR ((uint16_t)0xFFFF) /*!< RTC Alarm Low */ + +/******************************************************************************/ +/* */ +/* Independent WATCHDOG */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for IWDG_KR register ********************/ +#define IWDG_KR_KEY ((uint16_t)0xFFFF) /*!< Key value (write only, read 0000h) */ + +/******************* Bit definition for IWDG_PR register ********************/ +#define IWDG_PR_PR ((uint8_t)0x07) /*!< PR[2:0] (Prescaler divider) */ +#define IWDG_PR_PR_0 ((uint8_t)0x01) /*!< Bit 0 */ +#define IWDG_PR_PR_1 ((uint8_t)0x02) /*!< Bit 1 */ +#define IWDG_PR_PR_2 ((uint8_t)0x04) /*!< Bit 2 */ + +/******************* Bit definition for IWDG_RLR register *******************/ +#define IWDG_RLR_RL ((uint16_t)0x0FFF) /*!< Watchdog counter reload value */ + +/******************* Bit definition for IWDG_SR register ********************/ +#define IWDG_SR_PVU ((uint8_t)0x01) /*!< Watchdog prescaler value update */ +#define IWDG_SR_RVU ((uint8_t)0x02) /*!< Watchdog counter reload value update */ + +/******************************************************************************/ +/* */ +/* Window WATCHDOG */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for WWDG_CR register ********************/ +#define WWDG_CR_T ((uint8_t)0x7F) /*!< T[6:0] bits (7-Bit counter (MSB to LSB)) */ +#define WWDG_CR_T0 ((uint8_t)0x01) /*!< Bit 0 */ +#define WWDG_CR_T1 ((uint8_t)0x02) /*!< Bit 1 */ +#define WWDG_CR_T2 ((uint8_t)0x04) /*!< Bit 2 */ +#define WWDG_CR_T3 ((uint8_t)0x08) /*!< Bit 3 */ +#define WWDG_CR_T4 ((uint8_t)0x10) /*!< Bit 4 */ +#define WWDG_CR_T5 ((uint8_t)0x20) /*!< Bit 5 */ +#define WWDG_CR_T6 ((uint8_t)0x40) /*!< Bit 6 */ + +#define WWDG_CR_WDGA ((uint8_t)0x80) /*!< Activation bit */ + +/******************* Bit definition for WWDG_CFR register *******************/ +#define WWDG_CFR_W ((uint16_t)0x007F) /*!< W[6:0] bits (7-bit window value) */ +#define WWDG_CFR_W0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define WWDG_CFR_W1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define WWDG_CFR_W2 ((uint16_t)0x0004) /*!< Bit 2 */ +#define WWDG_CFR_W3 ((uint16_t)0x0008) /*!< Bit 3 */ +#define WWDG_CFR_W4 ((uint16_t)0x0010) /*!< Bit 4 */ +#define WWDG_CFR_W5 ((uint16_t)0x0020) /*!< Bit 5 */ +#define WWDG_CFR_W6 ((uint16_t)0x0040) /*!< Bit 6 */ + +#define WWDG_CFR_WDGTB ((uint16_t)0x0180) /*!< WDGTB[1:0] bits (Timer Base) */ +#define WWDG_CFR_WDGTB0 ((uint16_t)0x0080) /*!< Bit 0 */ +#define WWDG_CFR_WDGTB1 ((uint16_t)0x0100) /*!< Bit 1 */ + +#define WWDG_CFR_EWI ((uint16_t)0x0200) /*!< Early Wakeup Interrupt */ + +/******************* Bit definition for WWDG_SR register ********************/ +#define WWDG_SR_EWIF ((uint8_t)0x01) /*!< Early Wakeup Interrupt Flag */ + +/******************************************************************************/ +/* */ +/* Flexible Static Memory Controller */ +/* */ +/******************************************************************************/ + +/****************** Bit definition for FSMC_BCR1 register *******************/ +#define FSMC_BCR1_MBKEN ((uint32_t)0x00000001) /*!< Memory bank enable bit */ +#define FSMC_BCR1_MUXEN ((uint32_t)0x00000002) /*!< Address/data multiplexing enable bit */ + +#define FSMC_BCR1_MTYP ((uint32_t)0x0000000C) /*!< MTYP[1:0] bits (Memory type) */ +#define FSMC_BCR1_MTYP_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define FSMC_BCR1_MTYP_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define FSMC_BCR1_MWID ((uint32_t)0x00000030) /*!< MWID[1:0] bits (Memory data bus width) */ +#define FSMC_BCR1_MWID_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BCR1_MWID_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define FSMC_BCR1_FACCEN ((uint32_t)0x00000040) /*!< Flash access enable */ +#define FSMC_BCR1_BURSTEN ((uint32_t)0x00000100) /*!< Burst enable bit */ +#define FSMC_BCR1_WAITPOL ((uint32_t)0x00000200) /*!< Wait signal polarity bit */ +#define FSMC_BCR1_WRAPMOD ((uint32_t)0x00000400) /*!< Wrapped burst mode support */ +#define FSMC_BCR1_WAITCFG ((uint32_t)0x00000800) /*!< Wait timing configuration */ +#define FSMC_BCR1_WREN ((uint32_t)0x00001000) /*!< Write enable bit */ +#define FSMC_BCR1_WAITEN ((uint32_t)0x00002000) /*!< Wait enable bit */ +#define FSMC_BCR1_EXTMOD ((uint32_t)0x00004000) /*!< Extended mode enable */ +#define FSMC_BCR1_ASYNCWAIT ((uint32_t)0x00008000) /*!< Asynchronous wait */ +#define FSMC_BCR1_CBURSTRW ((uint32_t)0x00080000) /*!< Write burst enable */ + +/****************** Bit definition for FSMC_BCR2 register *******************/ +#define FSMC_BCR2_MBKEN ((uint32_t)0x00000001) /*!< Memory bank enable bit */ +#define FSMC_BCR2_MUXEN ((uint32_t)0x00000002) /*!< Address/data multiplexing enable bit */ + +#define FSMC_BCR2_MTYP ((uint32_t)0x0000000C) /*!< MTYP[1:0] bits (Memory type) */ +#define FSMC_BCR2_MTYP_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define FSMC_BCR2_MTYP_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define FSMC_BCR2_MWID ((uint32_t)0x00000030) /*!< MWID[1:0] bits (Memory data bus width) */ +#define FSMC_BCR2_MWID_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BCR2_MWID_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define FSMC_BCR2_FACCEN ((uint32_t)0x00000040) /*!< Flash access enable */ +#define FSMC_BCR2_BURSTEN ((uint32_t)0x00000100) /*!< Burst enable bit */ +#define FSMC_BCR2_WAITPOL ((uint32_t)0x00000200) /*!< Wait signal polarity bit */ +#define FSMC_BCR2_WRAPMOD ((uint32_t)0x00000400) /*!< Wrapped burst mode support */ +#define FSMC_BCR2_WAITCFG ((uint32_t)0x00000800) /*!< Wait timing configuration */ +#define FSMC_BCR2_WREN ((uint32_t)0x00001000) /*!< Write enable bit */ +#define FSMC_BCR2_WAITEN ((uint32_t)0x00002000) /*!< Wait enable bit */ +#define FSMC_BCR2_EXTMOD ((uint32_t)0x00004000) /*!< Extended mode enable */ +#define FSMC_BCR2_ASYNCWAIT ((uint32_t)0x00008000) /*!< Asynchronous wait */ +#define FSMC_BCR2_CBURSTRW ((uint32_t)0x00080000) /*!< Write burst enable */ + +/****************** Bit definition for FSMC_BCR3 register *******************/ +#define FSMC_BCR3_MBKEN ((uint32_t)0x00000001) /*!< Memory bank enable bit */ +#define FSMC_BCR3_MUXEN ((uint32_t)0x00000002) /*!< Address/data multiplexing enable bit */ + +#define FSMC_BCR3_MTYP ((uint32_t)0x0000000C) /*!< MTYP[1:0] bits (Memory type) */ +#define FSMC_BCR3_MTYP_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define FSMC_BCR3_MTYP_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define FSMC_BCR3_MWID ((uint32_t)0x00000030) /*!< MWID[1:0] bits (Memory data bus width) */ +#define FSMC_BCR3_MWID_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BCR3_MWID_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define FSMC_BCR3_FACCEN ((uint32_t)0x00000040) /*!< Flash access enable */ +#define FSMC_BCR3_BURSTEN ((uint32_t)0x00000100) /*!< Burst enable bit */ +#define FSMC_BCR3_WAITPOL ((uint32_t)0x00000200) /*!< Wait signal polarity bit. */ +#define FSMC_BCR3_WRAPMOD ((uint32_t)0x00000400) /*!< Wrapped burst mode support */ +#define FSMC_BCR3_WAITCFG ((uint32_t)0x00000800) /*!< Wait timing configuration */ +#define FSMC_BCR3_WREN ((uint32_t)0x00001000) /*!< Write enable bit */ +#define FSMC_BCR3_WAITEN ((uint32_t)0x00002000) /*!< Wait enable bit */ +#define FSMC_BCR3_EXTMOD ((uint32_t)0x00004000) /*!< Extended mode enable */ +#define FSMC_BCR3_ASYNCWAIT ((uint32_t)0x00008000) /*!< Asynchronous wait */ +#define FSMC_BCR3_CBURSTRW ((uint32_t)0x00080000) /*!< Write burst enable */ + +/****************** Bit definition for FSMC_BCR4 register *******************/ +#define FSMC_BCR4_MBKEN ((uint32_t)0x00000001) /*!< Memory bank enable bit */ +#define FSMC_BCR4_MUXEN ((uint32_t)0x00000002) /*!< Address/data multiplexing enable bit */ + +#define FSMC_BCR4_MTYP ((uint32_t)0x0000000C) /*!< MTYP[1:0] bits (Memory type) */ +#define FSMC_BCR4_MTYP_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define FSMC_BCR4_MTYP_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define FSMC_BCR4_MWID ((uint32_t)0x00000030) /*!< MWID[1:0] bits (Memory data bus width) */ +#define FSMC_BCR4_MWID_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BCR4_MWID_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define FSMC_BCR4_FACCEN ((uint32_t)0x00000040) /*!< Flash access enable */ +#define FSMC_BCR4_BURSTEN ((uint32_t)0x00000100) /*!< Burst enable bit */ +#define FSMC_BCR4_WAITPOL ((uint32_t)0x00000200) /*!< Wait signal polarity bit */ +#define FSMC_BCR4_WRAPMOD ((uint32_t)0x00000400) /*!< Wrapped burst mode support */ +#define FSMC_BCR4_WAITCFG ((uint32_t)0x00000800) /*!< Wait timing configuration */ +#define FSMC_BCR4_WREN ((uint32_t)0x00001000) /*!< Write enable bit */ +#define FSMC_BCR4_WAITEN ((uint32_t)0x00002000) /*!< Wait enable bit */ +#define FSMC_BCR4_EXTMOD ((uint32_t)0x00004000) /*!< Extended mode enable */ +#define FSMC_BCR4_ASYNCWAIT ((uint32_t)0x00008000) /*!< Asynchronous wait */ +#define FSMC_BCR4_CBURSTRW ((uint32_t)0x00080000) /*!< Write burst enable */ + +/****************** Bit definition for FSMC_BTR1 register ******************/ +#define FSMC_BTR1_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BTR1_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BTR1_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BTR1_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BTR1_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BTR1_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BTR1_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BTR1_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BTR1_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BTR1_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BTR1_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BTR1_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BTR1_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BTR1_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BTR1_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BTR1_BUSTURN ((uint32_t)0x000F0000) /*!< BUSTURN[3:0] bits (Bus turnaround phase duration) */ +#define FSMC_BTR1_BUSTURN_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_BTR1_BUSTURN_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_BTR1_BUSTURN_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_BTR1_BUSTURN_3 ((uint32_t)0x00080000) /*!< Bit 3 */ + +#define FSMC_BTR1_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BTR1_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BTR1_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define FSMC_BTR1_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BTR1_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BTR1_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BTR1_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BTR1_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BTR1_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BTR1_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BTR1_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BTR1_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BTR1_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/****************** Bit definition for FSMC_BTR2 register *******************/ +#define FSMC_BTR2_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BTR2_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BTR2_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BTR2_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BTR2_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BTR2_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BTR2_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BTR2_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BTR2_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BTR2_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BTR2_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BTR2_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BTR2_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BTR2_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BTR2_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BTR2_BUSTURN ((uint32_t)0x000F0000) /*!< BUSTURN[3:0] bits (Bus turnaround phase duration) */ +#define FSMC_BTR2_BUSTURN_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_BTR2_BUSTURN_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_BTR2_BUSTURN_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_BTR2_BUSTURN_3 ((uint32_t)0x00080000) /*!< Bit 3 */ + +#define FSMC_BTR2_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BTR2_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BTR2_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define FSMC_BTR2_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BTR2_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BTR2_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BTR2_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BTR2_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BTR2_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BTR2_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BTR2_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BTR2_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BTR2_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/******************* Bit definition for FSMC_BTR3 register *******************/ +#define FSMC_BTR3_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BTR3_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BTR3_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BTR3_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BTR3_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BTR3_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BTR3_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BTR3_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BTR3_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BTR3_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BTR3_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BTR3_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BTR3_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BTR3_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BTR3_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BTR3_BUSTURN ((uint32_t)0x000F0000) /*!< BUSTURN[3:0] bits (Bus turnaround phase duration) */ +#define FSMC_BTR3_BUSTURN_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_BTR3_BUSTURN_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_BTR3_BUSTURN_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_BTR3_BUSTURN_3 ((uint32_t)0x00080000) /*!< Bit 3 */ + +#define FSMC_BTR3_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BTR3_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BTR3_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define FSMC_BTR3_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BTR3_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BTR3_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BTR3_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BTR3_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BTR3_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BTR3_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BTR3_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BTR3_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BTR3_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/****************** Bit definition for FSMC_BTR4 register *******************/ +#define FSMC_BTR4_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BTR4_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BTR4_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BTR4_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BTR4_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BTR4_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BTR4_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BTR4_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BTR4_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BTR4_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BTR4_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BTR4_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BTR4_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BTR4_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BTR4_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BTR4_BUSTURN ((uint32_t)0x000F0000) /*!< BUSTURN[3:0] bits (Bus turnaround phase duration) */ +#define FSMC_BTR4_BUSTURN_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_BTR4_BUSTURN_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_BTR4_BUSTURN_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_BTR4_BUSTURN_3 ((uint32_t)0x00080000) /*!< Bit 3 */ + +#define FSMC_BTR4_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BTR4_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BTR4_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define FSMC_BTR4_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BTR4_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BTR4_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BTR4_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BTR4_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BTR4_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BTR4_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BTR4_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BTR4_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BTR4_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/****************** Bit definition for FSMC_BWTR1 register ******************/ +#define FSMC_BWTR1_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BWTR1_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BWTR1_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BWTR1_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BWTR1_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BWTR1_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BWTR1_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BWTR1_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BWTR1_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BWTR1_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BWTR1_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BWTR1_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BWTR1_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BWTR1_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BWTR1_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BWTR1_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BWTR1_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BWTR1_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define FSMC_BWTR1_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BWTR1_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BWTR1_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BWTR1_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BWTR1_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BWTR1_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BWTR1_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BWTR1_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BWTR1_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BWTR1_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/****************** Bit definition for FSMC_BWTR2 register ******************/ +#define FSMC_BWTR2_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BWTR2_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BWTR2_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BWTR2_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BWTR2_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BWTR2_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BWTR2_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BWTR2_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BWTR2_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BWTR2_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BWTR2_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BWTR2_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BWTR2_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BWTR2_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BWTR2_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BWTR2_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BWTR2_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BWTR2_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1*/ +#define FSMC_BWTR2_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BWTR2_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BWTR2_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BWTR2_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BWTR2_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BWTR2_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BWTR2_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BWTR2_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BWTR2_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BWTR2_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/****************** Bit definition for FSMC_BWTR3 register ******************/ +#define FSMC_BWTR3_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BWTR3_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BWTR3_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BWTR3_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BWTR3_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BWTR3_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BWTR3_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BWTR3_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BWTR3_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BWTR3_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BWTR3_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BWTR3_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BWTR3_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BWTR3_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BWTR3_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BWTR3_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BWTR3_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BWTR3_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define FSMC_BWTR3_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BWTR3_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BWTR3_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BWTR3_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BWTR3_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BWTR3_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BWTR3_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BWTR3_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BWTR3_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BWTR3_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/****************** Bit definition for FSMC_BWTR4 register ******************/ +#define FSMC_BWTR4_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BWTR4_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BWTR4_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BWTR4_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BWTR4_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BWTR4_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BWTR4_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BWTR4_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BWTR4_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BWTR4_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BWTR4_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BWTR4_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BWTR4_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BWTR4_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BWTR4_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BWTR4_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BWTR4_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BWTR4_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define FSMC_BWTR4_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BWTR4_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BWTR4_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BWTR4_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BWTR4_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BWTR4_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BWTR4_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BWTR4_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BWTR4_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BWTR4_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/****************** Bit definition for FSMC_PCR2 register *******************/ +#define FSMC_PCR2_PWAITEN ((uint32_t)0x00000002) /*!< Wait feature enable bit */ +#define FSMC_PCR2_PBKEN ((uint32_t)0x00000004) /*!< PC Card/NAND Flash memory bank enable bit */ +#define FSMC_PCR2_PTYP ((uint32_t)0x00000008) /*!< Memory type */ + +#define FSMC_PCR2_PWID ((uint32_t)0x00000030) /*!< PWID[1:0] bits (NAND Flash databus width) */ +#define FSMC_PCR2_PWID_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_PCR2_PWID_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define FSMC_PCR2_ECCEN ((uint32_t)0x00000040) /*!< ECC computation logic enable bit */ + +#define FSMC_PCR2_TCLR ((uint32_t)0x00001E00) /*!< TCLR[3:0] bits (CLE to RE delay) */ +#define FSMC_PCR2_TCLR_0 ((uint32_t)0x00000200) /*!< Bit 0 */ +#define FSMC_PCR2_TCLR_1 ((uint32_t)0x00000400) /*!< Bit 1 */ +#define FSMC_PCR2_TCLR_2 ((uint32_t)0x00000800) /*!< Bit 2 */ +#define FSMC_PCR2_TCLR_3 ((uint32_t)0x00001000) /*!< Bit 3 */ + +#define FSMC_PCR2_TAR ((uint32_t)0x0001E000) /*!< TAR[3:0] bits (ALE to RE delay) */ +#define FSMC_PCR2_TAR_0 ((uint32_t)0x00002000) /*!< Bit 0 */ +#define FSMC_PCR2_TAR_1 ((uint32_t)0x00004000) /*!< Bit 1 */ +#define FSMC_PCR2_TAR_2 ((uint32_t)0x00008000) /*!< Bit 2 */ +#define FSMC_PCR2_TAR_3 ((uint32_t)0x00010000) /*!< Bit 3 */ + +#define FSMC_PCR2_ECCPS ((uint32_t)0x000E0000) /*!< ECCPS[1:0] bits (ECC page size) */ +#define FSMC_PCR2_ECCPS_0 ((uint32_t)0x00020000) /*!< Bit 0 */ +#define FSMC_PCR2_ECCPS_1 ((uint32_t)0x00040000) /*!< Bit 1 */ +#define FSMC_PCR2_ECCPS_2 ((uint32_t)0x00080000) /*!< Bit 2 */ + +/****************** Bit definition for FSMC_PCR3 register *******************/ +#define FSMC_PCR3_PWAITEN ((uint32_t)0x00000002) /*!< Wait feature enable bit */ +#define FSMC_PCR3_PBKEN ((uint32_t)0x00000004) /*!< PC Card/NAND Flash memory bank enable bit */ +#define FSMC_PCR3_PTYP ((uint32_t)0x00000008) /*!< Memory type */ + +#define FSMC_PCR3_PWID ((uint32_t)0x00000030) /*!< PWID[1:0] bits (NAND Flash databus width) */ +#define FSMC_PCR3_PWID_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_PCR3_PWID_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define FSMC_PCR3_ECCEN ((uint32_t)0x00000040) /*!< ECC computation logic enable bit */ + +#define FSMC_PCR3_TCLR ((uint32_t)0x00001E00) /*!< TCLR[3:0] bits (CLE to RE delay) */ +#define FSMC_PCR3_TCLR_0 ((uint32_t)0x00000200) /*!< Bit 0 */ +#define FSMC_PCR3_TCLR_1 ((uint32_t)0x00000400) /*!< Bit 1 */ +#define FSMC_PCR3_TCLR_2 ((uint32_t)0x00000800) /*!< Bit 2 */ +#define FSMC_PCR3_TCLR_3 ((uint32_t)0x00001000) /*!< Bit 3 */ + +#define FSMC_PCR3_TAR ((uint32_t)0x0001E000) /*!< TAR[3:0] bits (ALE to RE delay) */ +#define FSMC_PCR3_TAR_0 ((uint32_t)0x00002000) /*!< Bit 0 */ +#define FSMC_PCR3_TAR_1 ((uint32_t)0x00004000) /*!< Bit 1 */ +#define FSMC_PCR3_TAR_2 ((uint32_t)0x00008000) /*!< Bit 2 */ +#define FSMC_PCR3_TAR_3 ((uint32_t)0x00010000) /*!< Bit 3 */ + +#define FSMC_PCR3_ECCPS ((uint32_t)0x000E0000) /*!< ECCPS[2:0] bits (ECC page size) */ +#define FSMC_PCR3_ECCPS_0 ((uint32_t)0x00020000) /*!< Bit 0 */ +#define FSMC_PCR3_ECCPS_1 ((uint32_t)0x00040000) /*!< Bit 1 */ +#define FSMC_PCR3_ECCPS_2 ((uint32_t)0x00080000) /*!< Bit 2 */ + +/****************** Bit definition for FSMC_PCR4 register *******************/ +#define FSMC_PCR4_PWAITEN ((uint32_t)0x00000002) /*!< Wait feature enable bit */ +#define FSMC_PCR4_PBKEN ((uint32_t)0x00000004) /*!< PC Card/NAND Flash memory bank enable bit */ +#define FSMC_PCR4_PTYP ((uint32_t)0x00000008) /*!< Memory type */ + +#define FSMC_PCR4_PWID ((uint32_t)0x00000030) /*!< PWID[1:0] bits (NAND Flash databus width) */ +#define FSMC_PCR4_PWID_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_PCR4_PWID_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define FSMC_PCR4_ECCEN ((uint32_t)0x00000040) /*!< ECC computation logic enable bit */ + +#define FSMC_PCR4_TCLR ((uint32_t)0x00001E00) /*!< TCLR[3:0] bits (CLE to RE delay) */ +#define FSMC_PCR4_TCLR_0 ((uint32_t)0x00000200) /*!< Bit 0 */ +#define FSMC_PCR4_TCLR_1 ((uint32_t)0x00000400) /*!< Bit 1 */ +#define FSMC_PCR4_TCLR_2 ((uint32_t)0x00000800) /*!< Bit 2 */ +#define FSMC_PCR4_TCLR_3 ((uint32_t)0x00001000) /*!< Bit 3 */ + +#define FSMC_PCR4_TAR ((uint32_t)0x0001E000) /*!< TAR[3:0] bits (ALE to RE delay) */ +#define FSMC_PCR4_TAR_0 ((uint32_t)0x00002000) /*!< Bit 0 */ +#define FSMC_PCR4_TAR_1 ((uint32_t)0x00004000) /*!< Bit 1 */ +#define FSMC_PCR4_TAR_2 ((uint32_t)0x00008000) /*!< Bit 2 */ +#define FSMC_PCR4_TAR_3 ((uint32_t)0x00010000) /*!< Bit 3 */ + +#define FSMC_PCR4_ECCPS ((uint32_t)0x000E0000) /*!< ECCPS[2:0] bits (ECC page size) */ +#define FSMC_PCR4_ECCPS_0 ((uint32_t)0x00020000) /*!< Bit 0 */ +#define FSMC_PCR4_ECCPS_1 ((uint32_t)0x00040000) /*!< Bit 1 */ +#define FSMC_PCR4_ECCPS_2 ((uint32_t)0x00080000) /*!< Bit 2 */ + +/******************* Bit definition for FSMC_SR2 register *******************/ +#define FSMC_SR2_IRS ((uint8_t)0x01) /*!< Interrupt Rising Edge status */ +#define FSMC_SR2_ILS ((uint8_t)0x02) /*!< Interrupt Level status */ +#define FSMC_SR2_IFS ((uint8_t)0x04) /*!< Interrupt Falling Edge status */ +#define FSMC_SR2_IREN ((uint8_t)0x08) /*!< Interrupt Rising Edge detection Enable bit */ +#define FSMC_SR2_ILEN ((uint8_t)0x10) /*!< Interrupt Level detection Enable bit */ +#define FSMC_SR2_IFEN ((uint8_t)0x20) /*!< Interrupt Falling Edge detection Enable bit */ +#define FSMC_SR2_FEMPT ((uint8_t)0x40) /*!< FIFO empty */ + +/******************* Bit definition for FSMC_SR3 register *******************/ +#define FSMC_SR3_IRS ((uint8_t)0x01) /*!< Interrupt Rising Edge status */ +#define FSMC_SR3_ILS ((uint8_t)0x02) /*!< Interrupt Level status */ +#define FSMC_SR3_IFS ((uint8_t)0x04) /*!< Interrupt Falling Edge status */ +#define FSMC_SR3_IREN ((uint8_t)0x08) /*!< Interrupt Rising Edge detection Enable bit */ +#define FSMC_SR3_ILEN ((uint8_t)0x10) /*!< Interrupt Level detection Enable bit */ +#define FSMC_SR3_IFEN ((uint8_t)0x20) /*!< Interrupt Falling Edge detection Enable bit */ +#define FSMC_SR3_FEMPT ((uint8_t)0x40) /*!< FIFO empty */ + +/******************* Bit definition for FSMC_SR4 register *******************/ +#define FSMC_SR4_IRS ((uint8_t)0x01) /*!< Interrupt Rising Edge status */ +#define FSMC_SR4_ILS ((uint8_t)0x02) /*!< Interrupt Level status */ +#define FSMC_SR4_IFS ((uint8_t)0x04) /*!< Interrupt Falling Edge status */ +#define FSMC_SR4_IREN ((uint8_t)0x08) /*!< Interrupt Rising Edge detection Enable bit */ +#define FSMC_SR4_ILEN ((uint8_t)0x10) /*!< Interrupt Level detection Enable bit */ +#define FSMC_SR4_IFEN ((uint8_t)0x20) /*!< Interrupt Falling Edge detection Enable bit */ +#define FSMC_SR4_FEMPT ((uint8_t)0x40) /*!< FIFO empty */ + +/****************** Bit definition for FSMC_PMEM2 register ******************/ +#define FSMC_PMEM2_MEMSET2 ((uint32_t)0x000000FF) /*!< MEMSET2[7:0] bits (Common memory 2 setup time) */ +#define FSMC_PMEM2_MEMSET2_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_PMEM2_MEMSET2_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_PMEM2_MEMSET2_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_PMEM2_MEMSET2_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define FSMC_PMEM2_MEMSET2_4 ((uint32_t)0x00000010) /*!< Bit 4 */ +#define FSMC_PMEM2_MEMSET2_5 ((uint32_t)0x00000020) /*!< Bit 5 */ +#define FSMC_PMEM2_MEMSET2_6 ((uint32_t)0x00000040) /*!< Bit 6 */ +#define FSMC_PMEM2_MEMSET2_7 ((uint32_t)0x00000080) /*!< Bit 7 */ + +#define FSMC_PMEM2_MEMWAIT2 ((uint32_t)0x0000FF00) /*!< MEMWAIT2[7:0] bits (Common memory 2 wait time) */ +#define FSMC_PMEM2_MEMWAIT2_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_PMEM2_MEMWAIT2_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_PMEM2_MEMWAIT2_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_PMEM2_MEMWAIT2_3 ((uint32_t)0x00000800) /*!< Bit 3 */ +#define FSMC_PMEM2_MEMWAIT2_4 ((uint32_t)0x00001000) /*!< Bit 4 */ +#define FSMC_PMEM2_MEMWAIT2_5 ((uint32_t)0x00002000) /*!< Bit 5 */ +#define FSMC_PMEM2_MEMWAIT2_6 ((uint32_t)0x00004000) /*!< Bit 6 */ +#define FSMC_PMEM2_MEMWAIT2_7 ((uint32_t)0x00008000) /*!< Bit 7 */ + +#define FSMC_PMEM2_MEMHOLD2 ((uint32_t)0x00FF0000) /*!< MEMHOLD2[7:0] bits (Common memory 2 hold time) */ +#define FSMC_PMEM2_MEMHOLD2_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_PMEM2_MEMHOLD2_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_PMEM2_MEMHOLD2_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_PMEM2_MEMHOLD2_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define FSMC_PMEM2_MEMHOLD2_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define FSMC_PMEM2_MEMHOLD2_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define FSMC_PMEM2_MEMHOLD2_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define FSMC_PMEM2_MEMHOLD2_7 ((uint32_t)0x00800000) /*!< Bit 7 */ + +#define FSMC_PMEM2_MEMHIZ2 ((uint32_t)0xFF000000) /*!< MEMHIZ2[7:0] bits (Common memory 2 databus HiZ time) */ +#define FSMC_PMEM2_MEMHIZ2_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_PMEM2_MEMHIZ2_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_PMEM2_MEMHIZ2_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_PMEM2_MEMHIZ2_3 ((uint32_t)0x08000000) /*!< Bit 3 */ +#define FSMC_PMEM2_MEMHIZ2_4 ((uint32_t)0x10000000) /*!< Bit 4 */ +#define FSMC_PMEM2_MEMHIZ2_5 ((uint32_t)0x20000000) /*!< Bit 5 */ +#define FSMC_PMEM2_MEMHIZ2_6 ((uint32_t)0x40000000) /*!< Bit 6 */ +#define FSMC_PMEM2_MEMHIZ2_7 ((uint32_t)0x80000000) /*!< Bit 7 */ + +/****************** Bit definition for FSMC_PMEM3 register ******************/ +#define FSMC_PMEM3_MEMSET3 ((uint32_t)0x000000FF) /*!< MEMSET3[7:0] bits (Common memory 3 setup time) */ +#define FSMC_PMEM3_MEMSET3_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_PMEM3_MEMSET3_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_PMEM3_MEMSET3_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_PMEM3_MEMSET3_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define FSMC_PMEM3_MEMSET3_4 ((uint32_t)0x00000010) /*!< Bit 4 */ +#define FSMC_PMEM3_MEMSET3_5 ((uint32_t)0x00000020) /*!< Bit 5 */ +#define FSMC_PMEM3_MEMSET3_6 ((uint32_t)0x00000040) /*!< Bit 6 */ +#define FSMC_PMEM3_MEMSET3_7 ((uint32_t)0x00000080) /*!< Bit 7 */ + +#define FSMC_PMEM3_MEMWAIT3 ((uint32_t)0x0000FF00) /*!< MEMWAIT3[7:0] bits (Common memory 3 wait time) */ +#define FSMC_PMEM3_MEMWAIT3_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_PMEM3_MEMWAIT3_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_PMEM3_MEMWAIT3_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_PMEM3_MEMWAIT3_3 ((uint32_t)0x00000800) /*!< Bit 3 */ +#define FSMC_PMEM3_MEMWAIT3_4 ((uint32_t)0x00001000) /*!< Bit 4 */ +#define FSMC_PMEM3_MEMWAIT3_5 ((uint32_t)0x00002000) /*!< Bit 5 */ +#define FSMC_PMEM3_MEMWAIT3_6 ((uint32_t)0x00004000) /*!< Bit 6 */ +#define FSMC_PMEM3_MEMWAIT3_7 ((uint32_t)0x00008000) /*!< Bit 7 */ + +#define FSMC_PMEM3_MEMHOLD3 ((uint32_t)0x00FF0000) /*!< MEMHOLD3[7:0] bits (Common memory 3 hold time) */ +#define FSMC_PMEM3_MEMHOLD3_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_PMEM3_MEMHOLD3_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_PMEM3_MEMHOLD3_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_PMEM3_MEMHOLD3_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define FSMC_PMEM3_MEMHOLD3_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define FSMC_PMEM3_MEMHOLD3_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define FSMC_PMEM3_MEMHOLD3_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define FSMC_PMEM3_MEMHOLD3_7 ((uint32_t)0x00800000) /*!< Bit 7 */ + +#define FSMC_PMEM3_MEMHIZ3 ((uint32_t)0xFF000000) /*!< MEMHIZ3[7:0] bits (Common memory 3 databus HiZ time) */ +#define FSMC_PMEM3_MEMHIZ3_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_PMEM3_MEMHIZ3_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_PMEM3_MEMHIZ3_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_PMEM3_MEMHIZ3_3 ((uint32_t)0x08000000) /*!< Bit 3 */ +#define FSMC_PMEM3_MEMHIZ3_4 ((uint32_t)0x10000000) /*!< Bit 4 */ +#define FSMC_PMEM3_MEMHIZ3_5 ((uint32_t)0x20000000) /*!< Bit 5 */ +#define FSMC_PMEM3_MEMHIZ3_6 ((uint32_t)0x40000000) /*!< Bit 6 */ +#define FSMC_PMEM3_MEMHIZ3_7 ((uint32_t)0x80000000) /*!< Bit 7 */ + +/****************** Bit definition for FSMC_PMEM4 register ******************/ +#define FSMC_PMEM4_MEMSET4 ((uint32_t)0x000000FF) /*!< MEMSET4[7:0] bits (Common memory 4 setup time) */ +#define FSMC_PMEM4_MEMSET4_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_PMEM4_MEMSET4_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_PMEM4_MEMSET4_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_PMEM4_MEMSET4_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define FSMC_PMEM4_MEMSET4_4 ((uint32_t)0x00000010) /*!< Bit 4 */ +#define FSMC_PMEM4_MEMSET4_5 ((uint32_t)0x00000020) /*!< Bit 5 */ +#define FSMC_PMEM4_MEMSET4_6 ((uint32_t)0x00000040) /*!< Bit 6 */ +#define FSMC_PMEM4_MEMSET4_7 ((uint32_t)0x00000080) /*!< Bit 7 */ + +#define FSMC_PMEM4_MEMWAIT4 ((uint32_t)0x0000FF00) /*!< MEMWAIT4[7:0] bits (Common memory 4 wait time) */ +#define FSMC_PMEM4_MEMWAIT4_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_PMEM4_MEMWAIT4_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_PMEM4_MEMWAIT4_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_PMEM4_MEMWAIT4_3 ((uint32_t)0x00000800) /*!< Bit 3 */ +#define FSMC_PMEM4_MEMWAIT4_4 ((uint32_t)0x00001000) /*!< Bit 4 */ +#define FSMC_PMEM4_MEMWAIT4_5 ((uint32_t)0x00002000) /*!< Bit 5 */ +#define FSMC_PMEM4_MEMWAIT4_6 ((uint32_t)0x00004000) /*!< Bit 6 */ +#define FSMC_PMEM4_MEMWAIT4_7 ((uint32_t)0x00008000) /*!< Bit 7 */ + +#define FSMC_PMEM4_MEMHOLD4 ((uint32_t)0x00FF0000) /*!< MEMHOLD4[7:0] bits (Common memory 4 hold time) */ +#define FSMC_PMEM4_MEMHOLD4_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_PMEM4_MEMHOLD4_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_PMEM4_MEMHOLD4_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_PMEM4_MEMHOLD4_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define FSMC_PMEM4_MEMHOLD4_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define FSMC_PMEM4_MEMHOLD4_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define FSMC_PMEM4_MEMHOLD4_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define FSMC_PMEM4_MEMHOLD4_7 ((uint32_t)0x00800000) /*!< Bit 7 */ + +#define FSMC_PMEM4_MEMHIZ4 ((uint32_t)0xFF000000) /*!< MEMHIZ4[7:0] bits (Common memory 4 databus HiZ time) */ +#define FSMC_PMEM4_MEMHIZ4_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_PMEM4_MEMHIZ4_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_PMEM4_MEMHIZ4_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_PMEM4_MEMHIZ4_3 ((uint32_t)0x08000000) /*!< Bit 3 */ +#define FSMC_PMEM4_MEMHIZ4_4 ((uint32_t)0x10000000) /*!< Bit 4 */ +#define FSMC_PMEM4_MEMHIZ4_5 ((uint32_t)0x20000000) /*!< Bit 5 */ +#define FSMC_PMEM4_MEMHIZ4_6 ((uint32_t)0x40000000) /*!< Bit 6 */ +#define FSMC_PMEM4_MEMHIZ4_7 ((uint32_t)0x80000000) /*!< Bit 7 */ + +/****************** Bit definition for FSMC_PATT2 register ******************/ +#define FSMC_PATT2_ATTSET2 ((uint32_t)0x000000FF) /*!< ATTSET2[7:0] bits (Attribute memory 2 setup time) */ +#define FSMC_PATT2_ATTSET2_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_PATT2_ATTSET2_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_PATT2_ATTSET2_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_PATT2_ATTSET2_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define FSMC_PATT2_ATTSET2_4 ((uint32_t)0x00000010) /*!< Bit 4 */ +#define FSMC_PATT2_ATTSET2_5 ((uint32_t)0x00000020) /*!< Bit 5 */ +#define FSMC_PATT2_ATTSET2_6 ((uint32_t)0x00000040) /*!< Bit 6 */ +#define FSMC_PATT2_ATTSET2_7 ((uint32_t)0x00000080) /*!< Bit 7 */ + +#define FSMC_PATT2_ATTWAIT2 ((uint32_t)0x0000FF00) /*!< ATTWAIT2[7:0] bits (Attribute memory 2 wait time) */ +#define FSMC_PATT2_ATTWAIT2_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_PATT2_ATTWAIT2_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_PATT2_ATTWAIT2_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_PATT2_ATTWAIT2_3 ((uint32_t)0x00000800) /*!< Bit 3 */ +#define FSMC_PATT2_ATTWAIT2_4 ((uint32_t)0x00001000) /*!< Bit 4 */ +#define FSMC_PATT2_ATTWAIT2_5 ((uint32_t)0x00002000) /*!< Bit 5 */ +#define FSMC_PATT2_ATTWAIT2_6 ((uint32_t)0x00004000) /*!< Bit 6 */ +#define FSMC_PATT2_ATTWAIT2_7 ((uint32_t)0x00008000) /*!< Bit 7 */ + +#define FSMC_PATT2_ATTHOLD2 ((uint32_t)0x00FF0000) /*!< ATTHOLD2[7:0] bits (Attribute memory 2 hold time) */ +#define FSMC_PATT2_ATTHOLD2_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_PATT2_ATTHOLD2_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_PATT2_ATTHOLD2_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_PATT2_ATTHOLD2_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define FSMC_PATT2_ATTHOLD2_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define FSMC_PATT2_ATTHOLD2_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define FSMC_PATT2_ATTHOLD2_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define FSMC_PATT2_ATTHOLD2_7 ((uint32_t)0x00800000) /*!< Bit 7 */ + +#define FSMC_PATT2_ATTHIZ2 ((uint32_t)0xFF000000) /*!< ATTHIZ2[7:0] bits (Attribute memory 2 databus HiZ time) */ +#define FSMC_PATT2_ATTHIZ2_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_PATT2_ATTHIZ2_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_PATT2_ATTHIZ2_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_PATT2_ATTHIZ2_3 ((uint32_t)0x08000000) /*!< Bit 3 */ +#define FSMC_PATT2_ATTHIZ2_4 ((uint32_t)0x10000000) /*!< Bit 4 */ +#define FSMC_PATT2_ATTHIZ2_5 ((uint32_t)0x20000000) /*!< Bit 5 */ +#define FSMC_PATT2_ATTHIZ2_6 ((uint32_t)0x40000000) /*!< Bit 6 */ +#define FSMC_PATT2_ATTHIZ2_7 ((uint32_t)0x80000000) /*!< Bit 7 */ + +/****************** Bit definition for FSMC_PATT3 register ******************/ +#define FSMC_PATT3_ATTSET3 ((uint32_t)0x000000FF) /*!< ATTSET3[7:0] bits (Attribute memory 3 setup time) */ +#define FSMC_PATT3_ATTSET3_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_PATT3_ATTSET3_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_PATT3_ATTSET3_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_PATT3_ATTSET3_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define FSMC_PATT3_ATTSET3_4 ((uint32_t)0x00000010) /*!< Bit 4 */ +#define FSMC_PATT3_ATTSET3_5 ((uint32_t)0x00000020) /*!< Bit 5 */ +#define FSMC_PATT3_ATTSET3_6 ((uint32_t)0x00000040) /*!< Bit 6 */ +#define FSMC_PATT3_ATTSET3_7 ((uint32_t)0x00000080) /*!< Bit 7 */ + +#define FSMC_PATT3_ATTWAIT3 ((uint32_t)0x0000FF00) /*!< ATTWAIT3[7:0] bits (Attribute memory 3 wait time) */ +#define FSMC_PATT3_ATTWAIT3_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_PATT3_ATTWAIT3_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_PATT3_ATTWAIT3_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_PATT3_ATTWAIT3_3 ((uint32_t)0x00000800) /*!< Bit 3 */ +#define FSMC_PATT3_ATTWAIT3_4 ((uint32_t)0x00001000) /*!< Bit 4 */ +#define FSMC_PATT3_ATTWAIT3_5 ((uint32_t)0x00002000) /*!< Bit 5 */ +#define FSMC_PATT3_ATTWAIT3_6 ((uint32_t)0x00004000) /*!< Bit 6 */ +#define FSMC_PATT3_ATTWAIT3_7 ((uint32_t)0x00008000) /*!< Bit 7 */ + +#define FSMC_PATT3_ATTHOLD3 ((uint32_t)0x00FF0000) /*!< ATTHOLD3[7:0] bits (Attribute memory 3 hold time) */ +#define FSMC_PATT3_ATTHOLD3_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_PATT3_ATTHOLD3_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_PATT3_ATTHOLD3_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_PATT3_ATTHOLD3_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define FSMC_PATT3_ATTHOLD3_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define FSMC_PATT3_ATTHOLD3_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define FSMC_PATT3_ATTHOLD3_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define FSMC_PATT3_ATTHOLD3_7 ((uint32_t)0x00800000) /*!< Bit 7 */ + +#define FSMC_PATT3_ATTHIZ3 ((uint32_t)0xFF000000) /*!< ATTHIZ3[7:0] bits (Attribute memory 3 databus HiZ time) */ +#define FSMC_PATT3_ATTHIZ3_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_PATT3_ATTHIZ3_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_PATT3_ATTHIZ3_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_PATT3_ATTHIZ3_3 ((uint32_t)0x08000000) /*!< Bit 3 */ +#define FSMC_PATT3_ATTHIZ3_4 ((uint32_t)0x10000000) /*!< Bit 4 */ +#define FSMC_PATT3_ATTHIZ3_5 ((uint32_t)0x20000000) /*!< Bit 5 */ +#define FSMC_PATT3_ATTHIZ3_6 ((uint32_t)0x40000000) /*!< Bit 6 */ +#define FSMC_PATT3_ATTHIZ3_7 ((uint32_t)0x80000000) /*!< Bit 7 */ + +/****************** Bit definition for FSMC_PATT4 register ******************/ +#define FSMC_PATT4_ATTSET4 ((uint32_t)0x000000FF) /*!< ATTSET4[7:0] bits (Attribute memory 4 setup time) */ +#define FSMC_PATT4_ATTSET4_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_PATT4_ATTSET4_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_PATT4_ATTSET4_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_PATT4_ATTSET4_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define FSMC_PATT4_ATTSET4_4 ((uint32_t)0x00000010) /*!< Bit 4 */ +#define FSMC_PATT4_ATTSET4_5 ((uint32_t)0x00000020) /*!< Bit 5 */ +#define FSMC_PATT4_ATTSET4_6 ((uint32_t)0x00000040) /*!< Bit 6 */ +#define FSMC_PATT4_ATTSET4_7 ((uint32_t)0x00000080) /*!< Bit 7 */ + +#define FSMC_PATT4_ATTWAIT4 ((uint32_t)0x0000FF00) /*!< ATTWAIT4[7:0] bits (Attribute memory 4 wait time) */ +#define FSMC_PATT4_ATTWAIT4_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_PATT4_ATTWAIT4_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_PATT4_ATTWAIT4_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_PATT4_ATTWAIT4_3 ((uint32_t)0x00000800) /*!< Bit 3 */ +#define FSMC_PATT4_ATTWAIT4_4 ((uint32_t)0x00001000) /*!< Bit 4 */ +#define FSMC_PATT4_ATTWAIT4_5 ((uint32_t)0x00002000) /*!< Bit 5 */ +#define FSMC_PATT4_ATTWAIT4_6 ((uint32_t)0x00004000) /*!< Bit 6 */ +#define FSMC_PATT4_ATTWAIT4_7 ((uint32_t)0x00008000) /*!< Bit 7 */ + +#define FSMC_PATT4_ATTHOLD4 ((uint32_t)0x00FF0000) /*!< ATTHOLD4[7:0] bits (Attribute memory 4 hold time) */ +#define FSMC_PATT4_ATTHOLD4_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_PATT4_ATTHOLD4_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_PATT4_ATTHOLD4_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_PATT4_ATTHOLD4_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define FSMC_PATT4_ATTHOLD4_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define FSMC_PATT4_ATTHOLD4_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define FSMC_PATT4_ATTHOLD4_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define FSMC_PATT4_ATTHOLD4_7 ((uint32_t)0x00800000) /*!< Bit 7 */ + +#define FSMC_PATT4_ATTHIZ4 ((uint32_t)0xFF000000) /*!< ATTHIZ4[7:0] bits (Attribute memory 4 databus HiZ time) */ +#define FSMC_PATT4_ATTHIZ4_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_PATT4_ATTHIZ4_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_PATT4_ATTHIZ4_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_PATT4_ATTHIZ4_3 ((uint32_t)0x08000000) /*!< Bit 3 */ +#define FSMC_PATT4_ATTHIZ4_4 ((uint32_t)0x10000000) /*!< Bit 4 */ +#define FSMC_PATT4_ATTHIZ4_5 ((uint32_t)0x20000000) /*!< Bit 5 */ +#define FSMC_PATT4_ATTHIZ4_6 ((uint32_t)0x40000000) /*!< Bit 6 */ +#define FSMC_PATT4_ATTHIZ4_7 ((uint32_t)0x80000000) /*!< Bit 7 */ + +/****************** Bit definition for FSMC_PIO4 register *******************/ +#define FSMC_PIO4_IOSET4 ((uint32_t)0x000000FF) /*!< IOSET4[7:0] bits (I/O 4 setup time) */ +#define FSMC_PIO4_IOSET4_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_PIO4_IOSET4_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_PIO4_IOSET4_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_PIO4_IOSET4_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define FSMC_PIO4_IOSET4_4 ((uint32_t)0x00000010) /*!< Bit 4 */ +#define FSMC_PIO4_IOSET4_5 ((uint32_t)0x00000020) /*!< Bit 5 */ +#define FSMC_PIO4_IOSET4_6 ((uint32_t)0x00000040) /*!< Bit 6 */ +#define FSMC_PIO4_IOSET4_7 ((uint32_t)0x00000080) /*!< Bit 7 */ + +#define FSMC_PIO4_IOWAIT4 ((uint32_t)0x0000FF00) /*!< IOWAIT4[7:0] bits (I/O 4 wait time) */ +#define FSMC_PIO4_IOWAIT4_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_PIO4_IOWAIT4_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_PIO4_IOWAIT4_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_PIO4_IOWAIT4_3 ((uint32_t)0x00000800) /*!< Bit 3 */ +#define FSMC_PIO4_IOWAIT4_4 ((uint32_t)0x00001000) /*!< Bit 4 */ +#define FSMC_PIO4_IOWAIT4_5 ((uint32_t)0x00002000) /*!< Bit 5 */ +#define FSMC_PIO4_IOWAIT4_6 ((uint32_t)0x00004000) /*!< Bit 6 */ +#define FSMC_PIO4_IOWAIT4_7 ((uint32_t)0x00008000) /*!< Bit 7 */ + +#define FSMC_PIO4_IOHOLD4 ((uint32_t)0x00FF0000) /*!< IOHOLD4[7:0] bits (I/O 4 hold time) */ +#define FSMC_PIO4_IOHOLD4_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_PIO4_IOHOLD4_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_PIO4_IOHOLD4_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_PIO4_IOHOLD4_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define FSMC_PIO4_IOHOLD4_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define FSMC_PIO4_IOHOLD4_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define FSMC_PIO4_IOHOLD4_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define FSMC_PIO4_IOHOLD4_7 ((uint32_t)0x00800000) /*!< Bit 7 */ + +#define FSMC_PIO4_IOHIZ4 ((uint32_t)0xFF000000) /*!< IOHIZ4[7:0] bits (I/O 4 databus HiZ time) */ +#define FSMC_PIO4_IOHIZ4_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_PIO4_IOHIZ4_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_PIO4_IOHIZ4_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_PIO4_IOHIZ4_3 ((uint32_t)0x08000000) /*!< Bit 3 */ +#define FSMC_PIO4_IOHIZ4_4 ((uint32_t)0x10000000) /*!< Bit 4 */ +#define FSMC_PIO4_IOHIZ4_5 ((uint32_t)0x20000000) /*!< Bit 5 */ +#define FSMC_PIO4_IOHIZ4_6 ((uint32_t)0x40000000) /*!< Bit 6 */ +#define FSMC_PIO4_IOHIZ4_7 ((uint32_t)0x80000000) /*!< Bit 7 */ + +/****************** Bit definition for FSMC_ECCR2 register ******************/ +#define FSMC_ECCR2_ECC2 ((uint32_t)0xFFFFFFFF) /*!< ECC result */ + +/****************** Bit definition for FSMC_ECCR3 register ******************/ +#define FSMC_ECCR3_ECC3 ((uint32_t)0xFFFFFFFF) /*!< ECC result */ + +/******************************************************************************/ +/* */ +/* SD host Interface */ +/* */ +/******************************************************************************/ + +/****************** Bit definition for SDIO_POWER register ******************/ +#define SDIO_POWER_PWRCTRL ((uint8_t)0x03) /*!< PWRCTRL[1:0] bits (Power supply control bits) */ +#define SDIO_POWER_PWRCTRL_0 ((uint8_t)0x01) /*!< Bit 0 */ +#define SDIO_POWER_PWRCTRL_1 ((uint8_t)0x02) /*!< Bit 1 */ + +/****************** Bit definition for SDIO_CLKCR register ******************/ +#define SDIO_CLKCR_CLKDIV ((uint16_t)0x00FF) /*!< Clock divide factor */ +#define SDIO_CLKCR_CLKEN ((uint16_t)0x0100) /*!< Clock enable bit */ +#define SDIO_CLKCR_PWRSAV ((uint16_t)0x0200) /*!< Power saving configuration bit */ +#define SDIO_CLKCR_BYPASS ((uint16_t)0x0400) /*!< Clock divider bypass enable bit */ + +#define SDIO_CLKCR_WIDBUS ((uint16_t)0x1800) /*!< WIDBUS[1:0] bits (Wide bus mode enable bit) */ +#define SDIO_CLKCR_WIDBUS_0 ((uint16_t)0x0800) /*!< Bit 0 */ +#define SDIO_CLKCR_WIDBUS_1 ((uint16_t)0x1000) /*!< Bit 1 */ + +#define SDIO_CLKCR_NEGEDGE ((uint16_t)0x2000) /*!< SDIO_CK dephasing selection bit */ +#define SDIO_CLKCR_HWFC_EN ((uint16_t)0x4000) /*!< HW Flow Control enable */ + +/******************* Bit definition for SDIO_ARG register *******************/ +#define SDIO_ARG_CMDARG ((uint32_t)0xFFFFFFFF) /*!< Command argument */ + +/******************* Bit definition for SDIO_CMD register *******************/ +#define SDIO_CMD_CMDINDEX ((uint16_t)0x003F) /*!< Command Index */ + +#define SDIO_CMD_WAITRESP ((uint16_t)0x00C0) /*!< WAITRESP[1:0] bits (Wait for response bits) */ +#define SDIO_CMD_WAITRESP_0 ((uint16_t)0x0040) /*!< Bit 0 */ +#define SDIO_CMD_WAITRESP_1 ((uint16_t)0x0080) /*!< Bit 1 */ + +#define SDIO_CMD_WAITINT ((uint16_t)0x0100) /*!< CPSM Waits for Interrupt Request */ +#define SDIO_CMD_WAITPEND ((uint16_t)0x0200) /*!< CPSM Waits for ends of data transfer (CmdPend internal signal) */ +#define SDIO_CMD_CPSMEN ((uint16_t)0x0400) /*!< Command path state machine (CPSM) Enable bit */ +#define SDIO_CMD_SDIOSUSPEND ((uint16_t)0x0800) /*!< SD I/O suspend command */ +#define SDIO_CMD_ENCMDCOMPL ((uint16_t)0x1000) /*!< Enable CMD completion */ +#define SDIO_CMD_NIEN ((uint16_t)0x2000) /*!< Not Interrupt Enable */ +#define SDIO_CMD_CEATACMD ((uint16_t)0x4000) /*!< CE-ATA command */ + +/***************** Bit definition for SDIO_RESPCMD register *****************/ +#define SDIO_RESPCMD_RESPCMD ((uint8_t)0x3F) /*!< Response command index */ + +/****************** Bit definition for SDIO_RESP0 register ******************/ +#define SDIO_RESP0_CARDSTATUS0 ((uint32_t)0xFFFFFFFF) /*!< Card Status */ + +/****************** Bit definition for SDIO_RESP1 register ******************/ +#define SDIO_RESP1_CARDSTATUS1 ((uint32_t)0xFFFFFFFF) /*!< Card Status */ + +/****************** Bit definition for SDIO_RESP2 register ******************/ +#define SDIO_RESP2_CARDSTATUS2 ((uint32_t)0xFFFFFFFF) /*!< Card Status */ + +/****************** Bit definition for SDIO_RESP3 register ******************/ +#define SDIO_RESP3_CARDSTATUS3 ((uint32_t)0xFFFFFFFF) /*!< Card Status */ + +/****************** Bit definition for SDIO_RESP4 register ******************/ +#define SDIO_RESP4_CARDSTATUS4 ((uint32_t)0xFFFFFFFF) /*!< Card Status */ + +/****************** Bit definition for SDIO_DTIMER register *****************/ +#define SDIO_DTIMER_DATATIME ((uint32_t)0xFFFFFFFF) /*!< Data timeout period. */ + +/****************** Bit definition for SDIO_DLEN register *******************/ +#define SDIO_DLEN_DATALENGTH ((uint32_t)0x01FFFFFF) /*!< Data length value */ + +/****************** Bit definition for SDIO_DCTRL register ******************/ +#define SDIO_DCTRL_DTEN ((uint16_t)0x0001) /*!< Data transfer enabled bit */ +#define SDIO_DCTRL_DTDIR ((uint16_t)0x0002) /*!< Data transfer direction selection */ +#define SDIO_DCTRL_DTMODE ((uint16_t)0x0004) /*!< Data transfer mode selection */ +#define SDIO_DCTRL_DMAEN ((uint16_t)0x0008) /*!< DMA enabled bit */ + +#define SDIO_DCTRL_DBLOCKSIZE ((uint16_t)0x00F0) /*!< DBLOCKSIZE[3:0] bits (Data block size) */ +#define SDIO_DCTRL_DBLOCKSIZE_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define SDIO_DCTRL_DBLOCKSIZE_1 ((uint16_t)0x0020) /*!< Bit 1 */ +#define SDIO_DCTRL_DBLOCKSIZE_2 ((uint16_t)0x0040) /*!< Bit 2 */ +#define SDIO_DCTRL_DBLOCKSIZE_3 ((uint16_t)0x0080) /*!< Bit 3 */ + +#define SDIO_DCTRL_RWSTART ((uint16_t)0x0100) /*!< Read wait start */ +#define SDIO_DCTRL_RWSTOP ((uint16_t)0x0200) /*!< Read wait stop */ +#define SDIO_DCTRL_RWMOD ((uint16_t)0x0400) /*!< Read wait mode */ +#define SDIO_DCTRL_SDIOEN ((uint16_t)0x0800) /*!< SD I/O enable functions */ + +/****************** Bit definition for SDIO_DCOUNT register *****************/ +#define SDIO_DCOUNT_DATACOUNT ((uint32_t)0x01FFFFFF) /*!< Data count value */ + +/****************** Bit definition for SDIO_STA register ********************/ +#define SDIO_STA_CCRCFAIL ((uint32_t)0x00000001) /*!< Command response received (CRC check failed) */ +#define SDIO_STA_DCRCFAIL ((uint32_t)0x00000002) /*!< Data block sent/received (CRC check failed) */ +#define SDIO_STA_CTIMEOUT ((uint32_t)0x00000004) /*!< Command response timeout */ +#define SDIO_STA_DTIMEOUT ((uint32_t)0x00000008) /*!< Data timeout */ +#define SDIO_STA_TXUNDERR ((uint32_t)0x00000010) /*!< Transmit FIFO underrun error */ +#define SDIO_STA_RXOVERR ((uint32_t)0x00000020) /*!< Received FIFO overrun error */ +#define SDIO_STA_CMDREND ((uint32_t)0x00000040) /*!< Command response received (CRC check passed) */ +#define SDIO_STA_CMDSENT ((uint32_t)0x00000080) /*!< Command sent (no response required) */ +#define SDIO_STA_DATAEND ((uint32_t)0x00000100) /*!< Data end (data counter, SDIDCOUNT, is zero) */ +#define SDIO_STA_STBITERR ((uint32_t)0x00000200) /*!< Start bit not detected on all data signals in wide bus mode */ +#define SDIO_STA_DBCKEND ((uint32_t)0x00000400) /*!< Data block sent/received (CRC check passed) */ +#define SDIO_STA_CMDACT ((uint32_t)0x00000800) /*!< Command transfer in progress */ +#define SDIO_STA_TXACT ((uint32_t)0x00001000) /*!< Data transmit in progress */ +#define SDIO_STA_RXACT ((uint32_t)0x00002000) /*!< Data receive in progress */ +#define SDIO_STA_TXFIFOHE ((uint32_t)0x00004000) /*!< Transmit FIFO Half Empty: at least 8 words can be written into the FIFO */ +#define SDIO_STA_RXFIFOHF ((uint32_t)0x00008000) /*!< Receive FIFO Half Full: there are at least 8 words in the FIFO */ +#define SDIO_STA_TXFIFOF ((uint32_t)0x00010000) /*!< Transmit FIFO full */ +#define SDIO_STA_RXFIFOF ((uint32_t)0x00020000) /*!< Receive FIFO full */ +#define SDIO_STA_TXFIFOE ((uint32_t)0x00040000) /*!< Transmit FIFO empty */ +#define SDIO_STA_RXFIFOE ((uint32_t)0x00080000) /*!< Receive FIFO empty */ +#define SDIO_STA_TXDAVL ((uint32_t)0x00100000) /*!< Data available in transmit FIFO */ +#define SDIO_STA_RXDAVL ((uint32_t)0x00200000) /*!< Data available in receive FIFO */ +#define SDIO_STA_SDIOIT ((uint32_t)0x00400000) /*!< SDIO interrupt received */ +#define SDIO_STA_CEATAEND ((uint32_t)0x00800000) /*!< CE-ATA command completion signal received for CMD61 */ + +/******************* Bit definition for SDIO_ICR register *******************/ +#define SDIO_ICR_CCRCFAILC ((uint32_t)0x00000001) /*!< CCRCFAIL flag clear bit */ +#define SDIO_ICR_DCRCFAILC ((uint32_t)0x00000002) /*!< DCRCFAIL flag clear bit */ +#define SDIO_ICR_CTIMEOUTC ((uint32_t)0x00000004) /*!< CTIMEOUT flag clear bit */ +#define SDIO_ICR_DTIMEOUTC ((uint32_t)0x00000008) /*!< DTIMEOUT flag clear bit */ +#define SDIO_ICR_TXUNDERRC ((uint32_t)0x00000010) /*!< TXUNDERR flag clear bit */ +#define SDIO_ICR_RXOVERRC ((uint32_t)0x00000020) /*!< RXOVERR flag clear bit */ +#define SDIO_ICR_CMDRENDC ((uint32_t)0x00000040) /*!< CMDREND flag clear bit */ +#define SDIO_ICR_CMDSENTC ((uint32_t)0x00000080) /*!< CMDSENT flag clear bit */ +#define SDIO_ICR_DATAENDC ((uint32_t)0x00000100) /*!< DATAEND flag clear bit */ +#define SDIO_ICR_STBITERRC ((uint32_t)0x00000200) /*!< STBITERR flag clear bit */ +#define SDIO_ICR_DBCKENDC ((uint32_t)0x00000400) /*!< DBCKEND flag clear bit */ +#define SDIO_ICR_SDIOITC ((uint32_t)0x00400000) /*!< SDIOIT flag clear bit */ +#define SDIO_ICR_CEATAENDC ((uint32_t)0x00800000) /*!< CEATAEND flag clear bit */ + +/****************** Bit definition for SDIO_MASK register *******************/ +#define SDIO_MASK_CCRCFAILIE ((uint32_t)0x00000001) /*!< Command CRC Fail Interrupt Enable */ +#define SDIO_MASK_DCRCFAILIE ((uint32_t)0x00000002) /*!< Data CRC Fail Interrupt Enable */ +#define SDIO_MASK_CTIMEOUTIE ((uint32_t)0x00000004) /*!< Command TimeOut Interrupt Enable */ +#define SDIO_MASK_DTIMEOUTIE ((uint32_t)0x00000008) /*!< Data TimeOut Interrupt Enable */ +#define SDIO_MASK_TXUNDERRIE ((uint32_t)0x00000010) /*!< Tx FIFO UnderRun Error Interrupt Enable */ +#define SDIO_MASK_RXOVERRIE ((uint32_t)0x00000020) /*!< Rx FIFO OverRun Error Interrupt Enable */ +#define SDIO_MASK_CMDRENDIE ((uint32_t)0x00000040) /*!< Command Response Received Interrupt Enable */ +#define SDIO_MASK_CMDSENTIE ((uint32_t)0x00000080) /*!< Command Sent Interrupt Enable */ +#define SDIO_MASK_DATAENDIE ((uint32_t)0x00000100) /*!< Data End Interrupt Enable */ +#define SDIO_MASK_STBITERRIE ((uint32_t)0x00000200) /*!< Start Bit Error Interrupt Enable */ +#define SDIO_MASK_DBCKENDIE ((uint32_t)0x00000400) /*!< Data Block End Interrupt Enable */ +#define SDIO_MASK_CMDACTIE ((uint32_t)0x00000800) /*!< Command Acting Interrupt Enable */ +#define SDIO_MASK_TXACTIE ((uint32_t)0x00001000) /*!< Data Transmit Acting Interrupt Enable */ +#define SDIO_MASK_RXACTIE ((uint32_t)0x00002000) /*!< Data receive acting interrupt enabled */ +#define SDIO_MASK_TXFIFOHEIE ((uint32_t)0x00004000) /*!< Tx FIFO Half Empty interrupt Enable */ +#define SDIO_MASK_RXFIFOHFIE ((uint32_t)0x00008000) /*!< Rx FIFO Half Full interrupt Enable */ +#define SDIO_MASK_TXFIFOFIE ((uint32_t)0x00010000) /*!< Tx FIFO Full interrupt Enable */ +#define SDIO_MASK_RXFIFOFIE ((uint32_t)0x00020000) /*!< Rx FIFO Full interrupt Enable */ +#define SDIO_MASK_TXFIFOEIE ((uint32_t)0x00040000) /*!< Tx FIFO Empty interrupt Enable */ +#define SDIO_MASK_RXFIFOEIE ((uint32_t)0x00080000) /*!< Rx FIFO Empty interrupt Enable */ +#define SDIO_MASK_TXDAVLIE ((uint32_t)0x00100000) /*!< Data available in Tx FIFO interrupt Enable */ +#define SDIO_MASK_RXDAVLIE ((uint32_t)0x00200000) /*!< Data available in Rx FIFO interrupt Enable */ +#define SDIO_MASK_SDIOITIE ((uint32_t)0x00400000) /*!< SDIO Mode Interrupt Received interrupt Enable */ +#define SDIO_MASK_CEATAENDIE ((uint32_t)0x00800000) /*!< CE-ATA command completion signal received Interrupt Enable */ + +/***************** Bit definition for SDIO_FIFOCNT register *****************/ +#define SDIO_FIFOCNT_FIFOCOUNT ((uint32_t)0x00FFFFFF) /*!< Remaining number of words to be written to or read from the FIFO */ + +/****************** Bit definition for SDIO_FIFO register *******************/ +#define SDIO_FIFO_FIFODATA ((uint32_t)0xFFFFFFFF) /*!< Receive and transmit FIFO data */ + +/******************************************************************************/ +/* */ +/* USB Device FS */ +/* */ +/******************************************************************************/ + +/*!< Endpoint-specific registers */ +/******************* Bit definition for USB_EP0R register *******************/ +#define USB_EP0R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP0R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP0R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP0R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP0R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP0R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP0R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP0R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP0R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP0R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP0R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP0R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP0R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP0R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP0R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP0R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/******************* Bit definition for USB_EP1R register *******************/ +#define USB_EP1R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP1R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP1R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP1R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP1R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP1R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP1R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP1R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP1R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP1R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP1R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP1R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP1R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP1R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP1R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP1R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/******************* Bit definition for USB_EP2R register *******************/ +#define USB_EP2R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP2R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP2R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP2R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP2R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP2R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP2R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP2R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP2R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP2R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP2R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP2R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP2R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP2R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP2R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP2R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/******************* Bit definition for USB_EP3R register *******************/ +#define USB_EP3R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP3R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP3R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP3R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP3R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP3R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP3R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP3R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP3R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP3R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP3R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP3R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP3R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP3R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP3R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP3R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/******************* Bit definition for USB_EP4R register *******************/ +#define USB_EP4R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP4R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP4R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP4R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP4R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP4R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP4R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP4R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP4R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP4R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP4R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP4R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP4R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP4R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP4R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP4R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/******************* Bit definition for USB_EP5R register *******************/ +#define USB_EP5R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP5R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP5R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP5R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP5R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP5R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP5R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP5R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP5R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP5R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP5R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP5R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP5R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP5R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP5R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP5R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/******************* Bit definition for USB_EP6R register *******************/ +#define USB_EP6R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP6R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP6R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP6R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP6R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP6R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP6R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP6R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP6R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP6R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP6R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP6R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP6R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP6R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP6R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP6R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/******************* Bit definition for USB_EP7R register *******************/ +#define USB_EP7R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP7R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP7R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP7R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP7R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP7R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP7R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP7R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP7R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP7R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP7R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP7R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP7R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP7R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP7R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP7R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/*!< Common registers */ +/******************* Bit definition for USB_CNTR register *******************/ +#define USB_CNTR_FRES ((uint16_t)0x0001) /*!< Force USB Reset */ +#define USB_CNTR_PDWN ((uint16_t)0x0002) /*!< Power down */ +#define USB_CNTR_LP_MODE ((uint16_t)0x0004) /*!< Low-power mode */ +#define USB_CNTR_FSUSP ((uint16_t)0x0008) /*!< Force suspend */ +#define USB_CNTR_RESUME ((uint16_t)0x0010) /*!< Resume request */ +#define USB_CNTR_ESOFM ((uint16_t)0x0100) /*!< Expected Start Of Frame Interrupt Mask */ +#define USB_CNTR_SOFM ((uint16_t)0x0200) /*!< Start Of Frame Interrupt Mask */ +#define USB_CNTR_RESETM ((uint16_t)0x0400) /*!< RESET Interrupt Mask */ +#define USB_CNTR_SUSPM ((uint16_t)0x0800) /*!< Suspend mode Interrupt Mask */ +#define USB_CNTR_WKUPM ((uint16_t)0x1000) /*!< Wakeup Interrupt Mask */ +#define USB_CNTR_ERRM ((uint16_t)0x2000) /*!< Error Interrupt Mask */ +#define USB_CNTR_PMAOVRM ((uint16_t)0x4000) /*!< Packet Memory Area Over / Underrun Interrupt Mask */ +#define USB_CNTR_CTRM ((uint16_t)0x8000) /*!< Correct Transfer Interrupt Mask */ + +/******************* Bit definition for USB_ISTR register *******************/ +#define USB_ISTR_EP_ID ((uint16_t)0x000F) /*!< Endpoint Identifier */ +#define USB_ISTR_DIR ((uint16_t)0x0010) /*!< Direction of transaction */ +#define USB_ISTR_ESOF ((uint16_t)0x0100) /*!< Expected Start Of Frame */ +#define USB_ISTR_SOF ((uint16_t)0x0200) /*!< Start Of Frame */ +#define USB_ISTR_RESET ((uint16_t)0x0400) /*!< USB RESET request */ +#define USB_ISTR_SUSP ((uint16_t)0x0800) /*!< Suspend mode request */ +#define USB_ISTR_WKUP ((uint16_t)0x1000) /*!< Wake up */ +#define USB_ISTR_ERR ((uint16_t)0x2000) /*!< Error */ +#define USB_ISTR_PMAOVR ((uint16_t)0x4000) /*!< Packet Memory Area Over / Underrun */ +#define USB_ISTR_CTR ((uint16_t)0x8000) /*!< Correct Transfer */ + +/******************* Bit definition for USB_FNR register ********************/ +#define USB_FNR_FN ((uint16_t)0x07FF) /*!< Frame Number */ +#define USB_FNR_LSOF ((uint16_t)0x1800) /*!< Lost SOF */ +#define USB_FNR_LCK ((uint16_t)0x2000) /*!< Locked */ +#define USB_FNR_RXDM ((uint16_t)0x4000) /*!< Receive Data - Line Status */ +#define USB_FNR_RXDP ((uint16_t)0x8000) /*!< Receive Data + Line Status */ + +/****************** Bit definition for USB_DADDR register *******************/ +#define USB_DADDR_ADD ((uint8_t)0x7F) /*!< ADD[6:0] bits (Device Address) */ +#define USB_DADDR_ADD0 ((uint8_t)0x01) /*!< Bit 0 */ +#define USB_DADDR_ADD1 ((uint8_t)0x02) /*!< Bit 1 */ +#define USB_DADDR_ADD2 ((uint8_t)0x04) /*!< Bit 2 */ +#define USB_DADDR_ADD3 ((uint8_t)0x08) /*!< Bit 3 */ +#define USB_DADDR_ADD4 ((uint8_t)0x10) /*!< Bit 4 */ +#define USB_DADDR_ADD5 ((uint8_t)0x20) /*!< Bit 5 */ +#define USB_DADDR_ADD6 ((uint8_t)0x40) /*!< Bit 6 */ + +#define USB_DADDR_EF ((uint8_t)0x80) /*!< Enable Function */ + +/****************** Bit definition for USB_BTABLE register ******************/ +#define USB_BTABLE_BTABLE ((uint16_t)0xFFF8) /*!< Buffer Table */ + +/*!< Buffer descriptor table */ +/***************** Bit definition for USB_ADDR0_TX register *****************/ +#define USB_ADDR0_TX_ADDR0_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 0 */ + +/***************** Bit definition for USB_ADDR1_TX register *****************/ +#define USB_ADDR1_TX_ADDR1_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 1 */ + +/***************** Bit definition for USB_ADDR2_TX register *****************/ +#define USB_ADDR2_TX_ADDR2_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 2 */ + +/***************** Bit definition for USB_ADDR3_TX register *****************/ +#define USB_ADDR3_TX_ADDR3_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 3 */ + +/***************** Bit definition for USB_ADDR4_TX register *****************/ +#define USB_ADDR4_TX_ADDR4_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 4 */ + +/***************** Bit definition for USB_ADDR5_TX register *****************/ +#define USB_ADDR5_TX_ADDR5_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 5 */ + +/***************** Bit definition for USB_ADDR6_TX register *****************/ +#define USB_ADDR6_TX_ADDR6_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 6 */ + +/***************** Bit definition for USB_ADDR7_TX register *****************/ +#define USB_ADDR7_TX_ADDR7_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 7 */ + +/*----------------------------------------------------------------------------*/ + +/***************** Bit definition for USB_COUNT0_TX register ****************/ +#define USB_COUNT0_TX_COUNT0_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 0 */ + +/***************** Bit definition for USB_COUNT1_TX register ****************/ +#define USB_COUNT1_TX_COUNT1_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 1 */ + +/***************** Bit definition for USB_COUNT2_TX register ****************/ +#define USB_COUNT2_TX_COUNT2_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 2 */ + +/***************** Bit definition for USB_COUNT3_TX register ****************/ +#define USB_COUNT3_TX_COUNT3_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 3 */ + +/***************** Bit definition for USB_COUNT4_TX register ****************/ +#define USB_COUNT4_TX_COUNT4_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 4 */ + +/***************** Bit definition for USB_COUNT5_TX register ****************/ +#define USB_COUNT5_TX_COUNT5_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 5 */ + +/***************** Bit definition for USB_COUNT6_TX register ****************/ +#define USB_COUNT6_TX_COUNT6_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 6 */ + +/***************** Bit definition for USB_COUNT7_TX register ****************/ +#define USB_COUNT7_TX_COUNT7_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 7 */ + +/*----------------------------------------------------------------------------*/ + +/**************** Bit definition for USB_COUNT0_TX_0 register ***************/ +#define USB_COUNT0_TX_0_COUNT0_TX_0 ((uint32_t)0x000003FF) /*!< Transmission Byte Count 0 (low) */ + +/**************** Bit definition for USB_COUNT0_TX_1 register ***************/ +#define USB_COUNT0_TX_1_COUNT0_TX_1 ((uint32_t)0x03FF0000) /*!< Transmission Byte Count 0 (high) */ + +/**************** Bit definition for USB_COUNT1_TX_0 register ***************/ +#define USB_COUNT1_TX_0_COUNT1_TX_0 ((uint32_t)0x000003FF) /*!< Transmission Byte Count 1 (low) */ + +/**************** Bit definition for USB_COUNT1_TX_1 register ***************/ +#define USB_COUNT1_TX_1_COUNT1_TX_1 ((uint32_t)0x03FF0000) /*!< Transmission Byte Count 1 (high) */ + +/**************** Bit definition for USB_COUNT2_TX_0 register ***************/ +#define USB_COUNT2_TX_0_COUNT2_TX_0 ((uint32_t)0x000003FF) /*!< Transmission Byte Count 2 (low) */ + +/**************** Bit definition for USB_COUNT2_TX_1 register ***************/ +#define USB_COUNT2_TX_1_COUNT2_TX_1 ((uint32_t)0x03FF0000) /*!< Transmission Byte Count 2 (high) */ + +/**************** Bit definition for USB_COUNT3_TX_0 register ***************/ +#define USB_COUNT3_TX_0_COUNT3_TX_0 ((uint16_t)0x000003FF) /*!< Transmission Byte Count 3 (low) */ + +/**************** Bit definition for USB_COUNT3_TX_1 register ***************/ +#define USB_COUNT3_TX_1_COUNT3_TX_1 ((uint16_t)0x03FF0000) /*!< Transmission Byte Count 3 (high) */ + +/**************** Bit definition for USB_COUNT4_TX_0 register ***************/ +#define USB_COUNT4_TX_0_COUNT4_TX_0 ((uint32_t)0x000003FF) /*!< Transmission Byte Count 4 (low) */ + +/**************** Bit definition for USB_COUNT4_TX_1 register ***************/ +#define USB_COUNT4_TX_1_COUNT4_TX_1 ((uint32_t)0x03FF0000) /*!< Transmission Byte Count 4 (high) */ + +/**************** Bit definition for USB_COUNT5_TX_0 register ***************/ +#define USB_COUNT5_TX_0_COUNT5_TX_0 ((uint32_t)0x000003FF) /*!< Transmission Byte Count 5 (low) */ + +/**************** Bit definition for USB_COUNT5_TX_1 register ***************/ +#define USB_COUNT5_TX_1_COUNT5_TX_1 ((uint32_t)0x03FF0000) /*!< Transmission Byte Count 5 (high) */ + +/**************** Bit definition for USB_COUNT6_TX_0 register ***************/ +#define USB_COUNT6_TX_0_COUNT6_TX_0 ((uint32_t)0x000003FF) /*!< Transmission Byte Count 6 (low) */ + +/**************** Bit definition for USB_COUNT6_TX_1 register ***************/ +#define USB_COUNT6_TX_1_COUNT6_TX_1 ((uint32_t)0x03FF0000) /*!< Transmission Byte Count 6 (high) */ + +/**************** Bit definition for USB_COUNT7_TX_0 register ***************/ +#define USB_COUNT7_TX_0_COUNT7_TX_0 ((uint32_t)0x000003FF) /*!< Transmission Byte Count 7 (low) */ + +/**************** Bit definition for USB_COUNT7_TX_1 register ***************/ +#define USB_COUNT7_TX_1_COUNT7_TX_1 ((uint32_t)0x03FF0000) /*!< Transmission Byte Count 7 (high) */ + +/*----------------------------------------------------------------------------*/ + +/***************** Bit definition for USB_ADDR0_RX register *****************/ +#define USB_ADDR0_RX_ADDR0_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 0 */ + +/***************** Bit definition for USB_ADDR1_RX register *****************/ +#define USB_ADDR1_RX_ADDR1_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 1 */ + +/***************** Bit definition for USB_ADDR2_RX register *****************/ +#define USB_ADDR2_RX_ADDR2_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 2 */ + +/***************** Bit definition for USB_ADDR3_RX register *****************/ +#define USB_ADDR3_RX_ADDR3_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 3 */ + +/***************** Bit definition for USB_ADDR4_RX register *****************/ +#define USB_ADDR4_RX_ADDR4_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 4 */ + +/***************** Bit definition for USB_ADDR5_RX register *****************/ +#define USB_ADDR5_RX_ADDR5_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 5 */ + +/***************** Bit definition for USB_ADDR6_RX register *****************/ +#define USB_ADDR6_RX_ADDR6_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 6 */ + +/***************** Bit definition for USB_ADDR7_RX register *****************/ +#define USB_ADDR7_RX_ADDR7_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 7 */ + +/*----------------------------------------------------------------------------*/ + +/***************** Bit definition for USB_COUNT0_RX register ****************/ +#define USB_COUNT0_RX_COUNT0_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT0_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT0_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT0_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT0_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT0_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT0_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT0_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/***************** Bit definition for USB_COUNT1_RX register ****************/ +#define USB_COUNT1_RX_COUNT1_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT1_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT1_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT1_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT1_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT1_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT1_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT1_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/***************** Bit definition for USB_COUNT2_RX register ****************/ +#define USB_COUNT2_RX_COUNT2_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT2_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT2_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT2_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT2_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT2_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT2_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT2_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/***************** Bit definition for USB_COUNT3_RX register ****************/ +#define USB_COUNT3_RX_COUNT3_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT3_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT3_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT3_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT3_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT3_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT3_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT3_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/***************** Bit definition for USB_COUNT4_RX register ****************/ +#define USB_COUNT4_RX_COUNT4_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT4_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT4_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT4_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT4_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT4_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT4_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT4_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/***************** Bit definition for USB_COUNT5_RX register ****************/ +#define USB_COUNT5_RX_COUNT5_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT5_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT5_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT5_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT5_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT5_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT5_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT5_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/***************** Bit definition for USB_COUNT6_RX register ****************/ +#define USB_COUNT6_RX_COUNT6_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT6_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT6_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT6_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT6_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT6_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT6_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT6_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/***************** Bit definition for USB_COUNT7_RX register ****************/ +#define USB_COUNT7_RX_COUNT7_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT7_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT7_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT7_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT7_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT7_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT7_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT7_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/*----------------------------------------------------------------------------*/ + +/**************** Bit definition for USB_COUNT0_RX_0 register ***************/ +#define USB_COUNT0_RX_0_COUNT0_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT0_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT0_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT0_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT0_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT0_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT0_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT0_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/**************** Bit definition for USB_COUNT0_RX_1 register ***************/ +#define USB_COUNT0_RX_1_COUNT0_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT0_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT0_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 1 */ +#define USB_COUNT0_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT0_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT0_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT0_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT0_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/**************** Bit definition for USB_COUNT1_RX_0 register ***************/ +#define USB_COUNT1_RX_0_COUNT1_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT1_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT1_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT1_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT1_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT1_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT1_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT1_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/**************** Bit definition for USB_COUNT1_RX_1 register ***************/ +#define USB_COUNT1_RX_1_COUNT1_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT1_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT1_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define USB_COUNT1_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT1_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT1_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT1_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT1_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/**************** Bit definition for USB_COUNT2_RX_0 register ***************/ +#define USB_COUNT2_RX_0_COUNT2_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT2_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT2_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT2_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT2_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT2_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT2_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT2_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/**************** Bit definition for USB_COUNT2_RX_1 register ***************/ +#define USB_COUNT2_RX_1_COUNT2_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT2_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT2_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define USB_COUNT2_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT2_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT2_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT2_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT2_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/**************** Bit definition for USB_COUNT3_RX_0 register ***************/ +#define USB_COUNT3_RX_0_COUNT3_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT3_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT3_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT3_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT3_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT3_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT3_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT3_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/**************** Bit definition for USB_COUNT3_RX_1 register ***************/ +#define USB_COUNT3_RX_1_COUNT3_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT3_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT3_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define USB_COUNT3_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT3_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT3_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT3_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT3_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/**************** Bit definition for USB_COUNT4_RX_0 register ***************/ +#define USB_COUNT4_RX_0_COUNT4_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT4_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT4_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT4_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT4_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT4_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT4_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT4_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/**************** Bit definition for USB_COUNT4_RX_1 register ***************/ +#define USB_COUNT4_RX_1_COUNT4_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT4_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT4_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define USB_COUNT4_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT4_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT4_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT4_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT4_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/**************** Bit definition for USB_COUNT5_RX_0 register ***************/ +#define USB_COUNT5_RX_0_COUNT5_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT5_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT5_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT5_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT5_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT5_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT5_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT5_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/**************** Bit definition for USB_COUNT5_RX_1 register ***************/ +#define USB_COUNT5_RX_1_COUNT5_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT5_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT5_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define USB_COUNT5_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT5_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT5_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT5_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT5_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/*************** Bit definition for USB_COUNT6_RX_0 register ***************/ +#define USB_COUNT6_RX_0_COUNT6_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT6_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT6_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT6_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT6_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT6_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT6_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT6_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/**************** Bit definition for USB_COUNT6_RX_1 register ***************/ +#define USB_COUNT6_RX_1_COUNT6_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT6_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT6_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define USB_COUNT6_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT6_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT6_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT6_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT6_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/*************** Bit definition for USB_COUNT7_RX_0 register ****************/ +#define USB_COUNT7_RX_0_COUNT7_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT7_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT7_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT7_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT7_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT7_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT7_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT7_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/*************** Bit definition for USB_COUNT7_RX_1 register ****************/ +#define USB_COUNT7_RX_1_COUNT7_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT7_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT7_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define USB_COUNT7_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT7_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT7_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT7_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT7_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/******************************************************************************/ +/* */ +/* Controller Area Network */ +/* */ +/******************************************************************************/ + +/*!< CAN control and status registers */ +/******************* Bit definition for CAN_MCR register ********************/ +#define CAN_MCR_INRQ ((uint16_t)0x0001) /*!< Initialization Request */ +#define CAN_MCR_SLEEP ((uint16_t)0x0002) /*!< Sleep Mode Request */ +#define CAN_MCR_TXFP ((uint16_t)0x0004) /*!< Transmit FIFO Priority */ +#define CAN_MCR_RFLM ((uint16_t)0x0008) /*!< Receive FIFO Locked Mode */ +#define CAN_MCR_NART ((uint16_t)0x0010) /*!< No Automatic Retransmission */ +#define CAN_MCR_AWUM ((uint16_t)0x0020) /*!< Automatic Wakeup Mode */ +#define CAN_MCR_ABOM ((uint16_t)0x0040) /*!< Automatic Bus-Off Management */ +#define CAN_MCR_TTCM ((uint16_t)0x0080) /*!< Time Triggered Communication Mode */ +#define CAN_MCR_RESET ((uint16_t)0x8000) /*!< CAN software master reset */ + +/******************* Bit definition for CAN_MSR register ********************/ +#define CAN_MSR_INAK ((uint16_t)0x0001) /*!< Initialization Acknowledge */ +#define CAN_MSR_SLAK ((uint16_t)0x0002) /*!< Sleep Acknowledge */ +#define CAN_MSR_ERRI ((uint16_t)0x0004) /*!< Error Interrupt */ +#define CAN_MSR_WKUI ((uint16_t)0x0008) /*!< Wakeup Interrupt */ +#define CAN_MSR_SLAKI ((uint16_t)0x0010) /*!< Sleep Acknowledge Interrupt */ +#define CAN_MSR_TXM ((uint16_t)0x0100) /*!< Transmit Mode */ +#define CAN_MSR_RXM ((uint16_t)0x0200) /*!< Receive Mode */ +#define CAN_MSR_SAMP ((uint16_t)0x0400) /*!< Last Sample Point */ +#define CAN_MSR_RX ((uint16_t)0x0800) /*!< CAN Rx Signal */ + +/******************* Bit definition for CAN_TSR register ********************/ +#define CAN_TSR_RQCP0 ((uint32_t)0x00000001) /*!< Request Completed Mailbox0 */ +#define CAN_TSR_TXOK0 ((uint32_t)0x00000002) /*!< Transmission OK of Mailbox0 */ +#define CAN_TSR_ALST0 ((uint32_t)0x00000004) /*!< Arbitration Lost for Mailbox0 */ +#define CAN_TSR_TERR0 ((uint32_t)0x00000008) /*!< Transmission Error of Mailbox0 */ +#define CAN_TSR_ABRQ0 ((uint32_t)0x00000080) /*!< Abort Request for Mailbox0 */ +#define CAN_TSR_RQCP1 ((uint32_t)0x00000100) /*!< Request Completed Mailbox1 */ +#define CAN_TSR_TXOK1 ((uint32_t)0x00000200) /*!< Transmission OK of Mailbox1 */ +#define CAN_TSR_ALST1 ((uint32_t)0x00000400) /*!< Arbitration Lost for Mailbox1 */ +#define CAN_TSR_TERR1 ((uint32_t)0x00000800) /*!< Transmission Error of Mailbox1 */ +#define CAN_TSR_ABRQ1 ((uint32_t)0x00008000) /*!< Abort Request for Mailbox 1 */ +#define CAN_TSR_RQCP2 ((uint32_t)0x00010000) /*!< Request Completed Mailbox2 */ +#define CAN_TSR_TXOK2 ((uint32_t)0x00020000) /*!< Transmission OK of Mailbox 2 */ +#define CAN_TSR_ALST2 ((uint32_t)0x00040000) /*!< Arbitration Lost for mailbox 2 */ +#define CAN_TSR_TERR2 ((uint32_t)0x00080000) /*!< Transmission Error of Mailbox 2 */ +#define CAN_TSR_ABRQ2 ((uint32_t)0x00800000) /*!< Abort Request for Mailbox 2 */ +#define CAN_TSR_CODE ((uint32_t)0x03000000) /*!< Mailbox Code */ + +#define CAN_TSR_TME ((uint32_t)0x1C000000) /*!< TME[2:0] bits */ +#define CAN_TSR_TME0 ((uint32_t)0x04000000) /*!< Transmit Mailbox 0 Empty */ +#define CAN_TSR_TME1 ((uint32_t)0x08000000) /*!< Transmit Mailbox 1 Empty */ +#define CAN_TSR_TME2 ((uint32_t)0x10000000) /*!< Transmit Mailbox 2 Empty */ + +#define CAN_TSR_LOW ((uint32_t)0xE0000000) /*!< LOW[2:0] bits */ +#define CAN_TSR_LOW0 ((uint32_t)0x20000000) /*!< Lowest Priority Flag for Mailbox 0 */ +#define CAN_TSR_LOW1 ((uint32_t)0x40000000) /*!< Lowest Priority Flag for Mailbox 1 */ +#define CAN_TSR_LOW2 ((uint32_t)0x80000000) /*!< Lowest Priority Flag for Mailbox 2 */ + +/******************* Bit definition for CAN_RF0R register *******************/ +#define CAN_RF0R_FMP0 ((uint8_t)0x03) /*!< FIFO 0 Message Pending */ +#define CAN_RF0R_FULL0 ((uint8_t)0x08) /*!< FIFO 0 Full */ +#define CAN_RF0R_FOVR0 ((uint8_t)0x10) /*!< FIFO 0 Overrun */ +#define CAN_RF0R_RFOM0 ((uint8_t)0x20) /*!< Release FIFO 0 Output Mailbox */ + +/******************* Bit definition for CAN_RF1R register *******************/ +#define CAN_RF1R_FMP1 ((uint8_t)0x03) /*!< FIFO 1 Message Pending */ +#define CAN_RF1R_FULL1 ((uint8_t)0x08) /*!< FIFO 1 Full */ +#define CAN_RF1R_FOVR1 ((uint8_t)0x10) /*!< FIFO 1 Overrun */ +#define CAN_RF1R_RFOM1 ((uint8_t)0x20) /*!< Release FIFO 1 Output Mailbox */ + +/******************** Bit definition for CAN_IER register *******************/ +#define CAN_IER_TMEIE ((uint32_t)0x00000001) /*!< Transmit Mailbox Empty Interrupt Enable */ +#define CAN_IER_FMPIE0 ((uint32_t)0x00000002) /*!< FIFO Message Pending Interrupt Enable */ +#define CAN_IER_FFIE0 ((uint32_t)0x00000004) /*!< FIFO Full Interrupt Enable */ +#define CAN_IER_FOVIE0 ((uint32_t)0x00000008) /*!< FIFO Overrun Interrupt Enable */ +#define CAN_IER_FMPIE1 ((uint32_t)0x00000010) /*!< FIFO Message Pending Interrupt Enable */ +#define CAN_IER_FFIE1 ((uint32_t)0x00000020) /*!< FIFO Full Interrupt Enable */ +#define CAN_IER_FOVIE1 ((uint32_t)0x00000040) /*!< FIFO Overrun Interrupt Enable */ +#define CAN_IER_EWGIE ((uint32_t)0x00000100) /*!< Error Warning Interrupt Enable */ +#define CAN_IER_EPVIE ((uint32_t)0x00000200) /*!< Error Passive Interrupt Enable */ +#define CAN_IER_BOFIE ((uint32_t)0x00000400) /*!< Bus-Off Interrupt Enable */ +#define CAN_IER_LECIE ((uint32_t)0x00000800) /*!< Last Error Code Interrupt Enable */ +#define CAN_IER_ERRIE ((uint32_t)0x00008000) /*!< Error Interrupt Enable */ +#define CAN_IER_WKUIE ((uint32_t)0x00010000) /*!< Wakeup Interrupt Enable */ +#define CAN_IER_SLKIE ((uint32_t)0x00020000) /*!< Sleep Interrupt Enable */ + +/******************** Bit definition for CAN_ESR register *******************/ +#define CAN_ESR_EWGF ((uint32_t)0x00000001) /*!< Error Warning Flag */ +#define CAN_ESR_EPVF ((uint32_t)0x00000002) /*!< Error Passive Flag */ +#define CAN_ESR_BOFF ((uint32_t)0x00000004) /*!< Bus-Off Flag */ + +#define CAN_ESR_LEC ((uint32_t)0x00000070) /*!< LEC[2:0] bits (Last Error Code) */ +#define CAN_ESR_LEC_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define CAN_ESR_LEC_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define CAN_ESR_LEC_2 ((uint32_t)0x00000040) /*!< Bit 2 */ + +#define CAN_ESR_TEC ((uint32_t)0x00FF0000) /*!< Least significant byte of the 9-bit Transmit Error Counter */ +#define CAN_ESR_REC ((uint32_t)0xFF000000) /*!< Receive Error Counter */ + +/******************* Bit definition for CAN_BTR register ********************/ +#define CAN_BTR_BRP ((uint32_t)0x000003FF) /*!< Baud Rate Prescaler */ +#define CAN_BTR_TS1 ((uint32_t)0x000F0000) /*!< Time Segment 1 */ +#define CAN_BTR_TS2 ((uint32_t)0x00700000) /*!< Time Segment 2 */ +#define CAN_BTR_SJW ((uint32_t)0x03000000) /*!< Resynchronization Jump Width */ +#define CAN_BTR_LBKM ((uint32_t)0x40000000) /*!< Loop Back Mode (Debug) */ +#define CAN_BTR_SILM ((uint32_t)0x80000000) /*!< Silent Mode */ + +/*!< Mailbox registers */ +/****************** Bit definition for CAN_TI0R register ********************/ +#define CAN_TI0R_TXRQ ((uint32_t)0x00000001) /*!< Transmit Mailbox Request */ +#define CAN_TI0R_RTR ((uint32_t)0x00000002) /*!< Remote Transmission Request */ +#define CAN_TI0R_IDE ((uint32_t)0x00000004) /*!< Identifier Extension */ +#define CAN_TI0R_EXID ((uint32_t)0x001FFFF8) /*!< Extended Identifier */ +#define CAN_TI0R_STID ((uint32_t)0xFFE00000) /*!< Standard Identifier or Extended Identifier */ + +/****************** Bit definition for CAN_TDT0R register *******************/ +#define CAN_TDT0R_DLC ((uint32_t)0x0000000F) /*!< Data Length Code */ +#define CAN_TDT0R_TGT ((uint32_t)0x00000100) /*!< Transmit Global Time */ +#define CAN_TDT0R_TIME ((uint32_t)0xFFFF0000) /*!< Message Time Stamp */ + +/****************** Bit definition for CAN_TDL0R register *******************/ +#define CAN_TDL0R_DATA0 ((uint32_t)0x000000FF) /*!< Data byte 0 */ +#define CAN_TDL0R_DATA1 ((uint32_t)0x0000FF00) /*!< Data byte 1 */ +#define CAN_TDL0R_DATA2 ((uint32_t)0x00FF0000) /*!< Data byte 2 */ +#define CAN_TDL0R_DATA3 ((uint32_t)0xFF000000) /*!< Data byte 3 */ + +/****************** Bit definition for CAN_TDH0R register *******************/ +#define CAN_TDH0R_DATA4 ((uint32_t)0x000000FF) /*!< Data byte 4 */ +#define CAN_TDH0R_DATA5 ((uint32_t)0x0000FF00) /*!< Data byte 5 */ +#define CAN_TDH0R_DATA6 ((uint32_t)0x00FF0000) /*!< Data byte 6 */ +#define CAN_TDH0R_DATA7 ((uint32_t)0xFF000000) /*!< Data byte 7 */ + +/******************* Bit definition for CAN_TI1R register *******************/ +#define CAN_TI1R_TXRQ ((uint32_t)0x00000001) /*!< Transmit Mailbox Request */ +#define CAN_TI1R_RTR ((uint32_t)0x00000002) /*!< Remote Transmission Request */ +#define CAN_TI1R_IDE ((uint32_t)0x00000004) /*!< Identifier Extension */ +#define CAN_TI1R_EXID ((uint32_t)0x001FFFF8) /*!< Extended Identifier */ +#define CAN_TI1R_STID ((uint32_t)0xFFE00000) /*!< Standard Identifier or Extended Identifier */ + +/******************* Bit definition for CAN_TDT1R register ******************/ +#define CAN_TDT1R_DLC ((uint32_t)0x0000000F) /*!< Data Length Code */ +#define CAN_TDT1R_TGT ((uint32_t)0x00000100) /*!< Transmit Global Time */ +#define CAN_TDT1R_TIME ((uint32_t)0xFFFF0000) /*!< Message Time Stamp */ + +/******************* Bit definition for CAN_TDL1R register ******************/ +#define CAN_TDL1R_DATA0 ((uint32_t)0x000000FF) /*!< Data byte 0 */ +#define CAN_TDL1R_DATA1 ((uint32_t)0x0000FF00) /*!< Data byte 1 */ +#define CAN_TDL1R_DATA2 ((uint32_t)0x00FF0000) /*!< Data byte 2 */ +#define CAN_TDL1R_DATA3 ((uint32_t)0xFF000000) /*!< Data byte 3 */ + +/******************* Bit definition for CAN_TDH1R register ******************/ +#define CAN_TDH1R_DATA4 ((uint32_t)0x000000FF) /*!< Data byte 4 */ +#define CAN_TDH1R_DATA5 ((uint32_t)0x0000FF00) /*!< Data byte 5 */ +#define CAN_TDH1R_DATA6 ((uint32_t)0x00FF0000) /*!< Data byte 6 */ +#define CAN_TDH1R_DATA7 ((uint32_t)0xFF000000) /*!< Data byte 7 */ + +/******************* Bit definition for CAN_TI2R register *******************/ +#define CAN_TI2R_TXRQ ((uint32_t)0x00000001) /*!< Transmit Mailbox Request */ +#define CAN_TI2R_RTR ((uint32_t)0x00000002) /*!< Remote Transmission Request */ +#define CAN_TI2R_IDE ((uint32_t)0x00000004) /*!< Identifier Extension */ +#define CAN_TI2R_EXID ((uint32_t)0x001FFFF8) /*!< Extended identifier */ +#define CAN_TI2R_STID ((uint32_t)0xFFE00000) /*!< Standard Identifier or Extended Identifier */ + +/******************* Bit definition for CAN_TDT2R register ******************/ +#define CAN_TDT2R_DLC ((uint32_t)0x0000000F) /*!< Data Length Code */ +#define CAN_TDT2R_TGT ((uint32_t)0x00000100) /*!< Transmit Global Time */ +#define CAN_TDT2R_TIME ((uint32_t)0xFFFF0000) /*!< Message Time Stamp */ + +/******************* Bit definition for CAN_TDL2R register ******************/ +#define CAN_TDL2R_DATA0 ((uint32_t)0x000000FF) /*!< Data byte 0 */ +#define CAN_TDL2R_DATA1 ((uint32_t)0x0000FF00) /*!< Data byte 1 */ +#define CAN_TDL2R_DATA2 ((uint32_t)0x00FF0000) /*!< Data byte 2 */ +#define CAN_TDL2R_DATA3 ((uint32_t)0xFF000000) /*!< Data byte 3 */ + +/******************* Bit definition for CAN_TDH2R register ******************/ +#define CAN_TDH2R_DATA4 ((uint32_t)0x000000FF) /*!< Data byte 4 */ +#define CAN_TDH2R_DATA5 ((uint32_t)0x0000FF00) /*!< Data byte 5 */ +#define CAN_TDH2R_DATA6 ((uint32_t)0x00FF0000) /*!< Data byte 6 */ +#define CAN_TDH2R_DATA7 ((uint32_t)0xFF000000) /*!< Data byte 7 */ + +/******************* Bit definition for CAN_RI0R register *******************/ +#define CAN_RI0R_RTR ((uint32_t)0x00000002) /*!< Remote Transmission Request */ +#define CAN_RI0R_IDE ((uint32_t)0x00000004) /*!< Identifier Extension */ +#define CAN_RI0R_EXID ((uint32_t)0x001FFFF8) /*!< Extended Identifier */ +#define CAN_RI0R_STID ((uint32_t)0xFFE00000) /*!< Standard Identifier or Extended Identifier */ + +/******************* Bit definition for CAN_RDT0R register ******************/ +#define CAN_RDT0R_DLC ((uint32_t)0x0000000F) /*!< Data Length Code */ +#define CAN_RDT0R_FMI ((uint32_t)0x0000FF00) /*!< Filter Match Index */ +#define CAN_RDT0R_TIME ((uint32_t)0xFFFF0000) /*!< Message Time Stamp */ + +/******************* Bit definition for CAN_RDL0R register ******************/ +#define CAN_RDL0R_DATA0 ((uint32_t)0x000000FF) /*!< Data byte 0 */ +#define CAN_RDL0R_DATA1 ((uint32_t)0x0000FF00) /*!< Data byte 1 */ +#define CAN_RDL0R_DATA2 ((uint32_t)0x00FF0000) /*!< Data byte 2 */ +#define CAN_RDL0R_DATA3 ((uint32_t)0xFF000000) /*!< Data byte 3 */ + +/******************* Bit definition for CAN_RDH0R register ******************/ +#define CAN_RDH0R_DATA4 ((uint32_t)0x000000FF) /*!< Data byte 4 */ +#define CAN_RDH0R_DATA5 ((uint32_t)0x0000FF00) /*!< Data byte 5 */ +#define CAN_RDH0R_DATA6 ((uint32_t)0x00FF0000) /*!< Data byte 6 */ +#define CAN_RDH0R_DATA7 ((uint32_t)0xFF000000) /*!< Data byte 7 */ + +/******************* Bit definition for CAN_RI1R register *******************/ +#define CAN_RI1R_RTR ((uint32_t)0x00000002) /*!< Remote Transmission Request */ +#define CAN_RI1R_IDE ((uint32_t)0x00000004) /*!< Identifier Extension */ +#define CAN_RI1R_EXID ((uint32_t)0x001FFFF8) /*!< Extended identifier */ +#define CAN_RI1R_STID ((uint32_t)0xFFE00000) /*!< Standard Identifier or Extended Identifier */ + +/******************* Bit definition for CAN_RDT1R register ******************/ +#define CAN_RDT1R_DLC ((uint32_t)0x0000000F) /*!< Data Length Code */ +#define CAN_RDT1R_FMI ((uint32_t)0x0000FF00) /*!< Filter Match Index */ +#define CAN_RDT1R_TIME ((uint32_t)0xFFFF0000) /*!< Message Time Stamp */ + +/******************* Bit definition for CAN_RDL1R register ******************/ +#define CAN_RDL1R_DATA0 ((uint32_t)0x000000FF) /*!< Data byte 0 */ +#define CAN_RDL1R_DATA1 ((uint32_t)0x0000FF00) /*!< Data byte 1 */ +#define CAN_RDL1R_DATA2 ((uint32_t)0x00FF0000) /*!< Data byte 2 */ +#define CAN_RDL1R_DATA3 ((uint32_t)0xFF000000) /*!< Data byte 3 */ + +/******************* Bit definition for CAN_RDH1R register ******************/ +#define CAN_RDH1R_DATA4 ((uint32_t)0x000000FF) /*!< Data byte 4 */ +#define CAN_RDH1R_DATA5 ((uint32_t)0x0000FF00) /*!< Data byte 5 */ +#define CAN_RDH1R_DATA6 ((uint32_t)0x00FF0000) /*!< Data byte 6 */ +#define CAN_RDH1R_DATA7 ((uint32_t)0xFF000000) /*!< Data byte 7 */ + +/*!< CAN filter registers */ +/******************* Bit definition for CAN_FMR register ********************/ +#define CAN_FMR_FINIT ((uint8_t)0x01) /*!< Filter Init Mode */ + +/******************* Bit definition for CAN_FM1R register *******************/ +#define CAN_FM1R_FBM ((uint16_t)0x3FFF) /*!< Filter Mode */ +#define CAN_FM1R_FBM0 ((uint16_t)0x0001) /*!< Filter Init Mode bit 0 */ +#define CAN_FM1R_FBM1 ((uint16_t)0x0002) /*!< Filter Init Mode bit 1 */ +#define CAN_FM1R_FBM2 ((uint16_t)0x0004) /*!< Filter Init Mode bit 2 */ +#define CAN_FM1R_FBM3 ((uint16_t)0x0008) /*!< Filter Init Mode bit 3 */ +#define CAN_FM1R_FBM4 ((uint16_t)0x0010) /*!< Filter Init Mode bit 4 */ +#define CAN_FM1R_FBM5 ((uint16_t)0x0020) /*!< Filter Init Mode bit 5 */ +#define CAN_FM1R_FBM6 ((uint16_t)0x0040) /*!< Filter Init Mode bit 6 */ +#define CAN_FM1R_FBM7 ((uint16_t)0x0080) /*!< Filter Init Mode bit 7 */ +#define CAN_FM1R_FBM8 ((uint16_t)0x0100) /*!< Filter Init Mode bit 8 */ +#define CAN_FM1R_FBM9 ((uint16_t)0x0200) /*!< Filter Init Mode bit 9 */ +#define CAN_FM1R_FBM10 ((uint16_t)0x0400) /*!< Filter Init Mode bit 10 */ +#define CAN_FM1R_FBM11 ((uint16_t)0x0800) /*!< Filter Init Mode bit 11 */ +#define CAN_FM1R_FBM12 ((uint16_t)0x1000) /*!< Filter Init Mode bit 12 */ +#define CAN_FM1R_FBM13 ((uint16_t)0x2000) /*!< Filter Init Mode bit 13 */ + +/******************* Bit definition for CAN_FS1R register *******************/ +#define CAN_FS1R_FSC ((uint16_t)0x3FFF) /*!< Filter Scale Configuration */ +#define CAN_FS1R_FSC0 ((uint16_t)0x0001) /*!< Filter Scale Configuration bit 0 */ +#define CAN_FS1R_FSC1 ((uint16_t)0x0002) /*!< Filter Scale Configuration bit 1 */ +#define CAN_FS1R_FSC2 ((uint16_t)0x0004) /*!< Filter Scale Configuration bit 2 */ +#define CAN_FS1R_FSC3 ((uint16_t)0x0008) /*!< Filter Scale Configuration bit 3 */ +#define CAN_FS1R_FSC4 ((uint16_t)0x0010) /*!< Filter Scale Configuration bit 4 */ +#define CAN_FS1R_FSC5 ((uint16_t)0x0020) /*!< Filter Scale Configuration bit 5 */ +#define CAN_FS1R_FSC6 ((uint16_t)0x0040) /*!< Filter Scale Configuration bit 6 */ +#define CAN_FS1R_FSC7 ((uint16_t)0x0080) /*!< Filter Scale Configuration bit 7 */ +#define CAN_FS1R_FSC8 ((uint16_t)0x0100) /*!< Filter Scale Configuration bit 8 */ +#define CAN_FS1R_FSC9 ((uint16_t)0x0200) /*!< Filter Scale Configuration bit 9 */ +#define CAN_FS1R_FSC10 ((uint16_t)0x0400) /*!< Filter Scale Configuration bit 10 */ +#define CAN_FS1R_FSC11 ((uint16_t)0x0800) /*!< Filter Scale Configuration bit 11 */ +#define CAN_FS1R_FSC12 ((uint16_t)0x1000) /*!< Filter Scale Configuration bit 12 */ +#define CAN_FS1R_FSC13 ((uint16_t)0x2000) /*!< Filter Scale Configuration bit 13 */ + +/****************** Bit definition for CAN_FFA1R register *******************/ +#define CAN_FFA1R_FFA ((uint16_t)0x3FFF) /*!< Filter FIFO Assignment */ +#define CAN_FFA1R_FFA0 ((uint16_t)0x0001) /*!< Filter FIFO Assignment for Filter 0 */ +#define CAN_FFA1R_FFA1 ((uint16_t)0x0002) /*!< Filter FIFO Assignment for Filter 1 */ +#define CAN_FFA1R_FFA2 ((uint16_t)0x0004) /*!< Filter FIFO Assignment for Filter 2 */ +#define CAN_FFA1R_FFA3 ((uint16_t)0x0008) /*!< Filter FIFO Assignment for Filter 3 */ +#define CAN_FFA1R_FFA4 ((uint16_t)0x0010) /*!< Filter FIFO Assignment for Filter 4 */ +#define CAN_FFA1R_FFA5 ((uint16_t)0x0020) /*!< Filter FIFO Assignment for Filter 5 */ +#define CAN_FFA1R_FFA6 ((uint16_t)0x0040) /*!< Filter FIFO Assignment for Filter 6 */ +#define CAN_FFA1R_FFA7 ((uint16_t)0x0080) /*!< Filter FIFO Assignment for Filter 7 */ +#define CAN_FFA1R_FFA8 ((uint16_t)0x0100) /*!< Filter FIFO Assignment for Filter 8 */ +#define CAN_FFA1R_FFA9 ((uint16_t)0x0200) /*!< Filter FIFO Assignment for Filter 9 */ +#define CAN_FFA1R_FFA10 ((uint16_t)0x0400) /*!< Filter FIFO Assignment for Filter 10 */ +#define CAN_FFA1R_FFA11 ((uint16_t)0x0800) /*!< Filter FIFO Assignment for Filter 11 */ +#define CAN_FFA1R_FFA12 ((uint16_t)0x1000) /*!< Filter FIFO Assignment for Filter 12 */ +#define CAN_FFA1R_FFA13 ((uint16_t)0x2000) /*!< Filter FIFO Assignment for Filter 13 */ + +/******************* Bit definition for CAN_FA1R register *******************/ +#define CAN_FA1R_FACT ((uint16_t)0x3FFF) /*!< Filter Active */ +#define CAN_FA1R_FACT0 ((uint16_t)0x0001) /*!< Filter 0 Active */ +#define CAN_FA1R_FACT1 ((uint16_t)0x0002) /*!< Filter 1 Active */ +#define CAN_FA1R_FACT2 ((uint16_t)0x0004) /*!< Filter 2 Active */ +#define CAN_FA1R_FACT3 ((uint16_t)0x0008) /*!< Filter 3 Active */ +#define CAN_FA1R_FACT4 ((uint16_t)0x0010) /*!< Filter 4 Active */ +#define CAN_FA1R_FACT5 ((uint16_t)0x0020) /*!< Filter 5 Active */ +#define CAN_FA1R_FACT6 ((uint16_t)0x0040) /*!< Filter 6 Active */ +#define CAN_FA1R_FACT7 ((uint16_t)0x0080) /*!< Filter 7 Active */ +#define CAN_FA1R_FACT8 ((uint16_t)0x0100) /*!< Filter 8 Active */ +#define CAN_FA1R_FACT9 ((uint16_t)0x0200) /*!< Filter 9 Active */ +#define CAN_FA1R_FACT10 ((uint16_t)0x0400) /*!< Filter 10 Active */ +#define CAN_FA1R_FACT11 ((uint16_t)0x0800) /*!< Filter 11 Active */ +#define CAN_FA1R_FACT12 ((uint16_t)0x1000) /*!< Filter 12 Active */ +#define CAN_FA1R_FACT13 ((uint16_t)0x2000) /*!< Filter 13 Active */ + +/******************* Bit definition for CAN_F0R1 register *******************/ +#define CAN_F0R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F0R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F0R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F0R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F0R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F0R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F0R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F0R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F0R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F0R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F0R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F0R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F0R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F0R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F0R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F0R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F0R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F0R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F0R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F0R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F0R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F0R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F0R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F0R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F0R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F0R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F0R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F0R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F0R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F0R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F0R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F0R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F1R1 register *******************/ +#define CAN_F1R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F1R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F1R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F1R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F1R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F1R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F1R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F1R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F1R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F1R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F1R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F1R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F1R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F1R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F1R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F1R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F1R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F1R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F1R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F1R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F1R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F1R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F1R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F1R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F1R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F1R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F1R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F1R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F1R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F1R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F1R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F1R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F2R1 register *******************/ +#define CAN_F2R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F2R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F2R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F2R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F2R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F2R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F2R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F2R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F2R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F2R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F2R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F2R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F2R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F2R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F2R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F2R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F2R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F2R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F2R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F2R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F2R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F2R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F2R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F2R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F2R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F2R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F2R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F2R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F2R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F2R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F2R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F2R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F3R1 register *******************/ +#define CAN_F3R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F3R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F3R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F3R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F3R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F3R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F3R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F3R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F3R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F3R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F3R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F3R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F3R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F3R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F3R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F3R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F3R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F3R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F3R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F3R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F3R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F3R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F3R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F3R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F3R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F3R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F3R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F3R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F3R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F3R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F3R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F3R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F4R1 register *******************/ +#define CAN_F4R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F4R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F4R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F4R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F4R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F4R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F4R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F4R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F4R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F4R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F4R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F4R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F4R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F4R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F4R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F4R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F4R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F4R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F4R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F4R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F4R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F4R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F4R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F4R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F4R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F4R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F4R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F4R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F4R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F4R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F4R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F4R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F5R1 register *******************/ +#define CAN_F5R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F5R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F5R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F5R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F5R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F5R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F5R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F5R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F5R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F5R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F5R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F5R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F5R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F5R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F5R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F5R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F5R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F5R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F5R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F5R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F5R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F5R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F5R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F5R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F5R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F5R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F5R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F5R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F5R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F5R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F5R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F5R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F6R1 register *******************/ +#define CAN_F6R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F6R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F6R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F6R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F6R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F6R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F6R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F6R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F6R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F6R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F6R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F6R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F6R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F6R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F6R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F6R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F6R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F6R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F6R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F6R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F6R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F6R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F6R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F6R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F6R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F6R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F6R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F6R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F6R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F6R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F6R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F6R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F7R1 register *******************/ +#define CAN_F7R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F7R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F7R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F7R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F7R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F7R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F7R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F7R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F7R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F7R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F7R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F7R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F7R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F7R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F7R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F7R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F7R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F7R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F7R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F7R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F7R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F7R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F7R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F7R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F7R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F7R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F7R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F7R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F7R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F7R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F7R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F7R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F8R1 register *******************/ +#define CAN_F8R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F8R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F8R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F8R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F8R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F8R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F8R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F8R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F8R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F8R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F8R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F8R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F8R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F8R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F8R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F8R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F8R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F8R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F8R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F8R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F8R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F8R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F8R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F8R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F8R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F8R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F8R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F8R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F8R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F8R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F8R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F8R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F9R1 register *******************/ +#define CAN_F9R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F9R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F9R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F9R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F9R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F9R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F9R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F9R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F9R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F9R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F9R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F9R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F9R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F9R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F9R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F9R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F9R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F9R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F9R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F9R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F9R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F9R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F9R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F9R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F9R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F9R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F9R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F9R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F9R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F9R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F9R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F9R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F10R1 register ******************/ +#define CAN_F10R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F10R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F10R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F10R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F10R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F10R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F10R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F10R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F10R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F10R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F10R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F10R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F10R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F10R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F10R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F10R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F10R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F10R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F10R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F10R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F10R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F10R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F10R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F10R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F10R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F10R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F10R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F10R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F10R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F10R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F10R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F10R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F11R1 register ******************/ +#define CAN_F11R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F11R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F11R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F11R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F11R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F11R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F11R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F11R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F11R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F11R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F11R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F11R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F11R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F11R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F11R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F11R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F11R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F11R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F11R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F11R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F11R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F11R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F11R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F11R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F11R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F11R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F11R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F11R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F11R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F11R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F11R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F11R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F12R1 register ******************/ +#define CAN_F12R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F12R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F12R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F12R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F12R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F12R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F12R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F12R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F12R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F12R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F12R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F12R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F12R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F12R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F12R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F12R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F12R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F12R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F12R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F12R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F12R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F12R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F12R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F12R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F12R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F12R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F12R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F12R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F12R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F12R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F12R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F12R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F13R1 register ******************/ +#define CAN_F13R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F13R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F13R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F13R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F13R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F13R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F13R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F13R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F13R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F13R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F13R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F13R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F13R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F13R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F13R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F13R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F13R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F13R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F13R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F13R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F13R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F13R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F13R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F13R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F13R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F13R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F13R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F13R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F13R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F13R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F13R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F13R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F0R2 register *******************/ +#define CAN_F0R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F0R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F0R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F0R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F0R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F0R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F0R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F0R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F0R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F0R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F0R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F0R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F0R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F0R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F0R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F0R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F0R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F0R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F0R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F0R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F0R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F0R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F0R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F0R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F0R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F0R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F0R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F0R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F0R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F0R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F0R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F0R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F1R2 register *******************/ +#define CAN_F1R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F1R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F1R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F1R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F1R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F1R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F1R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F1R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F1R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F1R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F1R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F1R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F1R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F1R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F1R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F1R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F1R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F1R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F1R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F1R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F1R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F1R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F1R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F1R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F1R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F1R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F1R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F1R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F1R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F1R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F1R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F1R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F2R2 register *******************/ +#define CAN_F2R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F2R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F2R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F2R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F2R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F2R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F2R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F2R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F2R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F2R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F2R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F2R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F2R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F2R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F2R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F2R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F2R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F2R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F2R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F2R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F2R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F2R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F2R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F2R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F2R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F2R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F2R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F2R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F2R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F2R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F2R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F2R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F3R2 register *******************/ +#define CAN_F3R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F3R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F3R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F3R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F3R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F3R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F3R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F3R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F3R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F3R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F3R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F3R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F3R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F3R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F3R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F3R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F3R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F3R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F3R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F3R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F3R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F3R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F3R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F3R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F3R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F3R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F3R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F3R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F3R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F3R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F3R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F3R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F4R2 register *******************/ +#define CAN_F4R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F4R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F4R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F4R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F4R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F4R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F4R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F4R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F4R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F4R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F4R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F4R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F4R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F4R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F4R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F4R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F4R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F4R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F4R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F4R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F4R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F4R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F4R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F4R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F4R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F4R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F4R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F4R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F4R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F4R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F4R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F4R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F5R2 register *******************/ +#define CAN_F5R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F5R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F5R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F5R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F5R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F5R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F5R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F5R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F5R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F5R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F5R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F5R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F5R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F5R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F5R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F5R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F5R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F5R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F5R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F5R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F5R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F5R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F5R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F5R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F5R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F5R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F5R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F5R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F5R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F5R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F5R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F5R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F6R2 register *******************/ +#define CAN_F6R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F6R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F6R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F6R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F6R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F6R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F6R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F6R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F6R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F6R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F6R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F6R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F6R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F6R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F6R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F6R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F6R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F6R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F6R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F6R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F6R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F6R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F6R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F6R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F6R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F6R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F6R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F6R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F6R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F6R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F6R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F6R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F7R2 register *******************/ +#define CAN_F7R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F7R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F7R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F7R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F7R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F7R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F7R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F7R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F7R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F7R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F7R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F7R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F7R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F7R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F7R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F7R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F7R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F7R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F7R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F7R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F7R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F7R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F7R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F7R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F7R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F7R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F7R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F7R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F7R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F7R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F7R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F7R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F8R2 register *******************/ +#define CAN_F8R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F8R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F8R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F8R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F8R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F8R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F8R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F8R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F8R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F8R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F8R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F8R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F8R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F8R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F8R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F8R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F8R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F8R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F8R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F8R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F8R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F8R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F8R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F8R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F8R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F8R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F8R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F8R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F8R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F8R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F8R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F8R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F9R2 register *******************/ +#define CAN_F9R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F9R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F9R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F9R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F9R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F9R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F9R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F9R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F9R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F9R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F9R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F9R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F9R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F9R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F9R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F9R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F9R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F9R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F9R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F9R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F9R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F9R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F9R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F9R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F9R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F9R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F9R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F9R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F9R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F9R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F9R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F9R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F10R2 register ******************/ +#define CAN_F10R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F10R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F10R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F10R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F10R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F10R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F10R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F10R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F10R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F10R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F10R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F10R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F10R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F10R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F10R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F10R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F10R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F10R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F10R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F10R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F10R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F10R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F10R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F10R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F10R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F10R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F10R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F10R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F10R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F10R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F10R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F10R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F11R2 register ******************/ +#define CAN_F11R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F11R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F11R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F11R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F11R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F11R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F11R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F11R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F11R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F11R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F11R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F11R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F11R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F11R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F11R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F11R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F11R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F11R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F11R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F11R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F11R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F11R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F11R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F11R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F11R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F11R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F11R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F11R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F11R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F11R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F11R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F11R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F12R2 register ******************/ +#define CAN_F12R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F12R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F12R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F12R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F12R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F12R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F12R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F12R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F12R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F12R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F12R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F12R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F12R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F12R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F12R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F12R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F12R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F12R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F12R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F12R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F12R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F12R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F12R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F12R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F12R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F12R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F12R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F12R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F12R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F12R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F12R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F12R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F13R2 register ******************/ +#define CAN_F13R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F13R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F13R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F13R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F13R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F13R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F13R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F13R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F13R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F13R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F13R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F13R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F13R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F13R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F13R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F13R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F13R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F13R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F13R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F13R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F13R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F13R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F13R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F13R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F13R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F13R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F13R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F13R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F13R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F13R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F13R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F13R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************************************************************************/ +/* */ +/* Serial Peripheral Interface */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for SPI_CR1 register ********************/ +#define SPI_CR1_CPHA ((uint16_t)0x0001) /*!< Clock Phase */ +#define SPI_CR1_CPOL ((uint16_t)0x0002) /*!< Clock Polarity */ +#define SPI_CR1_MSTR ((uint16_t)0x0004) /*!< Master Selection */ + +#define SPI_CR1_BR ((uint16_t)0x0038) /*!< BR[2:0] bits (Baud Rate Control) */ +#define SPI_CR1_BR_0 ((uint16_t)0x0008) /*!< Bit 0 */ +#define SPI_CR1_BR_1 ((uint16_t)0x0010) /*!< Bit 1 */ +#define SPI_CR1_BR_2 ((uint16_t)0x0020) /*!< Bit 2 */ + +#define SPI_CR1_SPE ((uint16_t)0x0040) /*!< SPI Enable */ +#define SPI_CR1_LSBFIRST ((uint16_t)0x0080) /*!< Frame Format */ +#define SPI_CR1_SSI ((uint16_t)0x0100) /*!< Internal slave select */ +#define SPI_CR1_SSM ((uint16_t)0x0200) /*!< Software slave management */ +#define SPI_CR1_RXONLY ((uint16_t)0x0400) /*!< Receive only */ +#define SPI_CR1_DFF ((uint16_t)0x0800) /*!< Data Frame Format */ +#define SPI_CR1_CRCNEXT ((uint16_t)0x1000) /*!< Transmit CRC next */ +#define SPI_CR1_CRCEN ((uint16_t)0x2000) /*!< Hardware CRC calculation enable */ +#define SPI_CR1_BIDIOE ((uint16_t)0x4000) /*!< Output enable in bidirectional mode */ +#define SPI_CR1_BIDIMODE ((uint16_t)0x8000) /*!< Bidirectional data mode enable */ + +/******************* Bit definition for SPI_CR2 register ********************/ +#define SPI_CR2_RXDMAEN ((uint8_t)0x01) /*!< Rx Buffer DMA Enable */ +#define SPI_CR2_TXDMAEN ((uint8_t)0x02) /*!< Tx Buffer DMA Enable */ +#define SPI_CR2_SSOE ((uint8_t)0x04) /*!< SS Output Enable */ +#define SPI_CR2_ERRIE ((uint8_t)0x20) /*!< Error Interrupt Enable */ +#define SPI_CR2_RXNEIE ((uint8_t)0x40) /*!< RX buffer Not Empty Interrupt Enable */ +#define SPI_CR2_TXEIE ((uint8_t)0x80) /*!< Tx buffer Empty Interrupt Enable */ + +/******************** Bit definition for SPI_SR register ********************/ +#define SPI_SR_RXNE ((uint8_t)0x01) /*!< Receive buffer Not Empty */ +#define SPI_SR_TXE ((uint8_t)0x02) /*!< Transmit buffer Empty */ +#define SPI_SR_CHSIDE ((uint8_t)0x04) /*!< Channel side */ +#define SPI_SR_UDR ((uint8_t)0x08) /*!< Underrun flag */ +#define SPI_SR_CRCERR ((uint8_t)0x10) /*!< CRC Error flag */ +#define SPI_SR_MODF ((uint8_t)0x20) /*!< Mode fault */ +#define SPI_SR_OVR ((uint8_t)0x40) /*!< Overrun flag */ +#define SPI_SR_BSY ((uint8_t)0x80) /*!< Busy flag */ + +/******************** Bit definition for SPI_DR register ********************/ +#define SPI_DR_DR ((uint16_t)0xFFFF) /*!< Data Register */ + +/******************* Bit definition for SPI_CRCPR register ******************/ +#define SPI_CRCPR_CRCPOLY ((uint16_t)0xFFFF) /*!< CRC polynomial register */ + +/****************** Bit definition for SPI_RXCRCR register ******************/ +#define SPI_RXCRCR_RXCRC ((uint16_t)0xFFFF) /*!< Rx CRC Register */ + +/****************** Bit definition for SPI_TXCRCR register ******************/ +#define SPI_TXCRCR_TXCRC ((uint16_t)0xFFFF) /*!< Tx CRC Register */ + +/****************** Bit definition for SPI_I2SCFGR register *****************/ +#define SPI_I2SCFGR_CHLEN ((uint16_t)0x0001) /*!< Channel length (number of bits per audio channel) */ + +#define SPI_I2SCFGR_DATLEN ((uint16_t)0x0006) /*!< DATLEN[1:0] bits (Data length to be transferred) */ +#define SPI_I2SCFGR_DATLEN_0 ((uint16_t)0x0002) /*!< Bit 0 */ +#define SPI_I2SCFGR_DATLEN_1 ((uint16_t)0x0004) /*!< Bit 1 */ + +#define SPI_I2SCFGR_CKPOL ((uint16_t)0x0008) /*!< steady state clock polarity */ + +#define SPI_I2SCFGR_I2SSTD ((uint16_t)0x0030) /*!< I2SSTD[1:0] bits (I2S standard selection) */ +#define SPI_I2SCFGR_I2SSTD_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define SPI_I2SCFGR_I2SSTD_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define SPI_I2SCFGR_PCMSYNC ((uint16_t)0x0080) /*!< PCM frame synchronization */ + +#define SPI_I2SCFGR_I2SCFG ((uint16_t)0x0300) /*!< I2SCFG[1:0] bits (I2S configuration mode) */ +#define SPI_I2SCFGR_I2SCFG_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define SPI_I2SCFGR_I2SCFG_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define SPI_I2SCFGR_I2SE ((uint16_t)0x0400) /*!< I2S Enable */ +#define SPI_I2SCFGR_I2SMOD ((uint16_t)0x0800) /*!< I2S mode selection */ + +/****************** Bit definition for SPI_I2SPR register *******************/ +#define SPI_I2SPR_I2SDIV ((uint16_t)0x00FF) /*!< I2S Linear prescaler */ +#define SPI_I2SPR_ODD ((uint16_t)0x0100) /*!< Odd factor for the prescaler */ +#define SPI_I2SPR_MCKOE ((uint16_t)0x0200) /*!< Master Clock Output Enable */ + +/******************************************************************************/ +/* */ +/* Inter-integrated Circuit Interface */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for I2C_CR1 register ********************/ +#define I2C_CR1_PE ((uint16_t)0x0001) /*!< Peripheral Enable */ +#define I2C_CR1_SMBUS ((uint16_t)0x0002) /*!< SMBus Mode */ +#define I2C_CR1_SMBTYPE ((uint16_t)0x0008) /*!< SMBus Type */ +#define I2C_CR1_ENARP ((uint16_t)0x0010) /*!< ARP Enable */ +#define I2C_CR1_ENPEC ((uint16_t)0x0020) /*!< PEC Enable */ +#define I2C_CR1_ENGC ((uint16_t)0x0040) /*!< General Call Enable */ +#define I2C_CR1_NOSTRETCH ((uint16_t)0x0080) /*!< Clock Stretching Disable (Slave mode) */ +#define I2C_CR1_START ((uint16_t)0x0100) /*!< Start Generation */ +#define I2C_CR1_STOP ((uint16_t)0x0200) /*!< Stop Generation */ +#define I2C_CR1_ACK ((uint16_t)0x0400) /*!< Acknowledge Enable */ +#define I2C_CR1_POS ((uint16_t)0x0800) /*!< Acknowledge/PEC Position (for data reception) */ +#define I2C_CR1_PEC ((uint16_t)0x1000) /*!< Packet Error Checking */ +#define I2C_CR1_ALERT ((uint16_t)0x2000) /*!< SMBus Alert */ +#define I2C_CR1_SWRST ((uint16_t)0x8000) /*!< Software Reset */ + +/******************* Bit definition for I2C_CR2 register ********************/ +#define I2C_CR2_FREQ ((uint16_t)0x003F) /*!< FREQ[5:0] bits (Peripheral Clock Frequency) */ +#define I2C_CR2_FREQ_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define I2C_CR2_FREQ_1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define I2C_CR2_FREQ_2 ((uint16_t)0x0004) /*!< Bit 2 */ +#define I2C_CR2_FREQ_3 ((uint16_t)0x0008) /*!< Bit 3 */ +#define I2C_CR2_FREQ_4 ((uint16_t)0x0010) /*!< Bit 4 */ +#define I2C_CR2_FREQ_5 ((uint16_t)0x0020) /*!< Bit 5 */ + +#define I2C_CR2_ITERREN ((uint16_t)0x0100) /*!< Error Interrupt Enable */ +#define I2C_CR2_ITEVTEN ((uint16_t)0x0200) /*!< Event Interrupt Enable */ +#define I2C_CR2_ITBUFEN ((uint16_t)0x0400) /*!< Buffer Interrupt Enable */ +#define I2C_CR2_DMAEN ((uint16_t)0x0800) /*!< DMA Requests Enable */ +#define I2C_CR2_LAST ((uint16_t)0x1000) /*!< DMA Last Transfer */ + +/******************* Bit definition for I2C_OAR1 register *******************/ +#define I2C_OAR1_ADD1_7 ((uint16_t)0x00FE) /*!< Interface Address */ +#define I2C_OAR1_ADD8_9 ((uint16_t)0x0300) /*!< Interface Address */ + +#define I2C_OAR1_ADD0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define I2C_OAR1_ADD1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define I2C_OAR1_ADD2 ((uint16_t)0x0004) /*!< Bit 2 */ +#define I2C_OAR1_ADD3 ((uint16_t)0x0008) /*!< Bit 3 */ +#define I2C_OAR1_ADD4 ((uint16_t)0x0010) /*!< Bit 4 */ +#define I2C_OAR1_ADD5 ((uint16_t)0x0020) /*!< Bit 5 */ +#define I2C_OAR1_ADD6 ((uint16_t)0x0040) /*!< Bit 6 */ +#define I2C_OAR1_ADD7 ((uint16_t)0x0080) /*!< Bit 7 */ +#define I2C_OAR1_ADD8 ((uint16_t)0x0100) /*!< Bit 8 */ +#define I2C_OAR1_ADD9 ((uint16_t)0x0200) /*!< Bit 9 */ + +#define I2C_OAR1_ADDMODE ((uint16_t)0x8000) /*!< Addressing Mode (Slave mode) */ + +/******************* Bit definition for I2C_OAR2 register *******************/ +#define I2C_OAR2_ENDUAL ((uint8_t)0x01) /*!< Dual addressing mode enable */ +#define I2C_OAR2_ADD2 ((uint8_t)0xFE) /*!< Interface address */ + +/******************** Bit definition for I2C_DR register ********************/ +#define I2C_DR_DR ((uint8_t)0xFF) /*!< 8-bit Data Register */ + +/******************* Bit definition for I2C_SR1 register ********************/ +#define I2C_SR1_SB ((uint16_t)0x0001) /*!< Start Bit (Master mode) */ +#define I2C_SR1_ADDR ((uint16_t)0x0002) /*!< Address sent (master mode)/matched (slave mode) */ +#define I2C_SR1_BTF ((uint16_t)0x0004) /*!< Byte Transfer Finished */ +#define I2C_SR1_ADD10 ((uint16_t)0x0008) /*!< 10-bit header sent (Master mode) */ +#define I2C_SR1_STOPF ((uint16_t)0x0010) /*!< Stop detection (Slave mode) */ +#define I2C_SR1_RXNE ((uint16_t)0x0040) /*!< Data Register not Empty (receivers) */ +#define I2C_SR1_TXE ((uint16_t)0x0080) /*!< Data Register Empty (transmitters) */ +#define I2C_SR1_BERR ((uint16_t)0x0100) /*!< Bus Error */ +#define I2C_SR1_ARLO ((uint16_t)0x0200) /*!< Arbitration Lost (master mode) */ +#define I2C_SR1_AF ((uint16_t)0x0400) /*!< Acknowledge Failure */ +#define I2C_SR1_OVR ((uint16_t)0x0800) /*!< Overrun/Underrun */ +#define I2C_SR1_PECERR ((uint16_t)0x1000) /*!< PEC Error in reception */ +#define I2C_SR1_TIMEOUT ((uint16_t)0x4000) /*!< Timeout or Tlow Error */ +#define I2C_SR1_SMBALERT ((uint16_t)0x8000) /*!< SMBus Alert */ + +/******************* Bit definition for I2C_SR2 register ********************/ +#define I2C_SR2_MSL ((uint16_t)0x0001) /*!< Master/Slave */ +#define I2C_SR2_BUSY ((uint16_t)0x0002) /*!< Bus Busy */ +#define I2C_SR2_TRA ((uint16_t)0x0004) /*!< Transmitter/Receiver */ +#define I2C_SR2_GENCALL ((uint16_t)0x0010) /*!< General Call Address (Slave mode) */ +#define I2C_SR2_SMBDEFAULT ((uint16_t)0x0020) /*!< SMBus Device Default Address (Slave mode) */ +#define I2C_SR2_SMBHOST ((uint16_t)0x0040) /*!< SMBus Host Header (Slave mode) */ +#define I2C_SR2_DUALF ((uint16_t)0x0080) /*!< Dual Flag (Slave mode) */ +#define I2C_SR2_PEC ((uint16_t)0xFF00) /*!< Packet Error Checking Register */ + +/******************* Bit definition for I2C_CCR register ********************/ +#define I2C_CCR_CCR ((uint16_t)0x0FFF) /*!< Clock Control Register in Fast/Standard mode (Master mode) */ +#define I2C_CCR_DUTY ((uint16_t)0x4000) /*!< Fast Mode Duty Cycle */ +#define I2C_CCR_FS ((uint16_t)0x8000) /*!< I2C Master Mode Selection */ + +/****************** Bit definition for I2C_TRISE register *******************/ +#define I2C_TRISE_TRISE ((uint8_t)0x3F) /*!< Maximum Rise Time in Fast/Standard mode (Master mode) */ + +/******************************************************************************/ +/* */ +/* Universal Synchronous Asynchronous Receiver Transmitter */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for USART_SR register *******************/ +#define USART_SR_PE ((uint16_t)0x0001) /*!< Parity Error */ +#define USART_SR_FE ((uint16_t)0x0002) /*!< Framing Error */ +#define USART_SR_NE ((uint16_t)0x0004) /*!< Noise Error Flag */ +#define USART_SR_ORE ((uint16_t)0x0008) /*!< OverRun Error */ +#define USART_SR_IDLE ((uint16_t)0x0010) /*!< IDLE line detected */ +#define USART_SR_RXNE ((uint16_t)0x0020) /*!< Read Data Register Not Empty */ +#define USART_SR_TC ((uint16_t)0x0040) /*!< Transmission Complete */ +#define USART_SR_TXE ((uint16_t)0x0080) /*!< Transmit Data Register Empty */ +#define USART_SR_LBD ((uint16_t)0x0100) /*!< LIN Break Detection Flag */ +#define USART_SR_CTS ((uint16_t)0x0200) /*!< CTS Flag */ + +/******************* Bit definition for USART_DR register *******************/ +#define USART_DR_DR ((uint16_t)0x01FF) /*!< Data value */ + +/****************** Bit definition for USART_BRR register *******************/ +#define USART_BRR_DIV_Fraction ((uint16_t)0x000F) /*!< Fraction of USARTDIV */ +#define USART_BRR_DIV_Mantissa ((uint16_t)0xFFF0) /*!< Mantissa of USARTDIV */ + +/****************** Bit definition for USART_CR1 register *******************/ +#define USART_CR1_SBK ((uint16_t)0x0001) /*!< Send Break */ +#define USART_CR1_RWU ((uint16_t)0x0002) /*!< Receiver wakeup */ +#define USART_CR1_RE ((uint16_t)0x0004) /*!< Receiver Enable */ +#define USART_CR1_TE ((uint16_t)0x0008) /*!< Transmitter Enable */ +#define USART_CR1_IDLEIE ((uint16_t)0x0010) /*!< IDLE Interrupt Enable */ +#define USART_CR1_RXNEIE ((uint16_t)0x0020) /*!< RXNE Interrupt Enable */ +#define USART_CR1_TCIE ((uint16_t)0x0040) /*!< Transmission Complete Interrupt Enable */ +#define USART_CR1_TXEIE ((uint16_t)0x0080) /*!< PE Interrupt Enable */ +#define USART_CR1_PEIE ((uint16_t)0x0100) /*!< PE Interrupt Enable */ +#define USART_CR1_PS ((uint16_t)0x0200) /*!< Parity Selection */ +#define USART_CR1_PCE ((uint16_t)0x0400) /*!< Parity Control Enable */ +#define USART_CR1_WAKE ((uint16_t)0x0800) /*!< Wakeup method */ +#define USART_CR1_M ((uint16_t)0x1000) /*!< Word length */ +#define USART_CR1_UE ((uint16_t)0x2000) /*!< USART Enable */ +#define USART_CR1_OVER8 ((uint16_t)0x8000) /*!< USART Oversmapling 8-bits */ + +/****************** Bit definition for USART_CR2 register *******************/ +#define USART_CR2_ADD ((uint16_t)0x000F) /*!< Address of the USART node */ +#define USART_CR2_LBDL ((uint16_t)0x0020) /*!< LIN Break Detection Length */ +#define USART_CR2_LBDIE ((uint16_t)0x0040) /*!< LIN Break Detection Interrupt Enable */ +#define USART_CR2_LBCL ((uint16_t)0x0100) /*!< Last Bit Clock pulse */ +#define USART_CR2_CPHA ((uint16_t)0x0200) /*!< Clock Phase */ +#define USART_CR2_CPOL ((uint16_t)0x0400) /*!< Clock Polarity */ +#define USART_CR2_CLKEN ((uint16_t)0x0800) /*!< Clock Enable */ + +#define USART_CR2_STOP ((uint16_t)0x3000) /*!< STOP[1:0] bits (STOP bits) */ +#define USART_CR2_STOP_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USART_CR2_STOP_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USART_CR2_LINEN ((uint16_t)0x4000) /*!< LIN mode enable */ + +/****************** Bit definition for USART_CR3 register *******************/ +#define USART_CR3_EIE ((uint16_t)0x0001) /*!< Error Interrupt Enable */ +#define USART_CR3_IREN ((uint16_t)0x0002) /*!< IrDA mode Enable */ +#define USART_CR3_IRLP ((uint16_t)0x0004) /*!< IrDA Low-Power */ +#define USART_CR3_HDSEL ((uint16_t)0x0008) /*!< Half-Duplex Selection */ +#define USART_CR3_NACK ((uint16_t)0x0010) /*!< Smartcard NACK enable */ +#define USART_CR3_SCEN ((uint16_t)0x0020) /*!< Smartcard mode enable */ +#define USART_CR3_DMAR ((uint16_t)0x0040) /*!< DMA Enable Receiver */ +#define USART_CR3_DMAT ((uint16_t)0x0080) /*!< DMA Enable Transmitter */ +#define USART_CR3_RTSE ((uint16_t)0x0100) /*!< RTS Enable */ +#define USART_CR3_CTSE ((uint16_t)0x0200) /*!< CTS Enable */ +#define USART_CR3_CTSIE ((uint16_t)0x0400) /*!< CTS Interrupt Enable */ +#define USART_CR3_ONEBIT ((uint16_t)0x0800) /*!< One Bit method */ + +/****************** Bit definition for USART_GTPR register ******************/ +#define USART_GTPR_PSC ((uint16_t)0x00FF) /*!< PSC[7:0] bits (Prescaler value) */ +#define USART_GTPR_PSC_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define USART_GTPR_PSC_1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define USART_GTPR_PSC_2 ((uint16_t)0x0004) /*!< Bit 2 */ +#define USART_GTPR_PSC_3 ((uint16_t)0x0008) /*!< Bit 3 */ +#define USART_GTPR_PSC_4 ((uint16_t)0x0010) /*!< Bit 4 */ +#define USART_GTPR_PSC_5 ((uint16_t)0x0020) /*!< Bit 5 */ +#define USART_GTPR_PSC_6 ((uint16_t)0x0040) /*!< Bit 6 */ +#define USART_GTPR_PSC_7 ((uint16_t)0x0080) /*!< Bit 7 */ + +#define USART_GTPR_GT ((uint16_t)0xFF00) /*!< Guard time value */ + +/******************************************************************************/ +/* */ +/* Debug MCU */ +/* */ +/******************************************************************************/ + +/**************** Bit definition for DBGMCU_IDCODE register *****************/ +#define DBGMCU_IDCODE_DEV_ID ((uint32_t)0x00000FFF) /*!< Device Identifier */ + +#define DBGMCU_IDCODE_REV_ID ((uint32_t)0xFFFF0000) /*!< REV_ID[15:0] bits (Revision Identifier) */ +#define DBGMCU_IDCODE_REV_ID_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define DBGMCU_IDCODE_REV_ID_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define DBGMCU_IDCODE_REV_ID_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define DBGMCU_IDCODE_REV_ID_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define DBGMCU_IDCODE_REV_ID_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define DBGMCU_IDCODE_REV_ID_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define DBGMCU_IDCODE_REV_ID_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define DBGMCU_IDCODE_REV_ID_7 ((uint32_t)0x00800000) /*!< Bit 7 */ +#define DBGMCU_IDCODE_REV_ID_8 ((uint32_t)0x01000000) /*!< Bit 8 */ +#define DBGMCU_IDCODE_REV_ID_9 ((uint32_t)0x02000000) /*!< Bit 9 */ +#define DBGMCU_IDCODE_REV_ID_10 ((uint32_t)0x04000000) /*!< Bit 10 */ +#define DBGMCU_IDCODE_REV_ID_11 ((uint32_t)0x08000000) /*!< Bit 11 */ +#define DBGMCU_IDCODE_REV_ID_12 ((uint32_t)0x10000000) /*!< Bit 12 */ +#define DBGMCU_IDCODE_REV_ID_13 ((uint32_t)0x20000000) /*!< Bit 13 */ +#define DBGMCU_IDCODE_REV_ID_14 ((uint32_t)0x40000000) /*!< Bit 14 */ +#define DBGMCU_IDCODE_REV_ID_15 ((uint32_t)0x80000000) /*!< Bit 15 */ + +/****************** Bit definition for DBGMCU_CR register *******************/ +#define DBGMCU_CR_DBG_SLEEP ((uint32_t)0x00000001) /*!< Debug Sleep Mode */ +#define DBGMCU_CR_DBG_STOP ((uint32_t)0x00000002) /*!< Debug Stop Mode */ +#define DBGMCU_CR_DBG_STANDBY ((uint32_t)0x00000004) /*!< Debug Standby mode */ +#define DBGMCU_CR_TRACE_IOEN ((uint32_t)0x00000020) /*!< Trace Pin Assignment Control */ + +#define DBGMCU_CR_TRACE_MODE ((uint32_t)0x000000C0) /*!< TRACE_MODE[1:0] bits (Trace Pin Assignment Control) */ +#define DBGMCU_CR_TRACE_MODE_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define DBGMCU_CR_TRACE_MODE_1 ((uint32_t)0x00000080) /*!< Bit 1 */ + +#define DBGMCU_CR_DBG_IWDG_STOP ((uint32_t)0x00000100) /*!< Debug Independent Watchdog stopped when Core is halted */ +#define DBGMCU_CR_DBG_WWDG_STOP ((uint32_t)0x00000200) /*!< Debug Window Watchdog stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM1_STOP ((uint32_t)0x00000400) /*!< TIM1 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_TIM2_STOP ((uint32_t)0x00000800) /*!< TIM2 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_TIM3_STOP ((uint32_t)0x00001000) /*!< TIM3 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_TIM4_STOP ((uint32_t)0x00002000) /*!< TIM4 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_CAN1_STOP ((uint32_t)0x00004000) /*!< Debug CAN1 stopped when Core is halted */ +#define DBGMCU_CR_DBG_I2C1_SMBUS_TIMEOUT ((uint32_t)0x00008000) /*!< SMBUS timeout mode stopped when Core is halted */ +#define DBGMCU_CR_DBG_I2C2_SMBUS_TIMEOUT ((uint32_t)0x00010000) /*!< SMBUS timeout mode stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM8_STOP ((uint32_t)0x00020000) /*!< TIM8 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_TIM5_STOP ((uint32_t)0x00040000) /*!< TIM5 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_TIM6_STOP ((uint32_t)0x00080000) /*!< TIM6 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_TIM7_STOP ((uint32_t)0x00100000) /*!< TIM7 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_CAN2_STOP ((uint32_t)0x00200000) /*!< Debug CAN2 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM15_STOP ((uint32_t)0x00400000) /*!< Debug TIM15 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM16_STOP ((uint32_t)0x00800000) /*!< Debug TIM16 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM17_STOP ((uint32_t)0x01000000) /*!< Debug TIM17 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM12_STOP ((uint32_t)0x02000000) /*!< Debug TIM12 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM13_STOP ((uint32_t)0x04000000) /*!< Debug TIM13 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM14_STOP ((uint32_t)0x08000000) /*!< Debug TIM14 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM9_STOP ((uint32_t)0x10000000) /*!< Debug TIM9 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM10_STOP ((uint32_t)0x20000000) /*!< Debug TIM10 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM11_STOP ((uint32_t)0x40000000) /*!< Debug TIM11 stopped when Core is halted */ + +/******************************************************************************/ +/* */ +/* FLASH and Option Bytes Registers */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for FLASH_ACR register ******************/ +#define FLASH_ACR_LATENCY ((uint8_t)0x03) /*!< LATENCY[2:0] bits (Latency) */ +#define FLASH_ACR_LATENCY_0 ((uint8_t)0x00) /*!< Bit 0 */ +#define FLASH_ACR_LATENCY_1 ((uint8_t)0x01) /*!< Bit 0 */ +#define FLASH_ACR_LATENCY_2 ((uint8_t)0x02) /*!< Bit 1 */ + +#define FLASH_ACR_HLFCYA ((uint8_t)0x08) /*!< Flash Half Cycle Access Enable */ +#define FLASH_ACR_PRFTBE ((uint8_t)0x10) /*!< Prefetch Buffer Enable */ +#define FLASH_ACR_PRFTBS ((uint8_t)0x20) /*!< Prefetch Buffer Status */ + +/****************** Bit definition for FLASH_KEYR register ******************/ +#define FLASH_KEYR_FKEYR ((uint32_t)0xFFFFFFFF) /*!< FPEC Key */ + +/***************** Bit definition for FLASH_OPTKEYR register ****************/ +#define FLASH_OPTKEYR_OPTKEYR ((uint32_t)0xFFFFFFFF) /*!< Option Byte Key */ + +/****************** Bit definition for FLASH_SR register *******************/ +#define FLASH_SR_BSY ((uint8_t)0x01) /*!< Busy */ +#define FLASH_SR_PGERR ((uint8_t)0x04) /*!< Programming Error */ +#define FLASH_SR_WRPRTERR ((uint8_t)0x10) /*!< Write Protection Error */ +#define FLASH_SR_EOP ((uint8_t)0x20) /*!< End of operation */ + +/******************* Bit definition for FLASH_CR register *******************/ +#define FLASH_CR_PG ((uint16_t)0x0001) /*!< Programming */ +#define FLASH_CR_PER ((uint16_t)0x0002) /*!< Page Erase */ +#define FLASH_CR_MER ((uint16_t)0x0004) /*!< Mass Erase */ +#define FLASH_CR_OPTPG ((uint16_t)0x0010) /*!< Option Byte Programming */ +#define FLASH_CR_OPTER ((uint16_t)0x0020) /*!< Option Byte Erase */ +#define FLASH_CR_STRT ((uint16_t)0x0040) /*!< Start */ +#define FLASH_CR_LOCK ((uint16_t)0x0080) /*!< Lock */ +#define FLASH_CR_OPTWRE ((uint16_t)0x0200) /*!< Option Bytes Write Enable */ +#define FLASH_CR_ERRIE ((uint16_t)0x0400) /*!< Error Interrupt Enable */ +#define FLASH_CR_EOPIE ((uint16_t)0x1000) /*!< End of operation interrupt enable */ + +/******************* Bit definition for FLASH_AR register *******************/ +#define FLASH_AR_FAR ((uint32_t)0xFFFFFFFF) /*!< Flash Address */ + +/****************** Bit definition for FLASH_OBR register *******************/ +#define FLASH_OBR_OPTERR ((uint16_t)0x0001) /*!< Option Byte Error */ +#define FLASH_OBR_RDPRT ((uint16_t)0x0002) /*!< Read protection */ + +#define FLASH_OBR_USER ((uint16_t)0x03FC) /*!< User Option Bytes */ +#define FLASH_OBR_WDG_SW ((uint16_t)0x0004) /*!< WDG_SW */ +#define FLASH_OBR_nRST_STOP ((uint16_t)0x0008) /*!< nRST_STOP */ +#define FLASH_OBR_nRST_STDBY ((uint16_t)0x0010) /*!< nRST_STDBY */ +#define FLASH_OBR_BFB2 ((uint16_t)0x0020) /*!< BFB2 */ + +/****************** Bit definition for FLASH_WRPR register ******************/ +#define FLASH_WRPR_WRP ((uint32_t)0xFFFFFFFF) /*!< Write Protect */ + +/*----------------------------------------------------------------------------*/ + +/****************** Bit definition for FLASH_RDP register *******************/ +#define FLASH_RDP_RDP ((uint32_t)0x000000FF) /*!< Read protection option byte */ +#define FLASH_RDP_nRDP ((uint32_t)0x0000FF00) /*!< Read protection complemented option byte */ + +/****************** Bit definition for FLASH_USER register ******************/ +#define FLASH_USER_USER ((uint32_t)0x00FF0000) /*!< User option byte */ +#define FLASH_USER_nUSER ((uint32_t)0xFF000000) /*!< User complemented option byte */ + +/****************** Bit definition for FLASH_Data0 register *****************/ +#define FLASH_Data0_Data0 ((uint32_t)0x000000FF) /*!< User data storage option byte */ +#define FLASH_Data0_nData0 ((uint32_t)0x0000FF00) /*!< User data storage complemented option byte */ + +/****************** Bit definition for FLASH_Data1 register *****************/ +#define FLASH_Data1_Data1 ((uint32_t)0x00FF0000) /*!< User data storage option byte */ +#define FLASH_Data1_nData1 ((uint32_t)0xFF000000) /*!< User data storage complemented option byte */ + +/****************** Bit definition for FLASH_WRP0 register ******************/ +#define FLASH_WRP0_WRP0 ((uint32_t)0x000000FF) /*!< Flash memory write protection option bytes */ +#define FLASH_WRP0_nWRP0 ((uint32_t)0x0000FF00) /*!< Flash memory write protection complemented option bytes */ + +/****************** Bit definition for FLASH_WRP1 register ******************/ +#define FLASH_WRP1_WRP1 ((uint32_t)0x00FF0000) /*!< Flash memory write protection option bytes */ +#define FLASH_WRP1_nWRP1 ((uint32_t)0xFF000000) /*!< Flash memory write protection complemented option bytes */ + +/****************** Bit definition for FLASH_WRP2 register ******************/ +#define FLASH_WRP2_WRP2 ((uint32_t)0x000000FF) /*!< Flash memory write protection option bytes */ +#define FLASH_WRP2_nWRP2 ((uint32_t)0x0000FF00) /*!< Flash memory write protection complemented option bytes */ + +/****************** Bit definition for FLASH_WRP3 register ******************/ +#define FLASH_WRP3_WRP3 ((uint32_t)0x00FF0000) /*!< Flash memory write protection option bytes */ +#define FLASH_WRP3_nWRP3 ((uint32_t)0xFF000000) /*!< Flash memory write protection complemented option bytes */ + +#ifdef STM32F10X_CL +/******************************************************************************/ +/* Ethernet MAC Registers bits definitions */ +/******************************************************************************/ +/* Bit definition for Ethernet MAC Control Register register */ +#define ETH_MACCR_WD ((uint32_t)0x00800000) /* Watchdog disable */ +#define ETH_MACCR_JD ((uint32_t)0x00400000) /* Jabber disable */ +#define ETH_MACCR_IFG ((uint32_t)0x000E0000) /* Inter-frame gap */ + #define ETH_MACCR_IFG_96Bit ((uint32_t)0x00000000) /* Minimum IFG between frames during transmission is 96Bit */ + #define ETH_MACCR_IFG_88Bit ((uint32_t)0x00020000) /* Minimum IFG between frames during transmission is 88Bit */ + #define ETH_MACCR_IFG_80Bit ((uint32_t)0x00040000) /* Minimum IFG between frames during transmission is 80Bit */ + #define ETH_MACCR_IFG_72Bit ((uint32_t)0x00060000) /* Minimum IFG between frames during transmission is 72Bit */ + #define ETH_MACCR_IFG_64Bit ((uint32_t)0x00080000) /* Minimum IFG between frames during transmission is 64Bit */ + #define ETH_MACCR_IFG_56Bit ((uint32_t)0x000A0000) /* Minimum IFG between frames during transmission is 56Bit */ + #define ETH_MACCR_IFG_48Bit ((uint32_t)0x000C0000) /* Minimum IFG between frames during transmission is 48Bit */ + #define ETH_MACCR_IFG_40Bit ((uint32_t)0x000E0000) /* Minimum IFG between frames during transmission is 40Bit */ +#define ETH_MACCR_CSD ((uint32_t)0x00010000) /* Carrier sense disable (during transmission) */ +#define ETH_MACCR_FES ((uint32_t)0x00004000) /* Fast ethernet speed */ +#define ETH_MACCR_ROD ((uint32_t)0x00002000) /* Receive own disable */ +#define ETH_MACCR_LM ((uint32_t)0x00001000) /* loopback mode */ +#define ETH_MACCR_DM ((uint32_t)0x00000800) /* Duplex mode */ +#define ETH_MACCR_IPCO ((uint32_t)0x00000400) /* IP Checksum offload */ +#define ETH_MACCR_RD ((uint32_t)0x00000200) /* Retry disable */ +#define ETH_MACCR_APCS ((uint32_t)0x00000080) /* Automatic Pad/CRC stripping */ +#define ETH_MACCR_BL ((uint32_t)0x00000060) /* Back-off limit: random integer number (r) of slot time delays before rescheduling + a transmission attempt during retries after a collision: 0 =< r <2^k */ + #define ETH_MACCR_BL_10 ((uint32_t)0x00000000) /* k = min (n, 10) */ + #define ETH_MACCR_BL_8 ((uint32_t)0x00000020) /* k = min (n, 8) */ + #define ETH_MACCR_BL_4 ((uint32_t)0x00000040) /* k = min (n, 4) */ + #define ETH_MACCR_BL_1 ((uint32_t)0x00000060) /* k = min (n, 1) */ +#define ETH_MACCR_DC ((uint32_t)0x00000010) /* Defferal check */ +#define ETH_MACCR_TE ((uint32_t)0x00000008) /* Transmitter enable */ +#define ETH_MACCR_RE ((uint32_t)0x00000004) /* Receiver enable */ + +/* Bit definition for Ethernet MAC Frame Filter Register */ +#define ETH_MACFFR_RA ((uint32_t)0x80000000) /* Receive all */ +#define ETH_MACFFR_HPF ((uint32_t)0x00000400) /* Hash or perfect filter */ +#define ETH_MACFFR_SAF ((uint32_t)0x00000200) /* Source address filter enable */ +#define ETH_MACFFR_SAIF ((uint32_t)0x00000100) /* SA inverse filtering */ +#define ETH_MACFFR_PCF ((uint32_t)0x000000C0) /* Pass control frames: 3 cases */ + #define ETH_MACFFR_PCF_BlockAll ((uint32_t)0x00000040) /* MAC filters all control frames from reaching the application */ + #define ETH_MACFFR_PCF_ForwardAll ((uint32_t)0x00000080) /* MAC forwards all control frames to application even if they fail the Address Filter */ + #define ETH_MACFFR_PCF_ForwardPassedAddrFilter ((uint32_t)0x000000C0) /* MAC forwards control frames that pass the Address Filter. */ +#define ETH_MACFFR_BFD ((uint32_t)0x00000020) /* Broadcast frame disable */ +#define ETH_MACFFR_PAM ((uint32_t)0x00000010) /* Pass all mutlicast */ +#define ETH_MACFFR_DAIF ((uint32_t)0x00000008) /* DA Inverse filtering */ +#define ETH_MACFFR_HM ((uint32_t)0x00000004) /* Hash multicast */ +#define ETH_MACFFR_HU ((uint32_t)0x00000002) /* Hash unicast */ +#define ETH_MACFFR_PM ((uint32_t)0x00000001) /* Promiscuous mode */ + +/* Bit definition for Ethernet MAC Hash Table High Register */ +#define ETH_MACHTHR_HTH ((uint32_t)0xFFFFFFFF) /* Hash table high */ + +/* Bit definition for Ethernet MAC Hash Table Low Register */ +#define ETH_MACHTLR_HTL ((uint32_t)0xFFFFFFFF) /* Hash table low */ + +/* Bit definition for Ethernet MAC MII Address Register */ +#define ETH_MACMIIAR_PA ((uint32_t)0x0000F800) /* Physical layer address */ +#define ETH_MACMIIAR_MR ((uint32_t)0x000007C0) /* MII register in the selected PHY */ +#define ETH_MACMIIAR_CR ((uint32_t)0x0000001C) /* CR clock range: 6 cases */ + #define ETH_MACMIIAR_CR_Div42 ((uint32_t)0x00000000) /* HCLK:60-72 MHz; MDC clock= HCLK/42 */ + #define ETH_MACMIIAR_CR_Div16 ((uint32_t)0x00000008) /* HCLK:20-35 MHz; MDC clock= HCLK/16 */ + #define ETH_MACMIIAR_CR_Div26 ((uint32_t)0x0000000C) /* HCLK:35-60 MHz; MDC clock= HCLK/26 */ +#define ETH_MACMIIAR_MW ((uint32_t)0x00000002) /* MII write */ +#define ETH_MACMIIAR_MB ((uint32_t)0x00000001) /* MII busy */ + +/* Bit definition for Ethernet MAC MII Data Register */ +#define ETH_MACMIIDR_MD ((uint32_t)0x0000FFFF) /* MII data: read/write data from/to PHY */ + +/* Bit definition for Ethernet MAC Flow Control Register */ +#define ETH_MACFCR_PT ((uint32_t)0xFFFF0000) /* Pause time */ +#define ETH_MACFCR_ZQPD ((uint32_t)0x00000080) /* Zero-quanta pause disable */ +#define ETH_MACFCR_PLT ((uint32_t)0x00000030) /* Pause low threshold: 4 cases */ + #define ETH_MACFCR_PLT_Minus4 ((uint32_t)0x00000000) /* Pause time minus 4 slot times */ + #define ETH_MACFCR_PLT_Minus28 ((uint32_t)0x00000010) /* Pause time minus 28 slot times */ + #define ETH_MACFCR_PLT_Minus144 ((uint32_t)0x00000020) /* Pause time minus 144 slot times */ + #define ETH_MACFCR_PLT_Minus256 ((uint32_t)0x00000030) /* Pause time minus 256 slot times */ +#define ETH_MACFCR_UPFD ((uint32_t)0x00000008) /* Unicast pause frame detect */ +#define ETH_MACFCR_RFCE ((uint32_t)0x00000004) /* Receive flow control enable */ +#define ETH_MACFCR_TFCE ((uint32_t)0x00000002) /* Transmit flow control enable */ +#define ETH_MACFCR_FCBBPA ((uint32_t)0x00000001) /* Flow control busy/backpressure activate */ + +/* Bit definition for Ethernet MAC VLAN Tag Register */ +#define ETH_MACVLANTR_VLANTC ((uint32_t)0x00010000) /* 12-bit VLAN tag comparison */ +#define ETH_MACVLANTR_VLANTI ((uint32_t)0x0000FFFF) /* VLAN tag identifier (for receive frames) */ + +/* Bit definition for Ethernet MAC Remote Wake-UpFrame Filter Register */ +#define ETH_MACRWUFFR_D ((uint32_t)0xFFFFFFFF) /* Wake-up frame filter register data */ +/* Eight sequential Writes to this address (offset 0x28) will write all Wake-UpFrame Filter Registers. + Eight sequential Reads from this address (offset 0x28) will read all Wake-UpFrame Filter Registers. */ +/* Wake-UpFrame Filter Reg0 : Filter 0 Byte Mask + Wake-UpFrame Filter Reg1 : Filter 1 Byte Mask + Wake-UpFrame Filter Reg2 : Filter 2 Byte Mask + Wake-UpFrame Filter Reg3 : Filter 3 Byte Mask + Wake-UpFrame Filter Reg4 : RSVD - Filter3 Command - RSVD - Filter2 Command - + RSVD - Filter1 Command - RSVD - Filter0 Command + Wake-UpFrame Filter Re5 : Filter3 Offset - Filter2 Offset - Filter1 Offset - Filter0 Offset + Wake-UpFrame Filter Re6 : Filter1 CRC16 - Filter0 CRC16 + Wake-UpFrame Filter Re7 : Filter3 CRC16 - Filter2 CRC16 */ + +/* Bit definition for Ethernet MAC PMT Control and Status Register */ +#define ETH_MACPMTCSR_WFFRPR ((uint32_t)0x80000000) /* Wake-Up Frame Filter Register Pointer Reset */ +#define ETH_MACPMTCSR_GU ((uint32_t)0x00000200) /* Global Unicast */ +#define ETH_MACPMTCSR_WFR ((uint32_t)0x00000040) /* Wake-Up Frame Received */ +#define ETH_MACPMTCSR_MPR ((uint32_t)0x00000020) /* Magic Packet Received */ +#define ETH_MACPMTCSR_WFE ((uint32_t)0x00000004) /* Wake-Up Frame Enable */ +#define ETH_MACPMTCSR_MPE ((uint32_t)0x00000002) /* Magic Packet Enable */ +#define ETH_MACPMTCSR_PD ((uint32_t)0x00000001) /* Power Down */ + +/* Bit definition for Ethernet MAC Status Register */ +#define ETH_MACSR_TSTS ((uint32_t)0x00000200) /* Time stamp trigger status */ +#define ETH_MACSR_MMCTS ((uint32_t)0x00000040) /* MMC transmit status */ +#define ETH_MACSR_MMMCRS ((uint32_t)0x00000020) /* MMC receive status */ +#define ETH_MACSR_MMCS ((uint32_t)0x00000010) /* MMC status */ +#define ETH_MACSR_PMTS ((uint32_t)0x00000008) /* PMT status */ + +/* Bit definition for Ethernet MAC Interrupt Mask Register */ +#define ETH_MACIMR_TSTIM ((uint32_t)0x00000200) /* Time stamp trigger interrupt mask */ +#define ETH_MACIMR_PMTIM ((uint32_t)0x00000008) /* PMT interrupt mask */ + +/* Bit definition for Ethernet MAC Address0 High Register */ +#define ETH_MACA0HR_MACA0H ((uint32_t)0x0000FFFF) /* MAC address0 high */ + +/* Bit definition for Ethernet MAC Address0 Low Register */ +#define ETH_MACA0LR_MACA0L ((uint32_t)0xFFFFFFFF) /* MAC address0 low */ + +/* Bit definition for Ethernet MAC Address1 High Register */ +#define ETH_MACA1HR_AE ((uint32_t)0x80000000) /* Address enable */ +#define ETH_MACA1HR_SA ((uint32_t)0x40000000) /* Source address */ +#define ETH_MACA1HR_MBC ((uint32_t)0x3F000000) /* Mask byte control: bits to mask for comparison of the MAC Address bytes */ + #define ETH_MACA1HR_MBC_HBits15_8 ((uint32_t)0x20000000) /* Mask MAC Address high reg bits [15:8] */ + #define ETH_MACA1HR_MBC_HBits7_0 ((uint32_t)0x10000000) /* Mask MAC Address high reg bits [7:0] */ + #define ETH_MACA1HR_MBC_LBits31_24 ((uint32_t)0x08000000) /* Mask MAC Address low reg bits [31:24] */ + #define ETH_MACA1HR_MBC_LBits23_16 ((uint32_t)0x04000000) /* Mask MAC Address low reg bits [23:16] */ + #define ETH_MACA1HR_MBC_LBits15_8 ((uint32_t)0x02000000) /* Mask MAC Address low reg bits [15:8] */ + #define ETH_MACA1HR_MBC_LBits7_0 ((uint32_t)0x01000000) /* Mask MAC Address low reg bits [7:0] */ +#define ETH_MACA1HR_MACA1H ((uint32_t)0x0000FFFF) /* MAC address1 high */ + +/* Bit definition for Ethernet MAC Address1 Low Register */ +#define ETH_MACA1LR_MACA1L ((uint32_t)0xFFFFFFFF) /* MAC address1 low */ + +/* Bit definition for Ethernet MAC Address2 High Register */ +#define ETH_MACA2HR_AE ((uint32_t)0x80000000) /* Address enable */ +#define ETH_MACA2HR_SA ((uint32_t)0x40000000) /* Source address */ +#define ETH_MACA2HR_MBC ((uint32_t)0x3F000000) /* Mask byte control */ + #define ETH_MACA2HR_MBC_HBits15_8 ((uint32_t)0x20000000) /* Mask MAC Address high reg bits [15:8] */ + #define ETH_MACA2HR_MBC_HBits7_0 ((uint32_t)0x10000000) /* Mask MAC Address high reg bits [7:0] */ + #define ETH_MACA2HR_MBC_LBits31_24 ((uint32_t)0x08000000) /* Mask MAC Address low reg bits [31:24] */ + #define ETH_MACA2HR_MBC_LBits23_16 ((uint32_t)0x04000000) /* Mask MAC Address low reg bits [23:16] */ + #define ETH_MACA2HR_MBC_LBits15_8 ((uint32_t)0x02000000) /* Mask MAC Address low reg bits [15:8] */ + #define ETH_MACA2HR_MBC_LBits7_0 ((uint32_t)0x01000000) /* Mask MAC Address low reg bits [70] */ +#define ETH_MACA2HR_MACA2H ((uint32_t)0x0000FFFF) /* MAC address1 high */ + +/* Bit definition for Ethernet MAC Address2 Low Register */ +#define ETH_MACA2LR_MACA2L ((uint32_t)0xFFFFFFFF) /* MAC address2 low */ + +/* Bit definition for Ethernet MAC Address3 High Register */ +#define ETH_MACA3HR_AE ((uint32_t)0x80000000) /* Address enable */ +#define ETH_MACA3HR_SA ((uint32_t)0x40000000) /* Source address */ +#define ETH_MACA3HR_MBC ((uint32_t)0x3F000000) /* Mask byte control */ + #define ETH_MACA3HR_MBC_HBits15_8 ((uint32_t)0x20000000) /* Mask MAC Address high reg bits [15:8] */ + #define ETH_MACA3HR_MBC_HBits7_0 ((uint32_t)0x10000000) /* Mask MAC Address high reg bits [7:0] */ + #define ETH_MACA3HR_MBC_LBits31_24 ((uint32_t)0x08000000) /* Mask MAC Address low reg bits [31:24] */ + #define ETH_MACA3HR_MBC_LBits23_16 ((uint32_t)0x04000000) /* Mask MAC Address low reg bits [23:16] */ + #define ETH_MACA3HR_MBC_LBits15_8 ((uint32_t)0x02000000) /* Mask MAC Address low reg bits [15:8] */ + #define ETH_MACA3HR_MBC_LBits7_0 ((uint32_t)0x01000000) /* Mask MAC Address low reg bits [70] */ +#define ETH_MACA3HR_MACA3H ((uint32_t)0x0000FFFF) /* MAC address3 high */ + +/* Bit definition for Ethernet MAC Address3 Low Register */ +#define ETH_MACA3LR_MACA3L ((uint32_t)0xFFFFFFFF) /* MAC address3 low */ + +/******************************************************************************/ +/* Ethernet MMC Registers bits definition */ +/******************************************************************************/ + +/* Bit definition for Ethernet MMC Contol Register */ +#define ETH_MMCCR_MCF ((uint32_t)0x00000008) /* MMC Counter Freeze */ +#define ETH_MMCCR_ROR ((uint32_t)0x00000004) /* Reset on Read */ +#define ETH_MMCCR_CSR ((uint32_t)0x00000002) /* Counter Stop Rollover */ +#define ETH_MMCCR_CR ((uint32_t)0x00000001) /* Counters Reset */ + +/* Bit definition for Ethernet MMC Receive Interrupt Register */ +#define ETH_MMCRIR_RGUFS ((uint32_t)0x00020000) /* Set when Rx good unicast frames counter reaches half the maximum value */ +#define ETH_MMCRIR_RFAES ((uint32_t)0x00000040) /* Set when Rx alignment error counter reaches half the maximum value */ +#define ETH_MMCRIR_RFCES ((uint32_t)0x00000020) /* Set when Rx crc error counter reaches half the maximum value */ + +/* Bit definition for Ethernet MMC Transmit Interrupt Register */ +#define ETH_MMCTIR_TGFS ((uint32_t)0x00200000) /* Set when Tx good frame count counter reaches half the maximum value */ +#define ETH_MMCTIR_TGFMSCS ((uint32_t)0x00008000) /* Set when Tx good multi col counter reaches half the maximum value */ +#define ETH_MMCTIR_TGFSCS ((uint32_t)0x00004000) /* Set when Tx good single col counter reaches half the maximum value */ + +/* Bit definition for Ethernet MMC Receive Interrupt Mask Register */ +#define ETH_MMCRIMR_RGUFM ((uint32_t)0x00020000) /* Mask the interrupt when Rx good unicast frames counter reaches half the maximum value */ +#define ETH_MMCRIMR_RFAEM ((uint32_t)0x00000040) /* Mask the interrupt when when Rx alignment error counter reaches half the maximum value */ +#define ETH_MMCRIMR_RFCEM ((uint32_t)0x00000020) /* Mask the interrupt when Rx crc error counter reaches half the maximum value */ + +/* Bit definition for Ethernet MMC Transmit Interrupt Mask Register */ +#define ETH_MMCTIMR_TGFM ((uint32_t)0x00200000) /* Mask the interrupt when Tx good frame count counter reaches half the maximum value */ +#define ETH_MMCTIMR_TGFMSCM ((uint32_t)0x00008000) /* Mask the interrupt when Tx good multi col counter reaches half the maximum value */ +#define ETH_MMCTIMR_TGFSCM ((uint32_t)0x00004000) /* Mask the interrupt when Tx good single col counter reaches half the maximum value */ + +/* Bit definition for Ethernet MMC Transmitted Good Frames after Single Collision Counter Register */ +#define ETH_MMCTGFSCCR_TGFSCC ((uint32_t)0xFFFFFFFF) /* Number of successfully transmitted frames after a single collision in Half-duplex mode. */ + +/* Bit definition for Ethernet MMC Transmitted Good Frames after More than a Single Collision Counter Register */ +#define ETH_MMCTGFMSCCR_TGFMSCC ((uint32_t)0xFFFFFFFF) /* Number of successfully transmitted frames after more than a single collision in Half-duplex mode. */ + +/* Bit definition for Ethernet MMC Transmitted Good Frames Counter Register */ +#define ETH_MMCTGFCR_TGFC ((uint32_t)0xFFFFFFFF) /* Number of good frames transmitted. */ + +/* Bit definition for Ethernet MMC Received Frames with CRC Error Counter Register */ +#define ETH_MMCRFCECR_RFCEC ((uint32_t)0xFFFFFFFF) /* Number of frames received with CRC error. */ + +/* Bit definition for Ethernet MMC Received Frames with Alignement Error Counter Register */ +#define ETH_MMCRFAECR_RFAEC ((uint32_t)0xFFFFFFFF) /* Number of frames received with alignment (dribble) error */ + +/* Bit definition for Ethernet MMC Received Good Unicast Frames Counter Register */ +#define ETH_MMCRGUFCR_RGUFC ((uint32_t)0xFFFFFFFF) /* Number of good unicast frames received. */ + +/******************************************************************************/ +/* Ethernet PTP Registers bits definition */ +/******************************************************************************/ + +/* Bit definition for Ethernet PTP Time Stamp Contol Register */ +#define ETH_PTPTSCR_TSARU ((uint32_t)0x00000020) /* Addend register update */ +#define ETH_PTPTSCR_TSITE ((uint32_t)0x00000010) /* Time stamp interrupt trigger enable */ +#define ETH_PTPTSCR_TSSTU ((uint32_t)0x00000008) /* Time stamp update */ +#define ETH_PTPTSCR_TSSTI ((uint32_t)0x00000004) /* Time stamp initialize */ +#define ETH_PTPTSCR_TSFCU ((uint32_t)0x00000002) /* Time stamp fine or coarse update */ +#define ETH_PTPTSCR_TSE ((uint32_t)0x00000001) /* Time stamp enable */ + +/* Bit definition for Ethernet PTP Sub-Second Increment Register */ +#define ETH_PTPSSIR_STSSI ((uint32_t)0x000000FF) /* System time Sub-second increment value */ + +/* Bit definition for Ethernet PTP Time Stamp High Register */ +#define ETH_PTPTSHR_STS ((uint32_t)0xFFFFFFFF) /* System Time second */ + +/* Bit definition for Ethernet PTP Time Stamp Low Register */ +#define ETH_PTPTSLR_STPNS ((uint32_t)0x80000000) /* System Time Positive or negative time */ +#define ETH_PTPTSLR_STSS ((uint32_t)0x7FFFFFFF) /* System Time sub-seconds */ + +/* Bit definition for Ethernet PTP Time Stamp High Update Register */ +#define ETH_PTPTSHUR_TSUS ((uint32_t)0xFFFFFFFF) /* Time stamp update seconds */ + +/* Bit definition for Ethernet PTP Time Stamp Low Update Register */ +#define ETH_PTPTSLUR_TSUPNS ((uint32_t)0x80000000) /* Time stamp update Positive or negative time */ +#define ETH_PTPTSLUR_TSUSS ((uint32_t)0x7FFFFFFF) /* Time stamp update sub-seconds */ + +/* Bit definition for Ethernet PTP Time Stamp Addend Register */ +#define ETH_PTPTSAR_TSA ((uint32_t)0xFFFFFFFF) /* Time stamp addend */ + +/* Bit definition for Ethernet PTP Target Time High Register */ +#define ETH_PTPTTHR_TTSH ((uint32_t)0xFFFFFFFF) /* Target time stamp high */ + +/* Bit definition for Ethernet PTP Target Time Low Register */ +#define ETH_PTPTTLR_TTSL ((uint32_t)0xFFFFFFFF) /* Target time stamp low */ + +/******************************************************************************/ +/* Ethernet DMA Registers bits definition */ +/******************************************************************************/ + +/* Bit definition for Ethernet DMA Bus Mode Register */ +#define ETH_DMABMR_AAB ((uint32_t)0x02000000) /* Address-Aligned beats */ +#define ETH_DMABMR_FPM ((uint32_t)0x01000000) /* 4xPBL mode */ +#define ETH_DMABMR_USP ((uint32_t)0x00800000) /* Use separate PBL */ +#define ETH_DMABMR_RDP ((uint32_t)0x007E0000) /* RxDMA PBL */ + #define ETH_DMABMR_RDP_1Beat ((uint32_t)0x00020000) /* maximum number of beats to be transferred in one RxDMA transaction is 1 */ + #define ETH_DMABMR_RDP_2Beat ((uint32_t)0x00040000) /* maximum number of beats to be transferred in one RxDMA transaction is 2 */ + #define ETH_DMABMR_RDP_4Beat ((uint32_t)0x00080000) /* maximum number of beats to be transferred in one RxDMA transaction is 4 */ + #define ETH_DMABMR_RDP_8Beat ((uint32_t)0x00100000) /* maximum number of beats to be transferred in one RxDMA transaction is 8 */ + #define ETH_DMABMR_RDP_16Beat ((uint32_t)0x00200000) /* maximum number of beats to be transferred in one RxDMA transaction is 16 */ + #define ETH_DMABMR_RDP_32Beat ((uint32_t)0x00400000) /* maximum number of beats to be transferred in one RxDMA transaction is 32 */ + #define ETH_DMABMR_RDP_4xPBL_4Beat ((uint32_t)0x01020000) /* maximum number of beats to be transferred in one RxDMA transaction is 4 */ + #define ETH_DMABMR_RDP_4xPBL_8Beat ((uint32_t)0x01040000) /* maximum number of beats to be transferred in one RxDMA transaction is 8 */ + #define ETH_DMABMR_RDP_4xPBL_16Beat ((uint32_t)0x01080000) /* maximum number of beats to be transferred in one RxDMA transaction is 16 */ + #define ETH_DMABMR_RDP_4xPBL_32Beat ((uint32_t)0x01100000) /* maximum number of beats to be transferred in one RxDMA transaction is 32 */ + #define ETH_DMABMR_RDP_4xPBL_64Beat ((uint32_t)0x01200000) /* maximum number of beats to be transferred in one RxDMA transaction is 64 */ + #define ETH_DMABMR_RDP_4xPBL_128Beat ((uint32_t)0x01400000) /* maximum number of beats to be transferred in one RxDMA transaction is 128 */ +#define ETH_DMABMR_FB ((uint32_t)0x00010000) /* Fixed Burst */ +#define ETH_DMABMR_RTPR ((uint32_t)0x0000C000) /* Rx Tx priority ratio */ + #define ETH_DMABMR_RTPR_1_1 ((uint32_t)0x00000000) /* Rx Tx priority ratio */ + #define ETH_DMABMR_RTPR_2_1 ((uint32_t)0x00004000) /* Rx Tx priority ratio */ + #define ETH_DMABMR_RTPR_3_1 ((uint32_t)0x00008000) /* Rx Tx priority ratio */ + #define ETH_DMABMR_RTPR_4_1 ((uint32_t)0x0000C000) /* Rx Tx priority ratio */ +#define ETH_DMABMR_PBL ((uint32_t)0x00003F00) /* Programmable burst length */ + #define ETH_DMABMR_PBL_1Beat ((uint32_t)0x00000100) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 1 */ + #define ETH_DMABMR_PBL_2Beat ((uint32_t)0x00000200) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 2 */ + #define ETH_DMABMR_PBL_4Beat ((uint32_t)0x00000400) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 4 */ + #define ETH_DMABMR_PBL_8Beat ((uint32_t)0x00000800) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 8 */ + #define ETH_DMABMR_PBL_16Beat ((uint32_t)0x00001000) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 16 */ + #define ETH_DMABMR_PBL_32Beat ((uint32_t)0x00002000) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 32 */ + #define ETH_DMABMR_PBL_4xPBL_4Beat ((uint32_t)0x01000100) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 4 */ + #define ETH_DMABMR_PBL_4xPBL_8Beat ((uint32_t)0x01000200) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 8 */ + #define ETH_DMABMR_PBL_4xPBL_16Beat ((uint32_t)0x01000400) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 16 */ + #define ETH_DMABMR_PBL_4xPBL_32Beat ((uint32_t)0x01000800) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 32 */ + #define ETH_DMABMR_PBL_4xPBL_64Beat ((uint32_t)0x01001000) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 64 */ + #define ETH_DMABMR_PBL_4xPBL_128Beat ((uint32_t)0x01002000) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 128 */ +#define ETH_DMABMR_DSL ((uint32_t)0x0000007C) /* Descriptor Skip Length */ +#define ETH_DMABMR_DA ((uint32_t)0x00000002) /* DMA arbitration scheme */ +#define ETH_DMABMR_SR ((uint32_t)0x00000001) /* Software reset */ + +/* Bit definition for Ethernet DMA Transmit Poll Demand Register */ +#define ETH_DMATPDR_TPD ((uint32_t)0xFFFFFFFF) /* Transmit poll demand */ + +/* Bit definition for Ethernet DMA Receive Poll Demand Register */ +#define ETH_DMARPDR_RPD ((uint32_t)0xFFFFFFFF) /* Receive poll demand */ + +/* Bit definition for Ethernet DMA Receive Descriptor List Address Register */ +#define ETH_DMARDLAR_SRL ((uint32_t)0xFFFFFFFF) /* Start of receive list */ + +/* Bit definition for Ethernet DMA Transmit Descriptor List Address Register */ +#define ETH_DMATDLAR_STL ((uint32_t)0xFFFFFFFF) /* Start of transmit list */ + +/* Bit definition for Ethernet DMA Status Register */ +#define ETH_DMASR_TSTS ((uint32_t)0x20000000) /* Time-stamp trigger status */ +#define ETH_DMASR_PMTS ((uint32_t)0x10000000) /* PMT status */ +#define ETH_DMASR_MMCS ((uint32_t)0x08000000) /* MMC status */ +#define ETH_DMASR_EBS ((uint32_t)0x03800000) /* Error bits status */ + /* combination with EBS[2:0] for GetFlagStatus function */ + #define ETH_DMASR_EBS_DescAccess ((uint32_t)0x02000000) /* Error bits 0-data buffer, 1-desc. access */ + #define ETH_DMASR_EBS_ReadTransf ((uint32_t)0x01000000) /* Error bits 0-write trnsf, 1-read transfr */ + #define ETH_DMASR_EBS_DataTransfTx ((uint32_t)0x00800000) /* Error bits 0-Rx DMA, 1-Tx DMA */ +#define ETH_DMASR_TPS ((uint32_t)0x00700000) /* Transmit process state */ + #define ETH_DMASR_TPS_Stopped ((uint32_t)0x00000000) /* Stopped - Reset or Stop Tx Command issued */ + #define ETH_DMASR_TPS_Fetching ((uint32_t)0x00100000) /* Running - fetching the Tx descriptor */ + #define ETH_DMASR_TPS_Waiting ((uint32_t)0x00200000) /* Running - waiting for status */ + #define ETH_DMASR_TPS_Reading ((uint32_t)0x00300000) /* Running - reading the data from host memory */ + #define ETH_DMASR_TPS_Suspended ((uint32_t)0x00600000) /* Suspended - Tx Descriptor unavailabe */ + #define ETH_DMASR_TPS_Closing ((uint32_t)0x00700000) /* Running - closing Rx descriptor */ +#define ETH_DMASR_RPS ((uint32_t)0x000E0000) /* Receive process state */ + #define ETH_DMASR_RPS_Stopped ((uint32_t)0x00000000) /* Stopped - Reset or Stop Rx Command issued */ + #define ETH_DMASR_RPS_Fetching ((uint32_t)0x00020000) /* Running - fetching the Rx descriptor */ + #define ETH_DMASR_RPS_Waiting ((uint32_t)0x00060000) /* Running - waiting for packet */ + #define ETH_DMASR_RPS_Suspended ((uint32_t)0x00080000) /* Suspended - Rx Descriptor unavailable */ + #define ETH_DMASR_RPS_Closing ((uint32_t)0x000A0000) /* Running - closing descriptor */ + #define ETH_DMASR_RPS_Queuing ((uint32_t)0x000E0000) /* Running - queuing the recieve frame into host memory */ +#define ETH_DMASR_NIS ((uint32_t)0x00010000) /* Normal interrupt summary */ +#define ETH_DMASR_AIS ((uint32_t)0x00008000) /* Abnormal interrupt summary */ +#define ETH_DMASR_ERS ((uint32_t)0x00004000) /* Early receive status */ +#define ETH_DMASR_FBES ((uint32_t)0x00002000) /* Fatal bus error status */ +#define ETH_DMASR_ETS ((uint32_t)0x00000400) /* Early transmit status */ +#define ETH_DMASR_RWTS ((uint32_t)0x00000200) /* Receive watchdog timeout status */ +#define ETH_DMASR_RPSS ((uint32_t)0x00000100) /* Receive process stopped status */ +#define ETH_DMASR_RBUS ((uint32_t)0x00000080) /* Receive buffer unavailable status */ +#define ETH_DMASR_RS ((uint32_t)0x00000040) /* Receive status */ +#define ETH_DMASR_TUS ((uint32_t)0x00000020) /* Transmit underflow status */ +#define ETH_DMASR_ROS ((uint32_t)0x00000010) /* Receive overflow status */ +#define ETH_DMASR_TJTS ((uint32_t)0x00000008) /* Transmit jabber timeout status */ +#define ETH_DMASR_TBUS ((uint32_t)0x00000004) /* Transmit buffer unavailable status */ +#define ETH_DMASR_TPSS ((uint32_t)0x00000002) /* Transmit process stopped status */ +#define ETH_DMASR_TS ((uint32_t)0x00000001) /* Transmit status */ + +/* Bit definition for Ethernet DMA Operation Mode Register */ +#define ETH_DMAOMR_DTCEFD ((uint32_t)0x04000000) /* Disable Dropping of TCP/IP checksum error frames */ +#define ETH_DMAOMR_RSF ((uint32_t)0x02000000) /* Receive store and forward */ +#define ETH_DMAOMR_DFRF ((uint32_t)0x01000000) /* Disable flushing of received frames */ +#define ETH_DMAOMR_TSF ((uint32_t)0x00200000) /* Transmit store and forward */ +#define ETH_DMAOMR_FTF ((uint32_t)0x00100000) /* Flush transmit FIFO */ +#define ETH_DMAOMR_TTC ((uint32_t)0x0001C000) /* Transmit threshold control */ + #define ETH_DMAOMR_TTC_64Bytes ((uint32_t)0x00000000) /* threshold level of the MTL Transmit FIFO is 64 Bytes */ + #define ETH_DMAOMR_TTC_128Bytes ((uint32_t)0x00004000) /* threshold level of the MTL Transmit FIFO is 128 Bytes */ + #define ETH_DMAOMR_TTC_192Bytes ((uint32_t)0x00008000) /* threshold level of the MTL Transmit FIFO is 192 Bytes */ + #define ETH_DMAOMR_TTC_256Bytes ((uint32_t)0x0000C000) /* threshold level of the MTL Transmit FIFO is 256 Bytes */ + #define ETH_DMAOMR_TTC_40Bytes ((uint32_t)0x00010000) /* threshold level of the MTL Transmit FIFO is 40 Bytes */ + #define ETH_DMAOMR_TTC_32Bytes ((uint32_t)0x00014000) /* threshold level of the MTL Transmit FIFO is 32 Bytes */ + #define ETH_DMAOMR_TTC_24Bytes ((uint32_t)0x00018000) /* threshold level of the MTL Transmit FIFO is 24 Bytes */ + #define ETH_DMAOMR_TTC_16Bytes ((uint32_t)0x0001C000) /* threshold level of the MTL Transmit FIFO is 16 Bytes */ +#define ETH_DMAOMR_ST ((uint32_t)0x00002000) /* Start/stop transmission command */ +#define ETH_DMAOMR_FEF ((uint32_t)0x00000080) /* Forward error frames */ +#define ETH_DMAOMR_FUGF ((uint32_t)0x00000040) /* Forward undersized good frames */ +#define ETH_DMAOMR_RTC ((uint32_t)0x00000018) /* receive threshold control */ + #define ETH_DMAOMR_RTC_64Bytes ((uint32_t)0x00000000) /* threshold level of the MTL Receive FIFO is 64 Bytes */ + #define ETH_DMAOMR_RTC_32Bytes ((uint32_t)0x00000008) /* threshold level of the MTL Receive FIFO is 32 Bytes */ + #define ETH_DMAOMR_RTC_96Bytes ((uint32_t)0x00000010) /* threshold level of the MTL Receive FIFO is 96 Bytes */ + #define ETH_DMAOMR_RTC_128Bytes ((uint32_t)0x00000018) /* threshold level of the MTL Receive FIFO is 128 Bytes */ +#define ETH_DMAOMR_OSF ((uint32_t)0x00000004) /* operate on second frame */ +#define ETH_DMAOMR_SR ((uint32_t)0x00000002) /* Start/stop receive */ + +/* Bit definition for Ethernet DMA Interrupt Enable Register */ +#define ETH_DMAIER_NISE ((uint32_t)0x00010000) /* Normal interrupt summary enable */ +#define ETH_DMAIER_AISE ((uint32_t)0x00008000) /* Abnormal interrupt summary enable */ +#define ETH_DMAIER_ERIE ((uint32_t)0x00004000) /* Early receive interrupt enable */ +#define ETH_DMAIER_FBEIE ((uint32_t)0x00002000) /* Fatal bus error interrupt enable */ +#define ETH_DMAIER_ETIE ((uint32_t)0x00000400) /* Early transmit interrupt enable */ +#define ETH_DMAIER_RWTIE ((uint32_t)0x00000200) /* Receive watchdog timeout interrupt enable */ +#define ETH_DMAIER_RPSIE ((uint32_t)0x00000100) /* Receive process stopped interrupt enable */ +#define ETH_DMAIER_RBUIE ((uint32_t)0x00000080) /* Receive buffer unavailable interrupt enable */ +#define ETH_DMAIER_RIE ((uint32_t)0x00000040) /* Receive interrupt enable */ +#define ETH_DMAIER_TUIE ((uint32_t)0x00000020) /* Transmit Underflow interrupt enable */ +#define ETH_DMAIER_ROIE ((uint32_t)0x00000010) /* Receive Overflow interrupt enable */ +#define ETH_DMAIER_TJTIE ((uint32_t)0x00000008) /* Transmit jabber timeout interrupt enable */ +#define ETH_DMAIER_TBUIE ((uint32_t)0x00000004) /* Transmit buffer unavailable interrupt enable */ +#define ETH_DMAIER_TPSIE ((uint32_t)0x00000002) /* Transmit process stopped interrupt enable */ +#define ETH_DMAIER_TIE ((uint32_t)0x00000001) /* Transmit interrupt enable */ + +/* Bit definition for Ethernet DMA Missed Frame and Buffer Overflow Counter Register */ +#define ETH_DMAMFBOCR_OFOC ((uint32_t)0x10000000) /* Overflow bit for FIFO overflow counter */ +#define ETH_DMAMFBOCR_MFA ((uint32_t)0x0FFE0000) /* Number of frames missed by the application */ +#define ETH_DMAMFBOCR_OMFC ((uint32_t)0x00010000) /* Overflow bit for missed frame counter */ +#define ETH_DMAMFBOCR_MFC ((uint32_t)0x0000FFFF) /* Number of frames missed by the controller */ + +/* Bit definition for Ethernet DMA Current Host Transmit Descriptor Register */ +#define ETH_DMACHTDR_HTDAP ((uint32_t)0xFFFFFFFF) /* Host transmit descriptor address pointer */ + +/* Bit definition for Ethernet DMA Current Host Receive Descriptor Register */ +#define ETH_DMACHRDR_HRDAP ((uint32_t)0xFFFFFFFF) /* Host receive descriptor address pointer */ + +/* Bit definition for Ethernet DMA Current Host Transmit Buffer Address Register */ +#define ETH_DMACHTBAR_HTBAP ((uint32_t)0xFFFFFFFF) /* Host transmit buffer address pointer */ + +/* Bit definition for Ethernet DMA Current Host Receive Buffer Address Register */ +#define ETH_DMACHRBAR_HRBAP ((uint32_t)0xFFFFFFFF) /* Host receive buffer address pointer */ +#endif /* STM32F10X_CL */ + +/** + * @} + */ + + /** + * @} + */ + +#ifdef USE_STDPERIPH_DRIVER + #include "stm32f10x_conf.h" +#endif + +/** @addtogroup Exported_macro + * @{ + */ + +#define SET_BIT(REG, BIT) ((REG) |= (BIT)) + +#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT)) + +#define READ_BIT(REG, BIT) ((REG) & (BIT)) + +#define CLEAR_REG(REG) ((REG) = (0x0)) + +#define WRITE_REG(REG, VAL) ((REG) = (VAL)) + +#define READ_REG(REG) ((REG)) + +#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK))) + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_H */ + +/** + * @} + */ + + /** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x_conf.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x_conf.h new file mode 100644 index 0000000..1865daf --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x_conf.h @@ -0,0 +1,79 @@ +/** + ****************************************************************************** + * @file Project/STM32F10x_StdPeriph_Template/stm32f10x_conf.h + * @author MCD Application Team + * @version V3.5.0 + * @date 08-April-2011 + * @brief Library configuration file. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_CONF_H +#define __STM32F10x_CONF_H + +/* Includes ------------------------------------------------------------------*/ +/* Uncomment/Comment the line below to enable/disable peripheral header file inclusion */ +#include "stm32f10x_adc.h" +#include "stm32f10x_bkp.h" +#include "stm32f10x_can.h" +#include "stm32f10x_cec.h" +#include "stm32f10x_crc.h" +#include "stm32f10x_dac.h" +#include "stm32f10x_dbgmcu.h" +#include "stm32f10x_dma.h" +#include "stm32f10x_exti.h" +#include "stm32f10x_flash.h" +#include "stm32f10x_fsmc.h" +#include "stm32f10x_gpio.h" +#include "stm32f10x_i2c.h" +#include "stm32f10x_iwdg.h" +#include "stm32f10x_pwr.h" +#include "stm32f10x_rcc.h" +#include "stm32f10x_rtc.h" +#include "stm32f10x_sdio.h" +#include "stm32f10x_spi.h" +#include "stm32f10x_tim.h" +#include "stm32f10x_usart.h" +#include "stm32f10x_wwdg.h" +#include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */ + +extern void assert_param(int val); + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Uncomment the line below to expanse the "assert_param" macro in the + Standard Peripheral Library drivers code */ +// #define USE_FULL_ASSERT 1 + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT + +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function which reports + * the name of the source file and the source line number of the call + * that failed. If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0) +#endif /* USE_FULL_ASSERT */ + +#endif /* __STM32F10x_CONF_H */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.c new file mode 100644 index 0000000..0f655f1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.c @@ -0,0 +1,175 @@ +#include +#include "stm32f10x.h" + +#define SYSCLK_FREQ_72MHz 72000000 + +uint32_t SystemCoreClock = SYSCLK_FREQ_72MHz; /*!< System Clock Frequency (Core Clock) */ + +__I uint8_t AHBPrescTable[16] = { 0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9 }; + +uint32_t hse_value = 8000000; + +void SystemInit(void) +{ + /* Reset the RCC clock configuration to the default reset state(for debug purpose) */ + /* Set HSION bit */ + RCC->CR |= (uint32_t) 0x00000001; + + /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */ + RCC->CFGR &= (uint32_t) 0xF8FF0000; + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t) 0xFEF6FFFF; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t) 0xFFFBFFFF; + + /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */ + RCC->CFGR &= (uint32_t) 0xFF80FFFF; + + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x009F0000; + + SCB->VTOR = FLASH_BASE; /* Vector Table Relocation in Internal FLASH. */ +} + +void SystemCoreClockUpdate(void) +{ + uint32_t tmp = 0, pllmull = 0, pllsource = 0; + + /* Get SYSCLK source ------------------------------------------------------- */ + tmp = RCC->CFGR & RCC_CFGR_SWS; + + switch (tmp) { + case 0x00: /* HSI used as system clock */ + SystemCoreClock = HSI_VALUE; + break; + case 0x04: /* HSE used as system clock */ + SystemCoreClock = hse_value; + break; + case 0x08: /* PLL used as system clock */ + + /* Get PLL clock source and multiplication factor ---------------------- */ + pllmull = RCC->CFGR & RCC_CFGR_PLLMULL; + pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; + + pllmull = (pllmull >> 18) + 2; + + if (pllsource == 0x00) { + /* HSI oscillator clock divided by 2 selected as PLL clock entry */ + SystemCoreClock = (HSI_VALUE >> 1) * pllmull; + } else { + /* HSE selected as PLL clock entry */ + if ((RCC->CFGR & RCC_CFGR_PLLXTPRE) != (uint32_t) RESET) { /* HSE oscillator clock divided by 2 */ + SystemCoreClock = (hse_value >> 1) * pllmull; + } else { + SystemCoreClock = hse_value * pllmull; + } + } + break; + + default: + SystemCoreClock = HSI_VALUE; + break; + } + + /* Compute HCLK clock frequency ---------------- */ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; + /* HCLK clock frequency */ + SystemCoreClock >>= tmp; +} + +enum { + SRC_NONE = 0, + SRC_HSI, + SRC_HSE +}; + +// Set system clock to 72 (HSE) or 64 (HSI) MHz +void SetSysClock(bool overclock) +{ + __IO uint32_t StartUpCounter = 0, status = 0, clocksrc = SRC_NONE; + __IO uint32_t *RCC_CRH = &GPIOC->CRH; + __IO uint32_t RCC_CFGR_PLLMUL = RCC_CFGR_PLLMULL9; + + // First, try running off HSE + RCC->CR |= ((uint32_t)RCC_CR_HSEON); + RCC->APB2ENR |= RCC_CFGR_HPRE_0; + + // Wait till HSE is ready + do { + status = RCC->CR & RCC_CR_HSERDY; + StartUpCounter++; + } while ((status == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + + if ((RCC->CR & RCC_CR_HSERDY) != RESET) { + // external xtal started up, we're good to go + clocksrc = SRC_HSE; + } else { + // If HSE fails to start-up, try to enable HSI and configure for 64MHz operation + RCC->CR |= ((uint32_t)RCC_CR_HSION); + StartUpCounter = 0; + do { + status = RCC->CR & RCC_CR_HSIRDY; + StartUpCounter++; + } while ((status == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + if ((RCC->CR & RCC_CR_HSIRDY) != RESET) { + // we're on internal RC + clocksrc = SRC_HSI; + } else { + // We're fucked + while(1); + } + } + + // Enable Prefetch Buffer + FLASH->ACR |= FLASH_ACR_PRFTBE; + // Flash 2 wait state + FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); + FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2; + // HCLK = SYSCLK + RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; + // PCLK2 = HCLK + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; + // PCLK1 = HCLK + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; + *RCC_CRH &= (uint32_t)~((uint32_t)0xF << (RCC_CFGR_PLLMULL9 >> 16)); + + // Configure PLL + hse_value = 8000000; + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); + *RCC_CRH |= (uint32_t)0x8 << (RCC_CFGR_PLLMULL9 >> 16); + GPIOC->ODR &= (uint32_t)~(CAN_MCR_RESET); + + RCC_CFGR_PLLMUL = GPIOC->IDR & CAN_MCR_RESET ? hse_value = 12000000, RCC_CFGR_PLLMULL6 : RCC_CFGR_PLLMULL9; + switch (clocksrc) { + case SRC_HSE: + if (overclock) { + if (RCC_CFGR_PLLMUL == RCC_CFGR_PLLMULL6) + RCC_CFGR_PLLMUL = RCC_CFGR_PLLMULL7; + else if (RCC_CFGR_PLLMUL == RCC_CFGR_PLLMULL9) + RCC_CFGR_PLLMUL = RCC_CFGR_PLLMULL10; + } + // overclock=false : PLL configuration: PLLCLK = HSE * 9 = 72 MHz || HSE * 6 = 72 MHz + // overclock=true : PLL configuration: PLLCLK = HSE * 10 = 80 MHz || HSE * 7 = 84 MHz + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMUL); + break; + case SRC_HSI: + // PLL configuration: PLLCLK = HSI / 2 * 16 = 64 MHz + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSI_Div2 | RCC_CFGR_PLLMULL16); + break; + } + + // Enable PLL + RCC->CR |= RCC_CR_PLLON; + // Wait till PLL is ready + while ((RCC->CR & RCC_CR_PLLRDY) == 0); + // Select PLL as system clock source + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; + // Wait till PLL is used as system clock source + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08); + + SystemCoreClockUpdate(); +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.h new file mode 100644 index 0000000..54bc1ab --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.h @@ -0,0 +1,98 @@ +/** + ****************************************************************************** + * @file system_stm32f10x.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Header File. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f10x_system + * @{ + */ + +/** + * @brief Define to prevent recursive inclusion + */ +#ifndef __SYSTEM_STM32F10X_H +#define __SYSTEM_STM32F10X_H + +#ifdef __cplusplus + extern "C" { +#endif + +/** @addtogroup STM32F10x_System_Includes + * @{ + */ + +/** + * @} + */ + + +/** @addtogroup STM32F10x_System_Exported_types + * @{ + */ + +extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ + +/** + * @} + */ + +/** @addtogroup STM32F10x_System_Exported_Constants + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F10x_System_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F10x_System_Exported_Functions + * @{ + */ + +extern void SystemInit(void); +extern void SystemCoreClockUpdate(void); +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /*__SYSTEM_STM32F10X_H */ + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/misc.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/misc.h new file mode 100644 index 0000000..9a6bd07 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/misc.h @@ -0,0 +1,220 @@ +/** + ****************************************************************************** + * @file misc.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the miscellaneous + * firmware library functions (add-on to CMSIS functions). + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __MISC_H +#define __MISC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup MISC + * @{ + */ + +/** @defgroup MISC_Exported_Types + * @{ + */ + +/** + * @brief NVIC Init Structure definition + */ + +typedef struct +{ + uint8_t NVIC_IRQChannel; /*!< Specifies the IRQ channel to be enabled or disabled. + This parameter can be a value of @ref IRQn_Type + (For the complete STM32 Devices IRQ Channels list, please + refer to stm32f10x.h file) */ + + uint8_t NVIC_IRQChannelPreemptionPriority; /*!< Specifies the pre-emption priority for the IRQ channel + specified in NVIC_IRQChannel. This parameter can be a value + between 0 and 15 as described in the table @ref NVIC_Priority_Table */ + + uint8_t NVIC_IRQChannelSubPriority; /*!< Specifies the subpriority level for the IRQ channel specified + in NVIC_IRQChannel. This parameter can be a value + between 0 and 15 as described in the table @ref NVIC_Priority_Table */ + + FunctionalState NVIC_IRQChannelCmd; /*!< Specifies whether the IRQ channel defined in NVIC_IRQChannel + will be enabled or disabled. + This parameter can be set either to ENABLE or DISABLE */ +} NVIC_InitTypeDef; + +/** + * @} + */ + +/** @defgroup NVIC_Priority_Table + * @{ + */ + +/** +@code + The table below gives the allowed values of the pre-emption priority and subpriority according + to the Priority Grouping configuration performed by NVIC_PriorityGroupConfig function + ============================================================================================================================ + NVIC_PriorityGroup | NVIC_IRQChannelPreemptionPriority | NVIC_IRQChannelSubPriority | Description + ============================================================================================================================ + NVIC_PriorityGroup_0 | 0 | 0-15 | 0 bits for pre-emption priority + | | | 4 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_1 | 0-1 | 0-7 | 1 bits for pre-emption priority + | | | 3 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_2 | 0-3 | 0-3 | 2 bits for pre-emption priority + | | | 2 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_3 | 0-7 | 0-1 | 3 bits for pre-emption priority + | | | 1 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_4 | 0-15 | 0 | 4 bits for pre-emption priority + | | | 0 bits for subpriority + ============================================================================================================================ +@endcode +*/ + +/** + * @} + */ + +/** @defgroup MISC_Exported_Constants + * @{ + */ + +/** @defgroup Vector_Table_Base + * @{ + */ + +#define NVIC_VectTab_RAM ((uint32_t)0x20000000) +#define NVIC_VectTab_FLASH ((uint32_t)0x08000000) +#define IS_NVIC_VECTTAB(VECTTAB) (((VECTTAB) == NVIC_VectTab_RAM) || \ + ((VECTTAB) == NVIC_VectTab_FLASH)) +/** + * @} + */ + +/** @defgroup System_Low_Power + * @{ + */ + +#define NVIC_LP_SEVONPEND ((uint8_t)0x10) +#define NVIC_LP_SLEEPDEEP ((uint8_t)0x04) +#define NVIC_LP_SLEEPONEXIT ((uint8_t)0x02) +#define IS_NVIC_LP(LP) (((LP) == NVIC_LP_SEVONPEND) || \ + ((LP) == NVIC_LP_SLEEPDEEP) || \ + ((LP) == NVIC_LP_SLEEPONEXIT)) +/** + * @} + */ + +/** @defgroup Preemption_Priority_Group + * @{ + */ + +#define NVIC_PriorityGroup_0 ((uint32_t)0x700) /*!< 0 bits for pre-emption priority + 4 bits for subpriority */ +#define NVIC_PriorityGroup_1 ((uint32_t)0x600) /*!< 1 bits for pre-emption priority + 3 bits for subpriority */ +#define NVIC_PriorityGroup_2 ((uint32_t)0x500) /*!< 2 bits for pre-emption priority + 2 bits for subpriority */ +#define NVIC_PriorityGroup_3 ((uint32_t)0x400) /*!< 3 bits for pre-emption priority + 1 bits for subpriority */ +#define NVIC_PriorityGroup_4 ((uint32_t)0x300) /*!< 4 bits for pre-emption priority + 0 bits for subpriority */ + +#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PriorityGroup_0) || \ + ((GROUP) == NVIC_PriorityGroup_1) || \ + ((GROUP) == NVIC_PriorityGroup_2) || \ + ((GROUP) == NVIC_PriorityGroup_3) || \ + ((GROUP) == NVIC_PriorityGroup_4)) + +#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x10) + +#define IS_NVIC_SUB_PRIORITY(PRIORITY) ((PRIORITY) < 0x10) + +#define IS_NVIC_OFFSET(OFFSET) ((OFFSET) < 0x000FFFFF) + +/** + * @} + */ + +/** @defgroup SysTick_clock_source + * @{ + */ + +#define SysTick_CLKSource_HCLK_Div8 ((uint32_t)0xFFFFFFFB) +#define SysTick_CLKSource_HCLK ((uint32_t)0x00000004) +#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SysTick_CLKSource_HCLK) || \ + ((SOURCE) == SysTick_CLKSource_HCLK_Div8)) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup MISC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup MISC_Exported_Functions + * @{ + */ + +void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup); +void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct); +void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset); +void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState); +void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource); + +#ifdef __cplusplus +} +#endif + +#endif /* __MISC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h new file mode 100644 index 0000000..c465d33 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h @@ -0,0 +1,483 @@ +/** + ****************************************************************************** + * @file stm32f10x_adc.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the ADC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_ADC_H +#define __STM32F10x_ADC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup ADC + * @{ + */ + +/** @defgroup ADC_Exported_Types + * @{ + */ + +/** + * @brief ADC Init structure definition + */ + +typedef struct +{ + uint32_t ADC_Mode; /*!< Configures the ADC to operate in independent or + dual mode. + This parameter can be a value of @ref ADC_mode */ + + FunctionalState ADC_ScanConvMode; /*!< Specifies whether the conversion is performed in + Scan (multichannels) or Single (one channel) mode. + This parameter can be set to ENABLE or DISABLE */ + + FunctionalState ADC_ContinuousConvMode; /*!< Specifies whether the conversion is performed in + Continuous or Single mode. + This parameter can be set to ENABLE or DISABLE. */ + + uint32_t ADC_ExternalTrigConv; /*!< Defines the external trigger used to start the analog + to digital conversion of regular channels. This parameter + can be a value of @ref ADC_external_trigger_sources_for_regular_channels_conversion */ + + uint32_t ADC_DataAlign; /*!< Specifies whether the ADC data alignment is left or right. + This parameter can be a value of @ref ADC_data_align */ + + uint8_t ADC_NbrOfChannel; /*!< Specifies the number of ADC channels that will be converted + using the sequencer for regular channel group. + This parameter must range from 1 to 16. */ +}ADC_InitTypeDef; +/** + * @} + */ + +/** @defgroup ADC_Exported_Constants + * @{ + */ + +#define IS_ADC_ALL_PERIPH(PERIPH) (((PERIPH) == ADC1) || \ + ((PERIPH) == ADC2) || \ + ((PERIPH) == ADC3)) + +#define IS_ADC_DMA_PERIPH(PERIPH) (((PERIPH) == ADC1) || \ + ((PERIPH) == ADC3)) + +/** @defgroup ADC_mode + * @{ + */ + +#define ADC_Mode_Independent ((uint32_t)0x00000000) +#define ADC_Mode_RegInjecSimult ((uint32_t)0x00010000) +#define ADC_Mode_RegSimult_AlterTrig ((uint32_t)0x00020000) +#define ADC_Mode_InjecSimult_FastInterl ((uint32_t)0x00030000) +#define ADC_Mode_InjecSimult_SlowInterl ((uint32_t)0x00040000) +#define ADC_Mode_InjecSimult ((uint32_t)0x00050000) +#define ADC_Mode_RegSimult ((uint32_t)0x00060000) +#define ADC_Mode_FastInterl ((uint32_t)0x00070000) +#define ADC_Mode_SlowInterl ((uint32_t)0x00080000) +#define ADC_Mode_AlterTrig ((uint32_t)0x00090000) + +#define IS_ADC_MODE(MODE) (((MODE) == ADC_Mode_Independent) || \ + ((MODE) == ADC_Mode_RegInjecSimult) || \ + ((MODE) == ADC_Mode_RegSimult_AlterTrig) || \ + ((MODE) == ADC_Mode_InjecSimult_FastInterl) || \ + ((MODE) == ADC_Mode_InjecSimult_SlowInterl) || \ + ((MODE) == ADC_Mode_InjecSimult) || \ + ((MODE) == ADC_Mode_RegSimult) || \ + ((MODE) == ADC_Mode_FastInterl) || \ + ((MODE) == ADC_Mode_SlowInterl) || \ + ((MODE) == ADC_Mode_AlterTrig)) +/** + * @} + */ + +/** @defgroup ADC_external_trigger_sources_for_regular_channels_conversion + * @{ + */ + +#define ADC_ExternalTrigConv_T1_CC1 ((uint32_t)0x00000000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigConv_T1_CC2 ((uint32_t)0x00020000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigConv_T2_CC2 ((uint32_t)0x00060000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigConv_T3_TRGO ((uint32_t)0x00080000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigConv_T4_CC4 ((uint32_t)0x000A0000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO ((uint32_t)0x000C0000) /*!< For ADC1 and ADC2 */ + +#define ADC_ExternalTrigConv_T1_CC3 ((uint32_t)0x00040000) /*!< For ADC1, ADC2 and ADC3 */ +#define ADC_ExternalTrigConv_None ((uint32_t)0x000E0000) /*!< For ADC1, ADC2 and ADC3 */ + +#define ADC_ExternalTrigConv_T3_CC1 ((uint32_t)0x00000000) /*!< For ADC3 only */ +#define ADC_ExternalTrigConv_T2_CC3 ((uint32_t)0x00020000) /*!< For ADC3 only */ +#define ADC_ExternalTrigConv_T8_CC1 ((uint32_t)0x00060000) /*!< For ADC3 only */ +#define ADC_ExternalTrigConv_T8_TRGO ((uint32_t)0x00080000) /*!< For ADC3 only */ +#define ADC_ExternalTrigConv_T5_CC1 ((uint32_t)0x000A0000) /*!< For ADC3 only */ +#define ADC_ExternalTrigConv_T5_CC3 ((uint32_t)0x000C0000) /*!< For ADC3 only */ + +#define IS_ADC_EXT_TRIG(REGTRIG) (((REGTRIG) == ADC_ExternalTrigConv_T1_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T1_CC2) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T1_CC3) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T2_CC2) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T3_TRGO) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T4_CC4) || \ + ((REGTRIG) == ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO) || \ + ((REGTRIG) == ADC_ExternalTrigConv_None) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T3_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T2_CC3) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T8_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T8_TRGO) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T5_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T5_CC3)) +/** + * @} + */ + +/** @defgroup ADC_data_align + * @{ + */ + +#define ADC_DataAlign_Right ((uint32_t)0x00000000) +#define ADC_DataAlign_Left ((uint32_t)0x00000800) +#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DataAlign_Right) || \ + ((ALIGN) == ADC_DataAlign_Left)) +/** + * @} + */ + +/** @defgroup ADC_channels + * @{ + */ + +#define ADC_Channel_0 ((uint8_t)0x00) +#define ADC_Channel_1 ((uint8_t)0x01) +#define ADC_Channel_2 ((uint8_t)0x02) +#define ADC_Channel_3 ((uint8_t)0x03) +#define ADC_Channel_4 ((uint8_t)0x04) +#define ADC_Channel_5 ((uint8_t)0x05) +#define ADC_Channel_6 ((uint8_t)0x06) +#define ADC_Channel_7 ((uint8_t)0x07) +#define ADC_Channel_8 ((uint8_t)0x08) +#define ADC_Channel_9 ((uint8_t)0x09) +#define ADC_Channel_10 ((uint8_t)0x0A) +#define ADC_Channel_11 ((uint8_t)0x0B) +#define ADC_Channel_12 ((uint8_t)0x0C) +#define ADC_Channel_13 ((uint8_t)0x0D) +#define ADC_Channel_14 ((uint8_t)0x0E) +#define ADC_Channel_15 ((uint8_t)0x0F) +#define ADC_Channel_16 ((uint8_t)0x10) +#define ADC_Channel_17 ((uint8_t)0x11) + +#define ADC_Channel_TempSensor ((uint8_t)ADC_Channel_16) +#define ADC_Channel_Vrefint ((uint8_t)ADC_Channel_17) + +#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) == ADC_Channel_0) || ((CHANNEL) == ADC_Channel_1) || \ + ((CHANNEL) == ADC_Channel_2) || ((CHANNEL) == ADC_Channel_3) || \ + ((CHANNEL) == ADC_Channel_4) || ((CHANNEL) == ADC_Channel_5) || \ + ((CHANNEL) == ADC_Channel_6) || ((CHANNEL) == ADC_Channel_7) || \ + ((CHANNEL) == ADC_Channel_8) || ((CHANNEL) == ADC_Channel_9) || \ + ((CHANNEL) == ADC_Channel_10) || ((CHANNEL) == ADC_Channel_11) || \ + ((CHANNEL) == ADC_Channel_12) || ((CHANNEL) == ADC_Channel_13) || \ + ((CHANNEL) == ADC_Channel_14) || ((CHANNEL) == ADC_Channel_15) || \ + ((CHANNEL) == ADC_Channel_16) || ((CHANNEL) == ADC_Channel_17)) +/** + * @} + */ + +/** @defgroup ADC_sampling_time + * @{ + */ + +#define ADC_SampleTime_1Cycles5 ((uint8_t)0x00) +#define ADC_SampleTime_7Cycles5 ((uint8_t)0x01) +#define ADC_SampleTime_13Cycles5 ((uint8_t)0x02) +#define ADC_SampleTime_28Cycles5 ((uint8_t)0x03) +#define ADC_SampleTime_41Cycles5 ((uint8_t)0x04) +#define ADC_SampleTime_55Cycles5 ((uint8_t)0x05) +#define ADC_SampleTime_71Cycles5 ((uint8_t)0x06) +#define ADC_SampleTime_239Cycles5 ((uint8_t)0x07) +#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SampleTime_1Cycles5) || \ + ((TIME) == ADC_SampleTime_7Cycles5) || \ + ((TIME) == ADC_SampleTime_13Cycles5) || \ + ((TIME) == ADC_SampleTime_28Cycles5) || \ + ((TIME) == ADC_SampleTime_41Cycles5) || \ + ((TIME) == ADC_SampleTime_55Cycles5) || \ + ((TIME) == ADC_SampleTime_71Cycles5) || \ + ((TIME) == ADC_SampleTime_239Cycles5)) +/** + * @} + */ + +/** @defgroup ADC_external_trigger_sources_for_injected_channels_conversion + * @{ + */ + +#define ADC_ExternalTrigInjecConv_T2_TRGO ((uint32_t)0x00002000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigInjecConv_T2_CC1 ((uint32_t)0x00003000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigInjecConv_T3_CC4 ((uint32_t)0x00004000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigInjecConv_T4_TRGO ((uint32_t)0x00005000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4 ((uint32_t)0x00006000) /*!< For ADC1 and ADC2 */ + +#define ADC_ExternalTrigInjecConv_T1_TRGO ((uint32_t)0x00000000) /*!< For ADC1, ADC2 and ADC3 */ +#define ADC_ExternalTrigInjecConv_T1_CC4 ((uint32_t)0x00001000) /*!< For ADC1, ADC2 and ADC3 */ +#define ADC_ExternalTrigInjecConv_None ((uint32_t)0x00007000) /*!< For ADC1, ADC2 and ADC3 */ + +#define ADC_ExternalTrigInjecConv_T4_CC3 ((uint32_t)0x00002000) /*!< For ADC3 only */ +#define ADC_ExternalTrigInjecConv_T8_CC2 ((uint32_t)0x00003000) /*!< For ADC3 only */ +#define ADC_ExternalTrigInjecConv_T8_CC4 ((uint32_t)0x00004000) /*!< For ADC3 only */ +#define ADC_ExternalTrigInjecConv_T5_TRGO ((uint32_t)0x00005000) /*!< For ADC3 only */ +#define ADC_ExternalTrigInjecConv_T5_CC4 ((uint32_t)0x00006000) /*!< For ADC3 only */ + +#define IS_ADC_EXT_INJEC_TRIG(INJTRIG) (((INJTRIG) == ADC_ExternalTrigInjecConv_T1_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T1_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_CC1) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T3_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_None) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_CC3) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC2) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_CC4)) +/** + * @} + */ + +/** @defgroup ADC_injected_channel_selection + * @{ + */ + +#define ADC_InjectedChannel_1 ((uint8_t)0x14) +#define ADC_InjectedChannel_2 ((uint8_t)0x18) +#define ADC_InjectedChannel_3 ((uint8_t)0x1C) +#define ADC_InjectedChannel_4 ((uint8_t)0x20) +#define IS_ADC_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) == ADC_InjectedChannel_1) || \ + ((CHANNEL) == ADC_InjectedChannel_2) || \ + ((CHANNEL) == ADC_InjectedChannel_3) || \ + ((CHANNEL) == ADC_InjectedChannel_4)) +/** + * @} + */ + +/** @defgroup ADC_analog_watchdog_selection + * @{ + */ + +#define ADC_AnalogWatchdog_SingleRegEnable ((uint32_t)0x00800200) +#define ADC_AnalogWatchdog_SingleInjecEnable ((uint32_t)0x00400200) +#define ADC_AnalogWatchdog_SingleRegOrInjecEnable ((uint32_t)0x00C00200) +#define ADC_AnalogWatchdog_AllRegEnable ((uint32_t)0x00800000) +#define ADC_AnalogWatchdog_AllInjecEnable ((uint32_t)0x00400000) +#define ADC_AnalogWatchdog_AllRegAllInjecEnable ((uint32_t)0x00C00000) +#define ADC_AnalogWatchdog_None ((uint32_t)0x00000000) + +#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_AnalogWatchdog_SingleRegEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_SingleInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_SingleRegOrInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_AllRegEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_AllInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_AllRegAllInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_None)) +/** + * @} + */ + +/** @defgroup ADC_interrupts_definition + * @{ + */ + +#define ADC_IT_EOC ((uint16_t)0x0220) +#define ADC_IT_AWD ((uint16_t)0x0140) +#define ADC_IT_JEOC ((uint16_t)0x0480) + +#define IS_ADC_IT(IT) ((((IT) & (uint16_t)0xF81F) == 0x00) && ((IT) != 0x00)) + +#define IS_ADC_GET_IT(IT) (((IT) == ADC_IT_EOC) || ((IT) == ADC_IT_AWD) || \ + ((IT) == ADC_IT_JEOC)) +/** + * @} + */ + +/** @defgroup ADC_flags_definition + * @{ + */ + +#define ADC_FLAG_AWD ((uint8_t)0x01) +#define ADC_FLAG_EOC ((uint8_t)0x02) +#define ADC_FLAG_JEOC ((uint8_t)0x04) +#define ADC_FLAG_JSTRT ((uint8_t)0x08) +#define ADC_FLAG_STRT ((uint8_t)0x10) +#define IS_ADC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint8_t)0xE0) == 0x00) && ((FLAG) != 0x00)) +#define IS_ADC_GET_FLAG(FLAG) (((FLAG) == ADC_FLAG_AWD) || ((FLAG) == ADC_FLAG_EOC) || \ + ((FLAG) == ADC_FLAG_JEOC) || ((FLAG)== ADC_FLAG_JSTRT) || \ + ((FLAG) == ADC_FLAG_STRT)) +/** + * @} + */ + +/** @defgroup ADC_thresholds + * @{ + */ + +#define IS_ADC_THRESHOLD(THRESHOLD) ((THRESHOLD) <= 0xFFF) + +/** + * @} + */ + +/** @defgroup ADC_injected_offset + * @{ + */ + +#define IS_ADC_OFFSET(OFFSET) ((OFFSET) <= 0xFFF) + +/** + * @} + */ + +/** @defgroup ADC_injected_length + * @{ + */ + +#define IS_ADC_INJECTED_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x4)) + +/** + * @} + */ + +/** @defgroup ADC_injected_rank + * @{ + */ + +#define IS_ADC_INJECTED_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x4)) + +/** + * @} + */ + + +/** @defgroup ADC_regular_length + * @{ + */ + +#define IS_ADC_REGULAR_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x10)) +/** + * @} + */ + +/** @defgroup ADC_regular_rank + * @{ + */ + +#define IS_ADC_REGULAR_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x10)) + +/** + * @} + */ + +/** @defgroup ADC_regular_discontinuous_mode_number + * @{ + */ + +#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER) (((NUMBER) >= 0x1) && ((NUMBER) <= 0x8)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup ADC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup ADC_Exported_Functions + * @{ + */ + +void ADC_DeInit(ADC_TypeDef* ADCx); +void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct); +void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct); +void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState); +void ADC_ResetCalibration(ADC_TypeDef* ADCx); +FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx); +void ADC_StartCalibration(ADC_TypeDef* ADCx); +FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx); +void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx); +void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number); +void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime); +void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx); +uint32_t ADC_GetDualModeConversionValue(void); +void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv); +void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx); +void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime); +void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length); +void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset); +uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel); +void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog); +void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold, uint16_t LowThreshold); +void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel); +void ADC_TempSensorVrefintCmd(FunctionalState NewState); +FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG); +void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG); +ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT); +void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_ADC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h new file mode 100644 index 0000000..275c5e1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h @@ -0,0 +1,195 @@ +/** + ****************************************************************************** + * @file stm32f10x_bkp.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the BKP firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_BKP_H +#define __STM32F10x_BKP_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup BKP + * @{ + */ + +/** @defgroup BKP_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Exported_Constants + * @{ + */ + +/** @defgroup Tamper_Pin_active_level + * @{ + */ + +#define BKP_TamperPinLevel_High ((uint16_t)0x0000) +#define BKP_TamperPinLevel_Low ((uint16_t)0x0001) +#define IS_BKP_TAMPER_PIN_LEVEL(LEVEL) (((LEVEL) == BKP_TamperPinLevel_High) || \ + ((LEVEL) == BKP_TamperPinLevel_Low)) +/** + * @} + */ + +/** @defgroup RTC_output_source_to_output_on_the_Tamper_pin + * @{ + */ + +#define BKP_RTCOutputSource_None ((uint16_t)0x0000) +#define BKP_RTCOutputSource_CalibClock ((uint16_t)0x0080) +#define BKP_RTCOutputSource_Alarm ((uint16_t)0x0100) +#define BKP_RTCOutputSource_Second ((uint16_t)0x0300) +#define IS_BKP_RTC_OUTPUT_SOURCE(SOURCE) (((SOURCE) == BKP_RTCOutputSource_None) || \ + ((SOURCE) == BKP_RTCOutputSource_CalibClock) || \ + ((SOURCE) == BKP_RTCOutputSource_Alarm) || \ + ((SOURCE) == BKP_RTCOutputSource_Second)) +/** + * @} + */ + +/** @defgroup Data_Backup_Register + * @{ + */ + +#define BKP_DR1 ((uint16_t)0x0004) +#define BKP_DR2 ((uint16_t)0x0008) +#define BKP_DR3 ((uint16_t)0x000C) +#define BKP_DR4 ((uint16_t)0x0010) +#define BKP_DR5 ((uint16_t)0x0014) +#define BKP_DR6 ((uint16_t)0x0018) +#define BKP_DR7 ((uint16_t)0x001C) +#define BKP_DR8 ((uint16_t)0x0020) +#define BKP_DR9 ((uint16_t)0x0024) +#define BKP_DR10 ((uint16_t)0x0028) +#define BKP_DR11 ((uint16_t)0x0040) +#define BKP_DR12 ((uint16_t)0x0044) +#define BKP_DR13 ((uint16_t)0x0048) +#define BKP_DR14 ((uint16_t)0x004C) +#define BKP_DR15 ((uint16_t)0x0050) +#define BKP_DR16 ((uint16_t)0x0054) +#define BKP_DR17 ((uint16_t)0x0058) +#define BKP_DR18 ((uint16_t)0x005C) +#define BKP_DR19 ((uint16_t)0x0060) +#define BKP_DR20 ((uint16_t)0x0064) +#define BKP_DR21 ((uint16_t)0x0068) +#define BKP_DR22 ((uint16_t)0x006C) +#define BKP_DR23 ((uint16_t)0x0070) +#define BKP_DR24 ((uint16_t)0x0074) +#define BKP_DR25 ((uint16_t)0x0078) +#define BKP_DR26 ((uint16_t)0x007C) +#define BKP_DR27 ((uint16_t)0x0080) +#define BKP_DR28 ((uint16_t)0x0084) +#define BKP_DR29 ((uint16_t)0x0088) +#define BKP_DR30 ((uint16_t)0x008C) +#define BKP_DR31 ((uint16_t)0x0090) +#define BKP_DR32 ((uint16_t)0x0094) +#define BKP_DR33 ((uint16_t)0x0098) +#define BKP_DR34 ((uint16_t)0x009C) +#define BKP_DR35 ((uint16_t)0x00A0) +#define BKP_DR36 ((uint16_t)0x00A4) +#define BKP_DR37 ((uint16_t)0x00A8) +#define BKP_DR38 ((uint16_t)0x00AC) +#define BKP_DR39 ((uint16_t)0x00B0) +#define BKP_DR40 ((uint16_t)0x00B4) +#define BKP_DR41 ((uint16_t)0x00B8) +#define BKP_DR42 ((uint16_t)0x00BC) + +#define IS_BKP_DR(DR) (((DR) == BKP_DR1) || ((DR) == BKP_DR2) || ((DR) == BKP_DR3) || \ + ((DR) == BKP_DR4) || ((DR) == BKP_DR5) || ((DR) == BKP_DR6) || \ + ((DR) == BKP_DR7) || ((DR) == BKP_DR8) || ((DR) == BKP_DR9) || \ + ((DR) == BKP_DR10) || ((DR) == BKP_DR11) || ((DR) == BKP_DR12) || \ + ((DR) == BKP_DR13) || ((DR) == BKP_DR14) || ((DR) == BKP_DR15) || \ + ((DR) == BKP_DR16) || ((DR) == BKP_DR17) || ((DR) == BKP_DR18) || \ + ((DR) == BKP_DR19) || ((DR) == BKP_DR20) || ((DR) == BKP_DR21) || \ + ((DR) == BKP_DR22) || ((DR) == BKP_DR23) || ((DR) == BKP_DR24) || \ + ((DR) == BKP_DR25) || ((DR) == BKP_DR26) || ((DR) == BKP_DR27) || \ + ((DR) == BKP_DR28) || ((DR) == BKP_DR29) || ((DR) == BKP_DR30) || \ + ((DR) == BKP_DR31) || ((DR) == BKP_DR32) || ((DR) == BKP_DR33) || \ + ((DR) == BKP_DR34) || ((DR) == BKP_DR35) || ((DR) == BKP_DR36) || \ + ((DR) == BKP_DR37) || ((DR) == BKP_DR38) || ((DR) == BKP_DR39) || \ + ((DR) == BKP_DR40) || ((DR) == BKP_DR41) || ((DR) == BKP_DR42)) + +#define IS_BKP_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x7F) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup BKP_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Exported_Functions + * @{ + */ + +void BKP_DeInit(void); +void BKP_TamperPinLevelConfig(uint16_t BKP_TamperPinLevel); +void BKP_TamperPinCmd(FunctionalState NewState); +void BKP_ITConfig(FunctionalState NewState); +void BKP_RTCOutputConfig(uint16_t BKP_RTCOutputSource); +void BKP_SetRTCCalibrationValue(uint8_t CalibrationValue); +void BKP_WriteBackupRegister(uint16_t BKP_DR, uint16_t Data); +uint16_t BKP_ReadBackupRegister(uint16_t BKP_DR); +FlagStatus BKP_GetFlagStatus(void); +void BKP_ClearFlag(void); +ITStatus BKP_GetITStatus(void); +void BKP_ClearITPendingBit(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_BKP_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h new file mode 100644 index 0000000..d185aa2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h @@ -0,0 +1,697 @@ +/** + ****************************************************************************** + * @file stm32f10x_can.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the CAN firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_CAN_H +#define __STM32F10x_CAN_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup CAN + * @{ + */ + +/** @defgroup CAN_Exported_Types + * @{ + */ + +#define IS_CAN_ALL_PERIPH(PERIPH) (((PERIPH) == CAN1) || \ + ((PERIPH) == CAN2)) + +/** + * @brief CAN init structure definition + */ + +typedef struct +{ + uint16_t CAN_Prescaler; /*!< Specifies the length of a time quantum. + It ranges from 1 to 1024. */ + + uint8_t CAN_Mode; /*!< Specifies the CAN operating mode. + This parameter can be a value of + @ref CAN_operating_mode */ + + uint8_t CAN_SJW; /*!< Specifies the maximum number of time quanta + the CAN hardware is allowed to lengthen or + shorten a bit to perform resynchronization. + This parameter can be a value of + @ref CAN_synchronisation_jump_width */ + + uint8_t CAN_BS1; /*!< Specifies the number of time quanta in Bit + Segment 1. This parameter can be a value of + @ref CAN_time_quantum_in_bit_segment_1 */ + + uint8_t CAN_BS2; /*!< Specifies the number of time quanta in Bit + Segment 2. + This parameter can be a value of + @ref CAN_time_quantum_in_bit_segment_2 */ + + FunctionalState CAN_TTCM; /*!< Enable or disable the time triggered + communication mode. This parameter can be set + either to ENABLE or DISABLE. */ + + FunctionalState CAN_ABOM; /*!< Enable or disable the automatic bus-off + management. This parameter can be set either + to ENABLE or DISABLE. */ + + FunctionalState CAN_AWUM; /*!< Enable or disable the automatic wake-up mode. + This parameter can be set either to ENABLE or + DISABLE. */ + + FunctionalState CAN_NART; /*!< Enable or disable the no-automatic + retransmission mode. This parameter can be + set either to ENABLE or DISABLE. */ + + FunctionalState CAN_RFLM; /*!< Enable or disable the Receive FIFO Locked mode. + This parameter can be set either to ENABLE + or DISABLE. */ + + FunctionalState CAN_TXFP; /*!< Enable or disable the transmit FIFO priority. + This parameter can be set either to ENABLE + or DISABLE. */ +} CAN_InitTypeDef; + +/** + * @brief CAN filter init structure definition + */ + +typedef struct +{ + uint16_t CAN_FilterIdHigh; /*!< Specifies the filter identification number (MSBs for a 32-bit + configuration, first one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterIdLow; /*!< Specifies the filter identification number (LSBs for a 32-bit + configuration, second one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterMaskIdHigh; /*!< Specifies the filter mask number or identification number, + according to the mode (MSBs for a 32-bit configuration, + first one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterMaskIdLow; /*!< Specifies the filter mask number or identification number, + according to the mode (LSBs for a 32-bit configuration, + second one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterFIFOAssignment; /*!< Specifies the FIFO (0 or 1) which will be assigned to the filter. + This parameter can be a value of @ref CAN_filter_FIFO */ + + uint8_t CAN_FilterNumber; /*!< Specifies the filter which will be initialized. It ranges from 0 to 13. */ + + uint8_t CAN_FilterMode; /*!< Specifies the filter mode to be initialized. + This parameter can be a value of @ref CAN_filter_mode */ + + uint8_t CAN_FilterScale; /*!< Specifies the filter scale. + This parameter can be a value of @ref CAN_filter_scale */ + + FunctionalState CAN_FilterActivation; /*!< Enable or disable the filter. + This parameter can be set either to ENABLE or DISABLE. */ +} CAN_FilterInitTypeDef; + +/** + * @brief CAN Tx message structure definition + */ + +typedef struct +{ + uint32_t StdId; /*!< Specifies the standard identifier. + This parameter can be a value between 0 to 0x7FF. */ + + uint32_t ExtId; /*!< Specifies the extended identifier. + This parameter can be a value between 0 to 0x1FFFFFFF. */ + + uint8_t IDE; /*!< Specifies the type of identifier for the message that + will be transmitted. This parameter can be a value + of @ref CAN_identifier_type */ + + uint8_t RTR; /*!< Specifies the type of frame for the message that will + be transmitted. This parameter can be a value of + @ref CAN_remote_transmission_request */ + + uint8_t DLC; /*!< Specifies the length of the frame that will be + transmitted. This parameter can be a value between + 0 to 8 */ + + uint8_t Data[8]; /*!< Contains the data to be transmitted. It ranges from 0 + to 0xFF. */ +} CanTxMsg; + +/** + * @brief CAN Rx message structure definition + */ + +typedef struct +{ + uint32_t StdId; /*!< Specifies the standard identifier. + This parameter can be a value between 0 to 0x7FF. */ + + uint32_t ExtId; /*!< Specifies the extended identifier. + This parameter can be a value between 0 to 0x1FFFFFFF. */ + + uint8_t IDE; /*!< Specifies the type of identifier for the message that + will be received. This parameter can be a value of + @ref CAN_identifier_type */ + + uint8_t RTR; /*!< Specifies the type of frame for the received message. + This parameter can be a value of + @ref CAN_remote_transmission_request */ + + uint8_t DLC; /*!< Specifies the length of the frame that will be received. + This parameter can be a value between 0 to 8 */ + + uint8_t Data[8]; /*!< Contains the data to be received. It ranges from 0 to + 0xFF. */ + + uint8_t FMI; /*!< Specifies the index of the filter the message stored in + the mailbox passes through. This parameter can be a + value between 0 to 0xFF */ +} CanRxMsg; + +/** + * @} + */ + +/** @defgroup CAN_Exported_Constants + * @{ + */ + +/** @defgroup CAN_sleep_constants + * @{ + */ + +#define CAN_InitStatus_Failed ((uint8_t)0x00) /*!< CAN initialization failed */ +#define CAN_InitStatus_Success ((uint8_t)0x01) /*!< CAN initialization OK */ + +/** + * @} + */ + +/** @defgroup CAN_Mode + * @{ + */ + +#define CAN_Mode_Normal ((uint8_t)0x00) /*!< normal mode */ +#define CAN_Mode_LoopBack ((uint8_t)0x01) /*!< loopback mode */ +#define CAN_Mode_Silent ((uint8_t)0x02) /*!< silent mode */ +#define CAN_Mode_Silent_LoopBack ((uint8_t)0x03) /*!< loopback combined with silent mode */ + +#define IS_CAN_MODE(MODE) (((MODE) == CAN_Mode_Normal) || \ + ((MODE) == CAN_Mode_LoopBack)|| \ + ((MODE) == CAN_Mode_Silent) || \ + ((MODE) == CAN_Mode_Silent_LoopBack)) +/** + * @} + */ + + +/** + * @defgroup CAN_Operating_Mode + * @{ + */ +#define CAN_OperatingMode_Initialization ((uint8_t)0x00) /*!< Initialization mode */ +#define CAN_OperatingMode_Normal ((uint8_t)0x01) /*!< Normal mode */ +#define CAN_OperatingMode_Sleep ((uint8_t)0x02) /*!< sleep mode */ + + +#define IS_CAN_OPERATING_MODE(MODE) (((MODE) == CAN_OperatingMode_Initialization) ||\ + ((MODE) == CAN_OperatingMode_Normal)|| \ + ((MODE) == CAN_OperatingMode_Sleep)) +/** + * @} + */ + +/** + * @defgroup CAN_Mode_Status + * @{ + */ + +#define CAN_ModeStatus_Failed ((uint8_t)0x00) /*!< CAN entering the specific mode failed */ +#define CAN_ModeStatus_Success ((uint8_t)!CAN_ModeStatus_Failed) /*!< CAN entering the specific mode Succeed */ + + +/** + * @} + */ + +/** @defgroup CAN_synchronisation_jump_width + * @{ + */ + +#define CAN_SJW_1tq ((uint8_t)0x00) /*!< 1 time quantum */ +#define CAN_SJW_2tq ((uint8_t)0x01) /*!< 2 time quantum */ +#define CAN_SJW_3tq ((uint8_t)0x02) /*!< 3 time quantum */ +#define CAN_SJW_4tq ((uint8_t)0x03) /*!< 4 time quantum */ + +#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1tq) || ((SJW) == CAN_SJW_2tq)|| \ + ((SJW) == CAN_SJW_3tq) || ((SJW) == CAN_SJW_4tq)) +/** + * @} + */ + +/** @defgroup CAN_time_quantum_in_bit_segment_1 + * @{ + */ + +#define CAN_BS1_1tq ((uint8_t)0x00) /*!< 1 time quantum */ +#define CAN_BS1_2tq ((uint8_t)0x01) /*!< 2 time quantum */ +#define CAN_BS1_3tq ((uint8_t)0x02) /*!< 3 time quantum */ +#define CAN_BS1_4tq ((uint8_t)0x03) /*!< 4 time quantum */ +#define CAN_BS1_5tq ((uint8_t)0x04) /*!< 5 time quantum */ +#define CAN_BS1_6tq ((uint8_t)0x05) /*!< 6 time quantum */ +#define CAN_BS1_7tq ((uint8_t)0x06) /*!< 7 time quantum */ +#define CAN_BS1_8tq ((uint8_t)0x07) /*!< 8 time quantum */ +#define CAN_BS1_9tq ((uint8_t)0x08) /*!< 9 time quantum */ +#define CAN_BS1_10tq ((uint8_t)0x09) /*!< 10 time quantum */ +#define CAN_BS1_11tq ((uint8_t)0x0A) /*!< 11 time quantum */ +#define CAN_BS1_12tq ((uint8_t)0x0B) /*!< 12 time quantum */ +#define CAN_BS1_13tq ((uint8_t)0x0C) /*!< 13 time quantum */ +#define CAN_BS1_14tq ((uint8_t)0x0D) /*!< 14 time quantum */ +#define CAN_BS1_15tq ((uint8_t)0x0E) /*!< 15 time quantum */ +#define CAN_BS1_16tq ((uint8_t)0x0F) /*!< 16 time quantum */ + +#define IS_CAN_BS1(BS1) ((BS1) <= CAN_BS1_16tq) +/** + * @} + */ + +/** @defgroup CAN_time_quantum_in_bit_segment_2 + * @{ + */ + +#define CAN_BS2_1tq ((uint8_t)0x00) /*!< 1 time quantum */ +#define CAN_BS2_2tq ((uint8_t)0x01) /*!< 2 time quantum */ +#define CAN_BS2_3tq ((uint8_t)0x02) /*!< 3 time quantum */ +#define CAN_BS2_4tq ((uint8_t)0x03) /*!< 4 time quantum */ +#define CAN_BS2_5tq ((uint8_t)0x04) /*!< 5 time quantum */ +#define CAN_BS2_6tq ((uint8_t)0x05) /*!< 6 time quantum */ +#define CAN_BS2_7tq ((uint8_t)0x06) /*!< 7 time quantum */ +#define CAN_BS2_8tq ((uint8_t)0x07) /*!< 8 time quantum */ + +#define IS_CAN_BS2(BS2) ((BS2) <= CAN_BS2_8tq) + +/** + * @} + */ + +/** @defgroup CAN_clock_prescaler + * @{ + */ + +#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1) && ((PRESCALER) <= 1024)) + +/** + * @} + */ + +/** @defgroup CAN_filter_number + * @{ + */ +#ifndef STM32F10X_CL + #define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 13) +#else + #define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 27) +#endif /* STM32F10X_CL */ +/** + * @} + */ + +/** @defgroup CAN_filter_mode + * @{ + */ + +#define CAN_FilterMode_IdMask ((uint8_t)0x00) /*!< identifier/mask mode */ +#define CAN_FilterMode_IdList ((uint8_t)0x01) /*!< identifier list mode */ + +#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FilterMode_IdMask) || \ + ((MODE) == CAN_FilterMode_IdList)) +/** + * @} + */ + +/** @defgroup CAN_filter_scale + * @{ + */ + +#define CAN_FilterScale_16bit ((uint8_t)0x00) /*!< Two 16-bit filters */ +#define CAN_FilterScale_32bit ((uint8_t)0x01) /*!< One 32-bit filter */ + +#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FilterScale_16bit) || \ + ((SCALE) == CAN_FilterScale_32bit)) + +/** + * @} + */ + +/** @defgroup CAN_filter_FIFO + * @{ + */ + +#define CAN_Filter_FIFO0 ((uint8_t)0x00) /*!< Filter FIFO 0 assignment for filter x */ +#define CAN_Filter_FIFO1 ((uint8_t)0x01) /*!< Filter FIFO 1 assignment for filter x */ +#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FilterFIFO0) || \ + ((FIFO) == CAN_FilterFIFO1)) +/** + * @} + */ + +/** @defgroup Start_bank_filter_for_slave_CAN + * @{ + */ +#define IS_CAN_BANKNUMBER(BANKNUMBER) (((BANKNUMBER) >= 1) && ((BANKNUMBER) <= 27)) +/** + * @} + */ + +/** @defgroup CAN_Tx + * @{ + */ + +#define IS_CAN_TRANSMITMAILBOX(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= ((uint8_t)0x02)) +#define IS_CAN_STDID(STDID) ((STDID) <= ((uint32_t)0x7FF)) +#define IS_CAN_EXTID(EXTID) ((EXTID) <= ((uint32_t)0x1FFFFFFF)) +#define IS_CAN_DLC(DLC) ((DLC) <= ((uint8_t)0x08)) + +/** + * @} + */ + +/** @defgroup CAN_identifier_type + * @{ + */ + +#define CAN_Id_Standard ((uint32_t)0x00000000) /*!< Standard Id */ +#define CAN_Id_Extended ((uint32_t)0x00000004) /*!< Extended Id */ +#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_Id_Standard) || \ + ((IDTYPE) == CAN_Id_Extended)) +/** + * @} + */ + +/** @defgroup CAN_remote_transmission_request + * @{ + */ + +#define CAN_RTR_Data ((uint32_t)0x00000000) /*!< Data frame */ +#define CAN_RTR_Remote ((uint32_t)0x00000002) /*!< Remote frame */ +#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_Data) || ((RTR) == CAN_RTR_Remote)) + +/** + * @} + */ + +/** @defgroup CAN_transmit_constants + * @{ + */ + +#define CAN_TxStatus_Failed ((uint8_t)0x00)/*!< CAN transmission failed */ +#define CAN_TxStatus_Ok ((uint8_t)0x01) /*!< CAN transmission succeeded */ +#define CAN_TxStatus_Pending ((uint8_t)0x02) /*!< CAN transmission pending */ +#define CAN_TxStatus_NoMailBox ((uint8_t)0x04) /*!< CAN cell did not provide an empty mailbox */ + +/** + * @} + */ + +/** @defgroup CAN_receive_FIFO_number_constants + * @{ + */ + +#define CAN_FIFO0 ((uint8_t)0x00) /*!< CAN FIFO 0 used to receive */ +#define CAN_FIFO1 ((uint8_t)0x01) /*!< CAN FIFO 1 used to receive */ + +#define IS_CAN_FIFO(FIFO) (((FIFO) == CAN_FIFO0) || ((FIFO) == CAN_FIFO1)) + +/** + * @} + */ + +/** @defgroup CAN_sleep_constants + * @{ + */ + +#define CAN_Sleep_Failed ((uint8_t)0x00) /*!< CAN did not enter the sleep mode */ +#define CAN_Sleep_Ok ((uint8_t)0x01) /*!< CAN entered the sleep mode */ + +/** + * @} + */ + +/** @defgroup CAN_wake_up_constants + * @{ + */ + +#define CAN_WakeUp_Failed ((uint8_t)0x00) /*!< CAN did not leave the sleep mode */ +#define CAN_WakeUp_Ok ((uint8_t)0x01) /*!< CAN leaved the sleep mode */ + +/** + * @} + */ + +/** + * @defgroup CAN_Error_Code_constants + * @{ + */ + +#define CAN_ErrorCode_NoErr ((uint8_t)0x00) /*!< No Error */ +#define CAN_ErrorCode_StuffErr ((uint8_t)0x10) /*!< Stuff Error */ +#define CAN_ErrorCode_FormErr ((uint8_t)0x20) /*!< Form Error */ +#define CAN_ErrorCode_ACKErr ((uint8_t)0x30) /*!< Acknowledgment Error */ +#define CAN_ErrorCode_BitRecessiveErr ((uint8_t)0x40) /*!< Bit Recessive Error */ +#define CAN_ErrorCode_BitDominantErr ((uint8_t)0x50) /*!< Bit Dominant Error */ +#define CAN_ErrorCode_CRCErr ((uint8_t)0x60) /*!< CRC Error */ +#define CAN_ErrorCode_SoftwareSetErr ((uint8_t)0x70) /*!< Software Set Error */ + + +/** + * @} + */ + +/** @defgroup CAN_flags + * @{ + */ +/* If the flag is 0x3XXXXXXX, it means that it can be used with CAN_GetFlagStatus() + and CAN_ClearFlag() functions. */ +/* If the flag is 0x1XXXXXXX, it means that it can only be used with CAN_GetFlagStatus() function. */ + +/* Transmit Flags */ +#define CAN_FLAG_RQCP0 ((uint32_t)0x38000001) /*!< Request MailBox0 Flag */ +#define CAN_FLAG_RQCP1 ((uint32_t)0x38000100) /*!< Request MailBox1 Flag */ +#define CAN_FLAG_RQCP2 ((uint32_t)0x38010000) /*!< Request MailBox2 Flag */ + +/* Receive Flags */ +#define CAN_FLAG_FMP0 ((uint32_t)0x12000003) /*!< FIFO 0 Message Pending Flag */ +#define CAN_FLAG_FF0 ((uint32_t)0x32000008) /*!< FIFO 0 Full Flag */ +#define CAN_FLAG_FOV0 ((uint32_t)0x32000010) /*!< FIFO 0 Overrun Flag */ +#define CAN_FLAG_FMP1 ((uint32_t)0x14000003) /*!< FIFO 1 Message Pending Flag */ +#define CAN_FLAG_FF1 ((uint32_t)0x34000008) /*!< FIFO 1 Full Flag */ +#define CAN_FLAG_FOV1 ((uint32_t)0x34000010) /*!< FIFO 1 Overrun Flag */ + +/* Operating Mode Flags */ +#define CAN_FLAG_WKU ((uint32_t)0x31000008) /*!< Wake up Flag */ +#define CAN_FLAG_SLAK ((uint32_t)0x31000012) /*!< Sleep acknowledge Flag */ +/* Note: When SLAK intterupt is disabled (SLKIE=0), no polling on SLAKI is possible. + In this case the SLAK bit can be polled.*/ + +/* Error Flags */ +#define CAN_FLAG_EWG ((uint32_t)0x10F00001) /*!< Error Warning Flag */ +#define CAN_FLAG_EPV ((uint32_t)0x10F00002) /*!< Error Passive Flag */ +#define CAN_FLAG_BOF ((uint32_t)0x10F00004) /*!< Bus-Off Flag */ +#define CAN_FLAG_LEC ((uint32_t)0x30F00070) /*!< Last error code Flag */ + +#define IS_CAN_GET_FLAG(FLAG) (((FLAG) == CAN_FLAG_LEC) || ((FLAG) == CAN_FLAG_BOF) || \ + ((FLAG) == CAN_FLAG_EPV) || ((FLAG) == CAN_FLAG_EWG) || \ + ((FLAG) == CAN_FLAG_WKU) || ((FLAG) == CAN_FLAG_FOV0) || \ + ((FLAG) == CAN_FLAG_FF0) || ((FLAG) == CAN_FLAG_FMP0) || \ + ((FLAG) == CAN_FLAG_FOV1) || ((FLAG) == CAN_FLAG_FF1) || \ + ((FLAG) == CAN_FLAG_FMP1) || ((FLAG) == CAN_FLAG_RQCP2) || \ + ((FLAG) == CAN_FLAG_RQCP1)|| ((FLAG) == CAN_FLAG_RQCP0) || \ + ((FLAG) == CAN_FLAG_SLAK )) + +#define IS_CAN_CLEAR_FLAG(FLAG)(((FLAG) == CAN_FLAG_LEC) || ((FLAG) == CAN_FLAG_RQCP2) || \ + ((FLAG) == CAN_FLAG_RQCP1) || ((FLAG) == CAN_FLAG_RQCP0) || \ + ((FLAG) == CAN_FLAG_FF0) || ((FLAG) == CAN_FLAG_FOV0) ||\ + ((FLAG) == CAN_FLAG_FF1) || ((FLAG) == CAN_FLAG_FOV1) || \ + ((FLAG) == CAN_FLAG_WKU) || ((FLAG) == CAN_FLAG_SLAK)) +/** + * @} + */ + + +/** @defgroup CAN_interrupts + * @{ + */ + + + +#define CAN_IT_TME ((uint32_t)0x00000001) /*!< Transmit mailbox empty Interrupt*/ + +/* Receive Interrupts */ +#define CAN_IT_FMP0 ((uint32_t)0x00000002) /*!< FIFO 0 message pending Interrupt*/ +#define CAN_IT_FF0 ((uint32_t)0x00000004) /*!< FIFO 0 full Interrupt*/ +#define CAN_IT_FOV0 ((uint32_t)0x00000008) /*!< FIFO 0 overrun Interrupt*/ +#define CAN_IT_FMP1 ((uint32_t)0x00000010) /*!< FIFO 1 message pending Interrupt*/ +#define CAN_IT_FF1 ((uint32_t)0x00000020) /*!< FIFO 1 full Interrupt*/ +#define CAN_IT_FOV1 ((uint32_t)0x00000040) /*!< FIFO 1 overrun Interrupt*/ + +/* Operating Mode Interrupts */ +#define CAN_IT_WKU ((uint32_t)0x00010000) /*!< Wake-up Interrupt*/ +#define CAN_IT_SLK ((uint32_t)0x00020000) /*!< Sleep acknowledge Interrupt*/ + +/* Error Interrupts */ +#define CAN_IT_EWG ((uint32_t)0x00000100) /*!< Error warning Interrupt*/ +#define CAN_IT_EPV ((uint32_t)0x00000200) /*!< Error passive Interrupt*/ +#define CAN_IT_BOF ((uint32_t)0x00000400) /*!< Bus-off Interrupt*/ +#define CAN_IT_LEC ((uint32_t)0x00000800) /*!< Last error code Interrupt*/ +#define CAN_IT_ERR ((uint32_t)0x00008000) /*!< Error Interrupt*/ + +/* Flags named as Interrupts : kept only for FW compatibility */ +#define CAN_IT_RQCP0 CAN_IT_TME +#define CAN_IT_RQCP1 CAN_IT_TME +#define CAN_IT_RQCP2 CAN_IT_TME + + +#define IS_CAN_IT(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FMP0) ||\ + ((IT) == CAN_IT_FF0) || ((IT) == CAN_IT_FOV0) ||\ + ((IT) == CAN_IT_FMP1) || ((IT) == CAN_IT_FF1) ||\ + ((IT) == CAN_IT_FOV1) || ((IT) == CAN_IT_EWG) ||\ + ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\ + ((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\ + ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK)) + +#define IS_CAN_CLEAR_IT(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FF0) ||\ + ((IT) == CAN_IT_FOV0)|| ((IT) == CAN_IT_FF1) ||\ + ((IT) == CAN_IT_FOV1)|| ((IT) == CAN_IT_EWG) ||\ + ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\ + ((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\ + ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK)) + +/** + * @} + */ + +/** @defgroup CAN_Legacy + * @{ + */ +#define CANINITFAILED CAN_InitStatus_Failed +#define CANINITOK CAN_InitStatus_Success +#define CAN_FilterFIFO0 CAN_Filter_FIFO0 +#define CAN_FilterFIFO1 CAN_Filter_FIFO1 +#define CAN_ID_STD CAN_Id_Standard +#define CAN_ID_EXT CAN_Id_Extended +#define CAN_RTR_DATA CAN_RTR_Data +#define CAN_RTR_REMOTE CAN_RTR_Remote +#define CANTXFAILE CAN_TxStatus_Failed +#define CANTXOK CAN_TxStatus_Ok +#define CANTXPENDING CAN_TxStatus_Pending +#define CAN_NO_MB CAN_TxStatus_NoMailBox +#define CANSLEEPFAILED CAN_Sleep_Failed +#define CANSLEEPOK CAN_Sleep_Ok +#define CANWAKEUPFAILED CAN_WakeUp_Failed +#define CANWAKEUPOK CAN_WakeUp_Ok + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup CAN_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup CAN_Exported_Functions + * @{ + */ +/* Function used to set the CAN configuration to the default reset state *****/ +void CAN_DeInit(CAN_TypeDef* CANx); + +/* Initialization and Configuration functions *********************************/ +uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct); +void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct); +void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct); +void CAN_SlaveStartBank(uint8_t CAN_BankNumber); +void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState); +void CAN_TTComModeCmd(CAN_TypeDef* CANx, FunctionalState NewState); + +/* Transmit functions *********************************************************/ +uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage); +uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox); +void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox); + +/* Receive functions **********************************************************/ +void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage); +void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber); +uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber); + + +/* Operation modes functions **************************************************/ +uint8_t CAN_OperatingModeRequest(CAN_TypeDef* CANx, uint8_t CAN_OperatingMode); +uint8_t CAN_Sleep(CAN_TypeDef* CANx); +uint8_t CAN_WakeUp(CAN_TypeDef* CANx); + +/* Error management functions *************************************************/ +uint8_t CAN_GetLastErrorCode(CAN_TypeDef* CANx); +uint8_t CAN_GetReceiveErrorCounter(CAN_TypeDef* CANx); +uint8_t CAN_GetLSBTransmitErrorCounter(CAN_TypeDef* CANx); + +/* Interrupts and flags management functions **********************************/ +void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState); +FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG); +void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG); +ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT); +void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_CAN_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_cec.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_cec.h new file mode 100644 index 0000000..7ce6896 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_cec.h @@ -0,0 +1,210 @@ +/** + ****************************************************************************** + * @file stm32f10x_cec.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the CEC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_CEC_H +#define __STM32F10x_CEC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup CEC + * @{ + */ + + +/** @defgroup CEC_Exported_Types + * @{ + */ + +/** + * @brief CEC Init structure definition + */ +typedef struct +{ + uint16_t CEC_BitTimingMode; /*!< Configures the CEC Bit Timing Error Mode. + This parameter can be a value of @ref CEC_BitTiming_Mode */ + uint16_t CEC_BitPeriodMode; /*!< Configures the CEC Bit Period Error Mode. + This parameter can be a value of @ref CEC_BitPeriod_Mode */ +}CEC_InitTypeDef; + +/** + * @} + */ + +/** @defgroup CEC_Exported_Constants + * @{ + */ + +/** @defgroup CEC_BitTiming_Mode + * @{ + */ +#define CEC_BitTimingStdMode ((uint16_t)0x00) /*!< Bit timing error Standard Mode */ +#define CEC_BitTimingErrFreeMode CEC_CFGR_BTEM /*!< Bit timing error Free Mode */ + +#define IS_CEC_BIT_TIMING_ERROR_MODE(MODE) (((MODE) == CEC_BitTimingStdMode) || \ + ((MODE) == CEC_BitTimingErrFreeMode)) +/** + * @} + */ + +/** @defgroup CEC_BitPeriod_Mode + * @{ + */ +#define CEC_BitPeriodStdMode ((uint16_t)0x00) /*!< Bit period error Standard Mode */ +#define CEC_BitPeriodFlexibleMode CEC_CFGR_BPEM /*!< Bit period error Flexible Mode */ + +#define IS_CEC_BIT_PERIOD_ERROR_MODE(MODE) (((MODE) == CEC_BitPeriodStdMode) || \ + ((MODE) == CEC_BitPeriodFlexibleMode)) +/** + * @} + */ + + +/** @defgroup CEC_interrupts_definition + * @{ + */ +#define CEC_IT_TERR CEC_CSR_TERR +#define CEC_IT_TBTRF CEC_CSR_TBTRF +#define CEC_IT_RERR CEC_CSR_RERR +#define CEC_IT_RBTF CEC_CSR_RBTF +#define IS_CEC_GET_IT(IT) (((IT) == CEC_IT_TERR) || ((IT) == CEC_IT_TBTRF) || \ + ((IT) == CEC_IT_RERR) || ((IT) == CEC_IT_RBTF)) +/** + * @} + */ + + +/** @defgroup CEC_Own_Address + * @{ + */ +#define IS_CEC_ADDRESS(ADDRESS) ((ADDRESS) < 0x10) +/** + * @} + */ + +/** @defgroup CEC_Prescaler + * @{ + */ +#define IS_CEC_PRESCALER(PRESCALER) ((PRESCALER) <= 0x3FFF) + +/** + * @} + */ + +/** @defgroup CEC_flags_definition + * @{ + */ + +/** + * @brief ESR register flags + */ +#define CEC_FLAG_BTE ((uint32_t)0x10010000) +#define CEC_FLAG_BPE ((uint32_t)0x10020000) +#define CEC_FLAG_RBTFE ((uint32_t)0x10040000) +#define CEC_FLAG_SBE ((uint32_t)0x10080000) +#define CEC_FLAG_ACKE ((uint32_t)0x10100000) +#define CEC_FLAG_LINE ((uint32_t)0x10200000) +#define CEC_FLAG_TBTFE ((uint32_t)0x10400000) + +/** + * @brief CSR register flags + */ +#define CEC_FLAG_TEOM ((uint32_t)0x00000002) +#define CEC_FLAG_TERR ((uint32_t)0x00000004) +#define CEC_FLAG_TBTRF ((uint32_t)0x00000008) +#define CEC_FLAG_RSOM ((uint32_t)0x00000010) +#define CEC_FLAG_REOM ((uint32_t)0x00000020) +#define CEC_FLAG_RERR ((uint32_t)0x00000040) +#define CEC_FLAG_RBTF ((uint32_t)0x00000080) + +#define IS_CEC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFF03) == 0x00) && ((FLAG) != 0x00)) + +#define IS_CEC_GET_FLAG(FLAG) (((FLAG) == CEC_FLAG_BTE) || ((FLAG) == CEC_FLAG_BPE) || \ + ((FLAG) == CEC_FLAG_RBTFE) || ((FLAG)== CEC_FLAG_SBE) || \ + ((FLAG) == CEC_FLAG_ACKE) || ((FLAG) == CEC_FLAG_LINE) || \ + ((FLAG) == CEC_FLAG_TBTFE) || ((FLAG) == CEC_FLAG_TEOM) || \ + ((FLAG) == CEC_FLAG_TERR) || ((FLAG) == CEC_FLAG_TBTRF) || \ + ((FLAG) == CEC_FLAG_RSOM) || ((FLAG) == CEC_FLAG_REOM) || \ + ((FLAG) == CEC_FLAG_RERR) || ((FLAG) == CEC_FLAG_RBTF)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup CEC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup CEC_Exported_Functions + * @{ + */ +void CEC_DeInit(void); +void CEC_Init(CEC_InitTypeDef* CEC_InitStruct); +void CEC_Cmd(FunctionalState NewState); +void CEC_ITConfig(FunctionalState NewState); +void CEC_OwnAddressConfig(uint8_t CEC_OwnAddress); +void CEC_SetPrescaler(uint16_t CEC_Prescaler); +void CEC_SendDataByte(uint8_t Data); +uint8_t CEC_ReceiveDataByte(void); +void CEC_StartOfMessage(void); +void CEC_EndOfMessageCmd(FunctionalState NewState); +FlagStatus CEC_GetFlagStatus(uint32_t CEC_FLAG); +void CEC_ClearFlag(uint32_t CEC_FLAG); +ITStatus CEC_GetITStatus(uint8_t CEC_IT); +void CEC_ClearITPendingBit(uint16_t CEC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_CEC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h new file mode 100644 index 0000000..3362fca --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h @@ -0,0 +1,94 @@ +/** + ****************************************************************************** + * @file stm32f10x_crc.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the CRC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_CRC_H +#define __STM32F10x_CRC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup CRC + * @{ + */ + +/** @defgroup CRC_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Exported_Constants + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Exported_Functions + * @{ + */ + +void CRC_ResetDR(void); +uint32_t CRC_CalcCRC(uint32_t Data); +uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength); +uint32_t CRC_GetCRC(void); +void CRC_SetIDRegister(uint8_t IDValue); +uint8_t CRC_GetIDRegister(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_CRC_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h new file mode 100644 index 0000000..174773c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h @@ -0,0 +1,317 @@ +/** + ****************************************************************************** + * @file stm32f10x_dac.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the DAC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_DAC_H +#define __STM32F10x_DAC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DAC + * @{ + */ + +/** @defgroup DAC_Exported_Types + * @{ + */ + +/** + * @brief DAC Init structure definition + */ + +typedef struct +{ + uint32_t DAC_Trigger; /*!< Specifies the external trigger for the selected DAC channel. + This parameter can be a value of @ref DAC_trigger_selection */ + + uint32_t DAC_WaveGeneration; /*!< Specifies whether DAC channel noise waves or triangle waves + are generated, or whether no wave is generated. + This parameter can be a value of @ref DAC_wave_generation */ + + uint32_t DAC_LFSRUnmask_TriangleAmplitude; /*!< Specifies the LFSR mask for noise wave generation or + the maximum amplitude triangle generation for the DAC channel. + This parameter can be a value of @ref DAC_lfsrunmask_triangleamplitude */ + + uint32_t DAC_OutputBuffer; /*!< Specifies whether the DAC channel output buffer is enabled or disabled. + This parameter can be a value of @ref DAC_output_buffer */ +}DAC_InitTypeDef; + +/** + * @} + */ + +/** @defgroup DAC_Exported_Constants + * @{ + */ + +/** @defgroup DAC_trigger_selection + * @{ + */ + +#define DAC_Trigger_None ((uint32_t)0x00000000) /*!< Conversion is automatic once the DAC1_DHRxxxx register + has been loaded, and not by external trigger */ +#define DAC_Trigger_T6_TRGO ((uint32_t)0x00000004) /*!< TIM6 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T8_TRGO ((uint32_t)0x0000000C) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel + only in High-density devices*/ +#define DAC_Trigger_T3_TRGO ((uint32_t)0x0000000C) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel + only in Connectivity line, Medium-density and Low-density Value Line devices */ +#define DAC_Trigger_T7_TRGO ((uint32_t)0x00000014) /*!< TIM7 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T5_TRGO ((uint32_t)0x0000001C) /*!< TIM5 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T15_TRGO ((uint32_t)0x0000001C) /*!< TIM15 TRGO selected as external conversion trigger for DAC channel + only in Medium-density and Low-density Value Line devices*/ +#define DAC_Trigger_T2_TRGO ((uint32_t)0x00000024) /*!< TIM2 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T4_TRGO ((uint32_t)0x0000002C) /*!< TIM4 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_Ext_IT9 ((uint32_t)0x00000034) /*!< EXTI Line9 event selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_Software ((uint32_t)0x0000003C) /*!< Conversion started by software trigger for DAC channel */ + +#define IS_DAC_TRIGGER(TRIGGER) (((TRIGGER) == DAC_Trigger_None) || \ + ((TRIGGER) == DAC_Trigger_T6_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T8_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T7_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T5_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T2_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T4_TRGO) || \ + ((TRIGGER) == DAC_Trigger_Ext_IT9) || \ + ((TRIGGER) == DAC_Trigger_Software)) + +/** + * @} + */ + +/** @defgroup DAC_wave_generation + * @{ + */ + +#define DAC_WaveGeneration_None ((uint32_t)0x00000000) +#define DAC_WaveGeneration_Noise ((uint32_t)0x00000040) +#define DAC_WaveGeneration_Triangle ((uint32_t)0x00000080) +#define IS_DAC_GENERATE_WAVE(WAVE) (((WAVE) == DAC_WaveGeneration_None) || \ + ((WAVE) == DAC_WaveGeneration_Noise) || \ + ((WAVE) == DAC_WaveGeneration_Triangle)) +/** + * @} + */ + +/** @defgroup DAC_lfsrunmask_triangleamplitude + * @{ + */ + +#define DAC_LFSRUnmask_Bit0 ((uint32_t)0x00000000) /*!< Unmask DAC channel LFSR bit0 for noise wave generation */ +#define DAC_LFSRUnmask_Bits1_0 ((uint32_t)0x00000100) /*!< Unmask DAC channel LFSR bit[1:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits2_0 ((uint32_t)0x00000200) /*!< Unmask DAC channel LFSR bit[2:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits3_0 ((uint32_t)0x00000300) /*!< Unmask DAC channel LFSR bit[3:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits4_0 ((uint32_t)0x00000400) /*!< Unmask DAC channel LFSR bit[4:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits5_0 ((uint32_t)0x00000500) /*!< Unmask DAC channel LFSR bit[5:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits6_0 ((uint32_t)0x00000600) /*!< Unmask DAC channel LFSR bit[6:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits7_0 ((uint32_t)0x00000700) /*!< Unmask DAC channel LFSR bit[7:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits8_0 ((uint32_t)0x00000800) /*!< Unmask DAC channel LFSR bit[8:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits9_0 ((uint32_t)0x00000900) /*!< Unmask DAC channel LFSR bit[9:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits10_0 ((uint32_t)0x00000A00) /*!< Unmask DAC channel LFSR bit[10:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits11_0 ((uint32_t)0x00000B00) /*!< Unmask DAC channel LFSR bit[11:0] for noise wave generation */ +#define DAC_TriangleAmplitude_1 ((uint32_t)0x00000000) /*!< Select max triangle amplitude of 1 */ +#define DAC_TriangleAmplitude_3 ((uint32_t)0x00000100) /*!< Select max triangle amplitude of 3 */ +#define DAC_TriangleAmplitude_7 ((uint32_t)0x00000200) /*!< Select max triangle amplitude of 7 */ +#define DAC_TriangleAmplitude_15 ((uint32_t)0x00000300) /*!< Select max triangle amplitude of 15 */ +#define DAC_TriangleAmplitude_31 ((uint32_t)0x00000400) /*!< Select max triangle amplitude of 31 */ +#define DAC_TriangleAmplitude_63 ((uint32_t)0x00000500) /*!< Select max triangle amplitude of 63 */ +#define DAC_TriangleAmplitude_127 ((uint32_t)0x00000600) /*!< Select max triangle amplitude of 127 */ +#define DAC_TriangleAmplitude_255 ((uint32_t)0x00000700) /*!< Select max triangle amplitude of 255 */ +#define DAC_TriangleAmplitude_511 ((uint32_t)0x00000800) /*!< Select max triangle amplitude of 511 */ +#define DAC_TriangleAmplitude_1023 ((uint32_t)0x00000900) /*!< Select max triangle amplitude of 1023 */ +#define DAC_TriangleAmplitude_2047 ((uint32_t)0x00000A00) /*!< Select max triangle amplitude of 2047 */ +#define DAC_TriangleAmplitude_4095 ((uint32_t)0x00000B00) /*!< Select max triangle amplitude of 4095 */ + +#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE) (((VALUE) == DAC_LFSRUnmask_Bit0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits1_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits2_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits3_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits4_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits5_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits6_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits7_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits8_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits9_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits10_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits11_0) || \ + ((VALUE) == DAC_TriangleAmplitude_1) || \ + ((VALUE) == DAC_TriangleAmplitude_3) || \ + ((VALUE) == DAC_TriangleAmplitude_7) || \ + ((VALUE) == DAC_TriangleAmplitude_15) || \ + ((VALUE) == DAC_TriangleAmplitude_31) || \ + ((VALUE) == DAC_TriangleAmplitude_63) || \ + ((VALUE) == DAC_TriangleAmplitude_127) || \ + ((VALUE) == DAC_TriangleAmplitude_255) || \ + ((VALUE) == DAC_TriangleAmplitude_511) || \ + ((VALUE) == DAC_TriangleAmplitude_1023) || \ + ((VALUE) == DAC_TriangleAmplitude_2047) || \ + ((VALUE) == DAC_TriangleAmplitude_4095)) +/** + * @} + */ + +/** @defgroup DAC_output_buffer + * @{ + */ + +#define DAC_OutputBuffer_Enable ((uint32_t)0x00000000) +#define DAC_OutputBuffer_Disable ((uint32_t)0x00000002) +#define IS_DAC_OUTPUT_BUFFER_STATE(STATE) (((STATE) == DAC_OutputBuffer_Enable) || \ + ((STATE) == DAC_OutputBuffer_Disable)) +/** + * @} + */ + +/** @defgroup DAC_Channel_selection + * @{ + */ + +#define DAC_Channel_1 ((uint32_t)0x00000000) +#define DAC_Channel_2 ((uint32_t)0x00000010) +#define IS_DAC_CHANNEL(CHANNEL) (((CHANNEL) == DAC_Channel_1) || \ + ((CHANNEL) == DAC_Channel_2)) +/** + * @} + */ + +/** @defgroup DAC_data_alignment + * @{ + */ + +#define DAC_Align_12b_R ((uint32_t)0x00000000) +#define DAC_Align_12b_L ((uint32_t)0x00000004) +#define DAC_Align_8b_R ((uint32_t)0x00000008) +#define IS_DAC_ALIGN(ALIGN) (((ALIGN) == DAC_Align_12b_R) || \ + ((ALIGN) == DAC_Align_12b_L) || \ + ((ALIGN) == DAC_Align_8b_R)) +/** + * @} + */ + +/** @defgroup DAC_wave_generation + * @{ + */ + +#define DAC_Wave_Noise ((uint32_t)0x00000040) +#define DAC_Wave_Triangle ((uint32_t)0x00000080) +#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_Wave_Noise) || \ + ((WAVE) == DAC_Wave_Triangle)) +/** + * @} + */ + +/** @defgroup DAC_data + * @{ + */ + +#define IS_DAC_DATA(DATA) ((DATA) <= 0xFFF0) +/** + * @} + */ +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/** @defgroup DAC_interrupts_definition + * @{ + */ + +#define DAC_IT_DMAUDR ((uint32_t)0x00002000) +#define IS_DAC_IT(IT) (((IT) == DAC_IT_DMAUDR)) + +/** + * @} + */ + +/** @defgroup DAC_flags_definition + * @{ + */ + +#define DAC_FLAG_DMAUDR ((uint32_t)0x00002000) +#define IS_DAC_FLAG(FLAG) (((FLAG) == DAC_FLAG_DMAUDR)) + +/** + * @} + */ +#endif + +/** + * @} + */ + +/** @defgroup DAC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DAC_Exported_Functions + * @{ + */ + +void DAC_DeInit(void); +void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct); +void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct); +void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState); +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +void DAC_ITConfig(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState); +#endif +void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState); +void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState); +void DAC_DualSoftwareTriggerCmd(FunctionalState NewState); +void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState); +void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data); +void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data); +void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1); +uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel); +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +FlagStatus DAC_GetFlagStatus(uint32_t DAC_Channel, uint32_t DAC_FLAG); +void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG); +ITStatus DAC_GetITStatus(uint32_t DAC_Channel, uint32_t DAC_IT); +void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT); +#endif + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_DAC_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h new file mode 100644 index 0000000..89ceb9a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h @@ -0,0 +1,119 @@ +/** + ****************************************************************************** + * @file stm32f10x_dbgmcu.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the DBGMCU + * firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_DBGMCU_H +#define __STM32F10x_DBGMCU_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DBGMCU + * @{ + */ + +/** @defgroup DBGMCU_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Exported_Constants + * @{ + */ + +#define DBGMCU_SLEEP ((uint32_t)0x00000001) +#define DBGMCU_STOP ((uint32_t)0x00000002) +#define DBGMCU_STANDBY ((uint32_t)0x00000004) +#define DBGMCU_IWDG_STOP ((uint32_t)0x00000100) +#define DBGMCU_WWDG_STOP ((uint32_t)0x00000200) +#define DBGMCU_TIM1_STOP ((uint32_t)0x00000400) +#define DBGMCU_TIM2_STOP ((uint32_t)0x00000800) +#define DBGMCU_TIM3_STOP ((uint32_t)0x00001000) +#define DBGMCU_TIM4_STOP ((uint32_t)0x00002000) +#define DBGMCU_CAN1_STOP ((uint32_t)0x00004000) +#define DBGMCU_I2C1_SMBUS_TIMEOUT ((uint32_t)0x00008000) +#define DBGMCU_I2C2_SMBUS_TIMEOUT ((uint32_t)0x00010000) +#define DBGMCU_TIM8_STOP ((uint32_t)0x00020000) +#define DBGMCU_TIM5_STOP ((uint32_t)0x00040000) +#define DBGMCU_TIM6_STOP ((uint32_t)0x00080000) +#define DBGMCU_TIM7_STOP ((uint32_t)0x00100000) +#define DBGMCU_CAN2_STOP ((uint32_t)0x00200000) +#define DBGMCU_TIM15_STOP ((uint32_t)0x00400000) +#define DBGMCU_TIM16_STOP ((uint32_t)0x00800000) +#define DBGMCU_TIM17_STOP ((uint32_t)0x01000000) +#define DBGMCU_TIM12_STOP ((uint32_t)0x02000000) +#define DBGMCU_TIM13_STOP ((uint32_t)0x04000000) +#define DBGMCU_TIM14_STOP ((uint32_t)0x08000000) +#define DBGMCU_TIM9_STOP ((uint32_t)0x10000000) +#define DBGMCU_TIM10_STOP ((uint32_t)0x20000000) +#define DBGMCU_TIM11_STOP ((uint32_t)0x40000000) + +#define IS_DBGMCU_PERIPH(PERIPH) ((((PERIPH) & 0x800000F8) == 0x00) && ((PERIPH) != 0x00)) +/** + * @} + */ + +/** @defgroup DBGMCU_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Exported_Functions + * @{ + */ + +uint32_t DBGMCU_GetREVID(void); +uint32_t DBGMCU_GetDEVID(void); +void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_DBGMCU_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h new file mode 100644 index 0000000..14275fe --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h @@ -0,0 +1,439 @@ +/** + ****************************************************************************** + * @file stm32f10x_dma.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the DMA firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_DMA_H +#define __STM32F10x_DMA_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DMA + * @{ + */ + +/** @defgroup DMA_Exported_Types + * @{ + */ + +/** + * @brief DMA Init structure definition + */ + +typedef struct +{ + uint32_t DMA_PeripheralBaseAddr; /*!< Specifies the peripheral base address for DMAy Channelx. */ + + uint32_t DMA_MemoryBaseAddr; /*!< Specifies the memory base address for DMAy Channelx. */ + + uint32_t DMA_DIR; /*!< Specifies if the peripheral is the source or destination. + This parameter can be a value of @ref DMA_data_transfer_direction */ + + uint32_t DMA_BufferSize; /*!< Specifies the buffer size, in data unit, of the specified Channel. + The data unit is equal to the configuration set in DMA_PeripheralDataSize + or DMA_MemoryDataSize members depending in the transfer direction. */ + + uint32_t DMA_PeripheralInc; /*!< Specifies whether the Peripheral address register is incremented or not. + This parameter can be a value of @ref DMA_peripheral_incremented_mode */ + + uint32_t DMA_MemoryInc; /*!< Specifies whether the memory address register is incremented or not. + This parameter can be a value of @ref DMA_memory_incremented_mode */ + + uint32_t DMA_PeripheralDataSize; /*!< Specifies the Peripheral data width. + This parameter can be a value of @ref DMA_peripheral_data_size */ + + uint32_t DMA_MemoryDataSize; /*!< Specifies the Memory data width. + This parameter can be a value of @ref DMA_memory_data_size */ + + uint32_t DMA_Mode; /*!< Specifies the operation mode of the DMAy Channelx. + This parameter can be a value of @ref DMA_circular_normal_mode. + @note: The circular buffer mode cannot be used if the memory-to-memory + data transfer is configured on the selected Channel */ + + uint32_t DMA_Priority; /*!< Specifies the software priority for the DMAy Channelx. + This parameter can be a value of @ref DMA_priority_level */ + + uint32_t DMA_M2M; /*!< Specifies if the DMAy Channelx will be used in memory-to-memory transfer. + This parameter can be a value of @ref DMA_memory_to_memory */ +}DMA_InitTypeDef; + +/** + * @} + */ + +/** @defgroup DMA_Exported_Constants + * @{ + */ + +#define IS_DMA_ALL_PERIPH(PERIPH) (((PERIPH) == DMA1_Channel1) || \ + ((PERIPH) == DMA1_Channel2) || \ + ((PERIPH) == DMA1_Channel3) || \ + ((PERIPH) == DMA1_Channel4) || \ + ((PERIPH) == DMA1_Channel5) || \ + ((PERIPH) == DMA1_Channel6) || \ + ((PERIPH) == DMA1_Channel7) || \ + ((PERIPH) == DMA2_Channel1) || \ + ((PERIPH) == DMA2_Channel2) || \ + ((PERIPH) == DMA2_Channel3) || \ + ((PERIPH) == DMA2_Channel4) || \ + ((PERIPH) == DMA2_Channel5)) + +/** @defgroup DMA_data_transfer_direction + * @{ + */ + +#define DMA_DIR_PeripheralDST ((uint32_t)0x00000010) +#define DMA_DIR_PeripheralSRC ((uint32_t)0x00000000) +#define IS_DMA_DIR(DIR) (((DIR) == DMA_DIR_PeripheralDST) || \ + ((DIR) == DMA_DIR_PeripheralSRC)) +/** + * @} + */ + +/** @defgroup DMA_peripheral_incremented_mode + * @{ + */ + +#define DMA_PeripheralInc_Enable ((uint32_t)0x00000040) +#define DMA_PeripheralInc_Disable ((uint32_t)0x00000000) +#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PeripheralInc_Enable) || \ + ((STATE) == DMA_PeripheralInc_Disable)) +/** + * @} + */ + +/** @defgroup DMA_memory_incremented_mode + * @{ + */ + +#define DMA_MemoryInc_Enable ((uint32_t)0x00000080) +#define DMA_MemoryInc_Disable ((uint32_t)0x00000000) +#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MemoryInc_Enable) || \ + ((STATE) == DMA_MemoryInc_Disable)) +/** + * @} + */ + +/** @defgroup DMA_peripheral_data_size + * @{ + */ + +#define DMA_PeripheralDataSize_Byte ((uint32_t)0x00000000) +#define DMA_PeripheralDataSize_HalfWord ((uint32_t)0x00000100) +#define DMA_PeripheralDataSize_Word ((uint32_t)0x00000200) +#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PeripheralDataSize_Byte) || \ + ((SIZE) == DMA_PeripheralDataSize_HalfWord) || \ + ((SIZE) == DMA_PeripheralDataSize_Word)) +/** + * @} + */ + +/** @defgroup DMA_memory_data_size + * @{ + */ + +#define DMA_MemoryDataSize_Byte ((uint32_t)0x00000000) +#define DMA_MemoryDataSize_HalfWord ((uint32_t)0x00000400) +#define DMA_MemoryDataSize_Word ((uint32_t)0x00000800) +#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MemoryDataSize_Byte) || \ + ((SIZE) == DMA_MemoryDataSize_HalfWord) || \ + ((SIZE) == DMA_MemoryDataSize_Word)) +/** + * @} + */ + +/** @defgroup DMA_circular_normal_mode + * @{ + */ + +#define DMA_Mode_Circular ((uint32_t)0x00000020) +#define DMA_Mode_Normal ((uint32_t)0x00000000) +#define IS_DMA_MODE(MODE) (((MODE) == DMA_Mode_Circular) || ((MODE) == DMA_Mode_Normal)) +/** + * @} + */ + +/** @defgroup DMA_priority_level + * @{ + */ + +#define DMA_Priority_VeryHigh ((uint32_t)0x00003000) +#define DMA_Priority_High ((uint32_t)0x00002000) +#define DMA_Priority_Medium ((uint32_t)0x00001000) +#define DMA_Priority_Low ((uint32_t)0x00000000) +#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_Priority_VeryHigh) || \ + ((PRIORITY) == DMA_Priority_High) || \ + ((PRIORITY) == DMA_Priority_Medium) || \ + ((PRIORITY) == DMA_Priority_Low)) +/** + * @} + */ + +/** @defgroup DMA_memory_to_memory + * @{ + */ + +#define DMA_M2M_Enable ((uint32_t)0x00004000) +#define DMA_M2M_Disable ((uint32_t)0x00000000) +#define IS_DMA_M2M_STATE(STATE) (((STATE) == DMA_M2M_Enable) || ((STATE) == DMA_M2M_Disable)) + +/** + * @} + */ + +/** @defgroup DMA_interrupts_definition + * @{ + */ + +#define DMA_IT_TC ((uint32_t)0x00000002) +#define DMA_IT_HT ((uint32_t)0x00000004) +#define DMA_IT_TE ((uint32_t)0x00000008) +#define IS_DMA_CONFIG_IT(IT) ((((IT) & 0xFFFFFFF1) == 0x00) && ((IT) != 0x00)) + +#define DMA1_IT_GL1 ((uint32_t)0x00000001) +#define DMA1_IT_TC1 ((uint32_t)0x00000002) +#define DMA1_IT_HT1 ((uint32_t)0x00000004) +#define DMA1_IT_TE1 ((uint32_t)0x00000008) +#define DMA1_IT_GL2 ((uint32_t)0x00000010) +#define DMA1_IT_TC2 ((uint32_t)0x00000020) +#define DMA1_IT_HT2 ((uint32_t)0x00000040) +#define DMA1_IT_TE2 ((uint32_t)0x00000080) +#define DMA1_IT_GL3 ((uint32_t)0x00000100) +#define DMA1_IT_TC3 ((uint32_t)0x00000200) +#define DMA1_IT_HT3 ((uint32_t)0x00000400) +#define DMA1_IT_TE3 ((uint32_t)0x00000800) +#define DMA1_IT_GL4 ((uint32_t)0x00001000) +#define DMA1_IT_TC4 ((uint32_t)0x00002000) +#define DMA1_IT_HT4 ((uint32_t)0x00004000) +#define DMA1_IT_TE4 ((uint32_t)0x00008000) +#define DMA1_IT_GL5 ((uint32_t)0x00010000) +#define DMA1_IT_TC5 ((uint32_t)0x00020000) +#define DMA1_IT_HT5 ((uint32_t)0x00040000) +#define DMA1_IT_TE5 ((uint32_t)0x00080000) +#define DMA1_IT_GL6 ((uint32_t)0x00100000) +#define DMA1_IT_TC6 ((uint32_t)0x00200000) +#define DMA1_IT_HT6 ((uint32_t)0x00400000) +#define DMA1_IT_TE6 ((uint32_t)0x00800000) +#define DMA1_IT_GL7 ((uint32_t)0x01000000) +#define DMA1_IT_TC7 ((uint32_t)0x02000000) +#define DMA1_IT_HT7 ((uint32_t)0x04000000) +#define DMA1_IT_TE7 ((uint32_t)0x08000000) + +#define DMA2_IT_GL1 ((uint32_t)0x10000001) +#define DMA2_IT_TC1 ((uint32_t)0x10000002) +#define DMA2_IT_HT1 ((uint32_t)0x10000004) +#define DMA2_IT_TE1 ((uint32_t)0x10000008) +#define DMA2_IT_GL2 ((uint32_t)0x10000010) +#define DMA2_IT_TC2 ((uint32_t)0x10000020) +#define DMA2_IT_HT2 ((uint32_t)0x10000040) +#define DMA2_IT_TE2 ((uint32_t)0x10000080) +#define DMA2_IT_GL3 ((uint32_t)0x10000100) +#define DMA2_IT_TC3 ((uint32_t)0x10000200) +#define DMA2_IT_HT3 ((uint32_t)0x10000400) +#define DMA2_IT_TE3 ((uint32_t)0x10000800) +#define DMA2_IT_GL4 ((uint32_t)0x10001000) +#define DMA2_IT_TC4 ((uint32_t)0x10002000) +#define DMA2_IT_HT4 ((uint32_t)0x10004000) +#define DMA2_IT_TE4 ((uint32_t)0x10008000) +#define DMA2_IT_GL5 ((uint32_t)0x10010000) +#define DMA2_IT_TC5 ((uint32_t)0x10020000) +#define DMA2_IT_HT5 ((uint32_t)0x10040000) +#define DMA2_IT_TE5 ((uint32_t)0x10080000) + +#define IS_DMA_CLEAR_IT(IT) (((((IT) & 0xF0000000) == 0x00) || (((IT) & 0xEFF00000) == 0x00)) && ((IT) != 0x00)) + +#define IS_DMA_GET_IT(IT) (((IT) == DMA1_IT_GL1) || ((IT) == DMA1_IT_TC1) || \ + ((IT) == DMA1_IT_HT1) || ((IT) == DMA1_IT_TE1) || \ + ((IT) == DMA1_IT_GL2) || ((IT) == DMA1_IT_TC2) || \ + ((IT) == DMA1_IT_HT2) || ((IT) == DMA1_IT_TE2) || \ + ((IT) == DMA1_IT_GL3) || ((IT) == DMA1_IT_TC3) || \ + ((IT) == DMA1_IT_HT3) || ((IT) == DMA1_IT_TE3) || \ + ((IT) == DMA1_IT_GL4) || ((IT) == DMA1_IT_TC4) || \ + ((IT) == DMA1_IT_HT4) || ((IT) == DMA1_IT_TE4) || \ + ((IT) == DMA1_IT_GL5) || ((IT) == DMA1_IT_TC5) || \ + ((IT) == DMA1_IT_HT5) || ((IT) == DMA1_IT_TE5) || \ + ((IT) == DMA1_IT_GL6) || ((IT) == DMA1_IT_TC6) || \ + ((IT) == DMA1_IT_HT6) || ((IT) == DMA1_IT_TE6) || \ + ((IT) == DMA1_IT_GL7) || ((IT) == DMA1_IT_TC7) || \ + ((IT) == DMA1_IT_HT7) || ((IT) == DMA1_IT_TE7) || \ + ((IT) == DMA2_IT_GL1) || ((IT) == DMA2_IT_TC1) || \ + ((IT) == DMA2_IT_HT1) || ((IT) == DMA2_IT_TE1) || \ + ((IT) == DMA2_IT_GL2) || ((IT) == DMA2_IT_TC2) || \ + ((IT) == DMA2_IT_HT2) || ((IT) == DMA2_IT_TE2) || \ + ((IT) == DMA2_IT_GL3) || ((IT) == DMA2_IT_TC3) || \ + ((IT) == DMA2_IT_HT3) || ((IT) == DMA2_IT_TE3) || \ + ((IT) == DMA2_IT_GL4) || ((IT) == DMA2_IT_TC4) || \ + ((IT) == DMA2_IT_HT4) || ((IT) == DMA2_IT_TE4) || \ + ((IT) == DMA2_IT_GL5) || ((IT) == DMA2_IT_TC5) || \ + ((IT) == DMA2_IT_HT5) || ((IT) == DMA2_IT_TE5)) + +/** + * @} + */ + +/** @defgroup DMA_flags_definition + * @{ + */ +#define DMA1_FLAG_GL1 ((uint32_t)0x00000001) +#define DMA1_FLAG_TC1 ((uint32_t)0x00000002) +#define DMA1_FLAG_HT1 ((uint32_t)0x00000004) +#define DMA1_FLAG_TE1 ((uint32_t)0x00000008) +#define DMA1_FLAG_GL2 ((uint32_t)0x00000010) +#define DMA1_FLAG_TC2 ((uint32_t)0x00000020) +#define DMA1_FLAG_HT2 ((uint32_t)0x00000040) +#define DMA1_FLAG_TE2 ((uint32_t)0x00000080) +#define DMA1_FLAG_GL3 ((uint32_t)0x00000100) +#define DMA1_FLAG_TC3 ((uint32_t)0x00000200) +#define DMA1_FLAG_HT3 ((uint32_t)0x00000400) +#define DMA1_FLAG_TE3 ((uint32_t)0x00000800) +#define DMA1_FLAG_GL4 ((uint32_t)0x00001000) +#define DMA1_FLAG_TC4 ((uint32_t)0x00002000) +#define DMA1_FLAG_HT4 ((uint32_t)0x00004000) +#define DMA1_FLAG_TE4 ((uint32_t)0x00008000) +#define DMA1_FLAG_GL5 ((uint32_t)0x00010000) +#define DMA1_FLAG_TC5 ((uint32_t)0x00020000) +#define DMA1_FLAG_HT5 ((uint32_t)0x00040000) +#define DMA1_FLAG_TE5 ((uint32_t)0x00080000) +#define DMA1_FLAG_GL6 ((uint32_t)0x00100000) +#define DMA1_FLAG_TC6 ((uint32_t)0x00200000) +#define DMA1_FLAG_HT6 ((uint32_t)0x00400000) +#define DMA1_FLAG_TE6 ((uint32_t)0x00800000) +#define DMA1_FLAG_GL7 ((uint32_t)0x01000000) +#define DMA1_FLAG_TC7 ((uint32_t)0x02000000) +#define DMA1_FLAG_HT7 ((uint32_t)0x04000000) +#define DMA1_FLAG_TE7 ((uint32_t)0x08000000) + +#define DMA2_FLAG_GL1 ((uint32_t)0x10000001) +#define DMA2_FLAG_TC1 ((uint32_t)0x10000002) +#define DMA2_FLAG_HT1 ((uint32_t)0x10000004) +#define DMA2_FLAG_TE1 ((uint32_t)0x10000008) +#define DMA2_FLAG_GL2 ((uint32_t)0x10000010) +#define DMA2_FLAG_TC2 ((uint32_t)0x10000020) +#define DMA2_FLAG_HT2 ((uint32_t)0x10000040) +#define DMA2_FLAG_TE2 ((uint32_t)0x10000080) +#define DMA2_FLAG_GL3 ((uint32_t)0x10000100) +#define DMA2_FLAG_TC3 ((uint32_t)0x10000200) +#define DMA2_FLAG_HT3 ((uint32_t)0x10000400) +#define DMA2_FLAG_TE3 ((uint32_t)0x10000800) +#define DMA2_FLAG_GL4 ((uint32_t)0x10001000) +#define DMA2_FLAG_TC4 ((uint32_t)0x10002000) +#define DMA2_FLAG_HT4 ((uint32_t)0x10004000) +#define DMA2_FLAG_TE4 ((uint32_t)0x10008000) +#define DMA2_FLAG_GL5 ((uint32_t)0x10010000) +#define DMA2_FLAG_TC5 ((uint32_t)0x10020000) +#define DMA2_FLAG_HT5 ((uint32_t)0x10040000) +#define DMA2_FLAG_TE5 ((uint32_t)0x10080000) + +#define IS_DMA_CLEAR_FLAG(FLAG) (((((FLAG) & 0xF0000000) == 0x00) || (((FLAG) & 0xEFF00000) == 0x00)) && ((FLAG) != 0x00)) + +#define IS_DMA_GET_FLAG(FLAG) (((FLAG) == DMA1_FLAG_GL1) || ((FLAG) == DMA1_FLAG_TC1) || \ + ((FLAG) == DMA1_FLAG_HT1) || ((FLAG) == DMA1_FLAG_TE1) || \ + ((FLAG) == DMA1_FLAG_GL2) || ((FLAG) == DMA1_FLAG_TC2) || \ + ((FLAG) == DMA1_FLAG_HT2) || ((FLAG) == DMA1_FLAG_TE2) || \ + ((FLAG) == DMA1_FLAG_GL3) || ((FLAG) == DMA1_FLAG_TC3) || \ + ((FLAG) == DMA1_FLAG_HT3) || ((FLAG) == DMA1_FLAG_TE3) || \ + ((FLAG) == DMA1_FLAG_GL4) || ((FLAG) == DMA1_FLAG_TC4) || \ + ((FLAG) == DMA1_FLAG_HT4) || ((FLAG) == DMA1_FLAG_TE4) || \ + ((FLAG) == DMA1_FLAG_GL5) || ((FLAG) == DMA1_FLAG_TC5) || \ + ((FLAG) == DMA1_FLAG_HT5) || ((FLAG) == DMA1_FLAG_TE5) || \ + ((FLAG) == DMA1_FLAG_GL6) || ((FLAG) == DMA1_FLAG_TC6) || \ + ((FLAG) == DMA1_FLAG_HT6) || ((FLAG) == DMA1_FLAG_TE6) || \ + ((FLAG) == DMA1_FLAG_GL7) || ((FLAG) == DMA1_FLAG_TC7) || \ + ((FLAG) == DMA1_FLAG_HT7) || ((FLAG) == DMA1_FLAG_TE7) || \ + ((FLAG) == DMA2_FLAG_GL1) || ((FLAG) == DMA2_FLAG_TC1) || \ + ((FLAG) == DMA2_FLAG_HT1) || ((FLAG) == DMA2_FLAG_TE1) || \ + ((FLAG) == DMA2_FLAG_GL2) || ((FLAG) == DMA2_FLAG_TC2) || \ + ((FLAG) == DMA2_FLAG_HT2) || ((FLAG) == DMA2_FLAG_TE2) || \ + ((FLAG) == DMA2_FLAG_GL3) || ((FLAG) == DMA2_FLAG_TC3) || \ + ((FLAG) == DMA2_FLAG_HT3) || ((FLAG) == DMA2_FLAG_TE3) || \ + ((FLAG) == DMA2_FLAG_GL4) || ((FLAG) == DMA2_FLAG_TC4) || \ + ((FLAG) == DMA2_FLAG_HT4) || ((FLAG) == DMA2_FLAG_TE4) || \ + ((FLAG) == DMA2_FLAG_GL5) || ((FLAG) == DMA2_FLAG_TC5) || \ + ((FLAG) == DMA2_FLAG_HT5) || ((FLAG) == DMA2_FLAG_TE5)) +/** + * @} + */ + +/** @defgroup DMA_Buffer_Size + * @{ + */ + +#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x1) && ((SIZE) < 0x10000)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup DMA_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DMA_Exported_Functions + * @{ + */ + +void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx); +void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct); +void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct); +void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState); +void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState); +void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber); +uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx); +FlagStatus DMA_GetFlagStatus(uint32_t DMAy_FLAG); +void DMA_ClearFlag(uint32_t DMAy_FLAG); +ITStatus DMA_GetITStatus(uint32_t DMAy_IT); +void DMA_ClearITPendingBit(uint32_t DMAy_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_DMA_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h new file mode 100644 index 0000000..bb9d7f6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h @@ -0,0 +1,184 @@ +/** + ****************************************************************************** + * @file stm32f10x_exti.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the EXTI firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_EXTI_H +#define __STM32F10x_EXTI_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup EXTI + * @{ + */ + +/** @defgroup EXTI_Exported_Types + * @{ + */ + +/** + * @brief EXTI mode enumeration + */ + +typedef enum +{ + EXTI_Mode_Interrupt = 0x00, + EXTI_Mode_Event = 0x04 +}EXTIMode_TypeDef; + +#define IS_EXTI_MODE(MODE) (((MODE) == EXTI_Mode_Interrupt) || ((MODE) == EXTI_Mode_Event)) + +/** + * @brief EXTI Trigger enumeration + */ + +typedef enum +{ + EXTI_Trigger_Rising = 0x08, + EXTI_Trigger_Falling = 0x0C, + EXTI_Trigger_Rising_Falling = 0x10 +}EXTITrigger_TypeDef; + +#define IS_EXTI_TRIGGER(TRIGGER) (((TRIGGER) == EXTI_Trigger_Rising) || \ + ((TRIGGER) == EXTI_Trigger_Falling) || \ + ((TRIGGER) == EXTI_Trigger_Rising_Falling)) +/** + * @brief EXTI Init Structure definition + */ + +typedef struct +{ + uint32_t EXTI_Line; /*!< Specifies the EXTI lines to be enabled or disabled. + This parameter can be any combination of @ref EXTI_Lines */ + + EXTIMode_TypeDef EXTI_Mode; /*!< Specifies the mode for the EXTI lines. + This parameter can be a value of @ref EXTIMode_TypeDef */ + + EXTITrigger_TypeDef EXTI_Trigger; /*!< Specifies the trigger signal active edge for the EXTI lines. + This parameter can be a value of @ref EXTIMode_TypeDef */ + + FunctionalState EXTI_LineCmd; /*!< Specifies the new state of the selected EXTI lines. + This parameter can be set either to ENABLE or DISABLE */ +}EXTI_InitTypeDef; + +/** + * @} + */ + +/** @defgroup EXTI_Exported_Constants + * @{ + */ + +/** @defgroup EXTI_Lines + * @{ + */ + +#define EXTI_Line0 ((uint32_t)0x00001) /*!< External interrupt line 0 */ +#define EXTI_Line1 ((uint32_t)0x00002) /*!< External interrupt line 1 */ +#define EXTI_Line2 ((uint32_t)0x00004) /*!< External interrupt line 2 */ +#define EXTI_Line3 ((uint32_t)0x00008) /*!< External interrupt line 3 */ +#define EXTI_Line4 ((uint32_t)0x00010) /*!< External interrupt line 4 */ +#define EXTI_Line5 ((uint32_t)0x00020) /*!< External interrupt line 5 */ +#define EXTI_Line6 ((uint32_t)0x00040) /*!< External interrupt line 6 */ +#define EXTI_Line7 ((uint32_t)0x00080) /*!< External interrupt line 7 */ +#define EXTI_Line8 ((uint32_t)0x00100) /*!< External interrupt line 8 */ +#define EXTI_Line9 ((uint32_t)0x00200) /*!< External interrupt line 9 */ +#define EXTI_Line10 ((uint32_t)0x00400) /*!< External interrupt line 10 */ +#define EXTI_Line11 ((uint32_t)0x00800) /*!< External interrupt line 11 */ +#define EXTI_Line12 ((uint32_t)0x01000) /*!< External interrupt line 12 */ +#define EXTI_Line13 ((uint32_t)0x02000) /*!< External interrupt line 13 */ +#define EXTI_Line14 ((uint32_t)0x04000) /*!< External interrupt line 14 */ +#define EXTI_Line15 ((uint32_t)0x08000) /*!< External interrupt line 15 */ +#define EXTI_Line16 ((uint32_t)0x10000) /*!< External interrupt line 16 Connected to the PVD Output */ +#define EXTI_Line17 ((uint32_t)0x20000) /*!< External interrupt line 17 Connected to the RTC Alarm event */ +#define EXTI_Line18 ((uint32_t)0x40000) /*!< External interrupt line 18 Connected to the USB Device/USB OTG FS + Wakeup from suspend event */ +#define EXTI_Line19 ((uint32_t)0x80000) /*!< External interrupt line 19 Connected to the Ethernet Wakeup event */ + +#define IS_EXTI_LINE(LINE) ((((LINE) & (uint32_t)0xFFF00000) == 0x00) && ((LINE) != (uint16_t)0x00)) +#define IS_GET_EXTI_LINE(LINE) (((LINE) == EXTI_Line0) || ((LINE) == EXTI_Line1) || \ + ((LINE) == EXTI_Line2) || ((LINE) == EXTI_Line3) || \ + ((LINE) == EXTI_Line4) || ((LINE) == EXTI_Line5) || \ + ((LINE) == EXTI_Line6) || ((LINE) == EXTI_Line7) || \ + ((LINE) == EXTI_Line8) || ((LINE) == EXTI_Line9) || \ + ((LINE) == EXTI_Line10) || ((LINE) == EXTI_Line11) || \ + ((LINE) == EXTI_Line12) || ((LINE) == EXTI_Line13) || \ + ((LINE) == EXTI_Line14) || ((LINE) == EXTI_Line15) || \ + ((LINE) == EXTI_Line16) || ((LINE) == EXTI_Line17) || \ + ((LINE) == EXTI_Line18) || ((LINE) == EXTI_Line19)) + + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup EXTI_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup EXTI_Exported_Functions + * @{ + */ + +void EXTI_DeInit(void); +void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct); +void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct); +void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line); +FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line); +void EXTI_ClearFlag(uint32_t EXTI_Line); +ITStatus EXTI_GetITStatus(uint32_t EXTI_Line); +void EXTI_ClearITPendingBit(uint32_t EXTI_Line); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_EXTI_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h new file mode 100644 index 0000000..63720de --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h @@ -0,0 +1,426 @@ +/** + ****************************************************************************** + * @file stm32f10x_flash.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the FLASH + * firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_FLASH_H +#define __STM32F10x_FLASH_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup FLASH + * @{ + */ + +/** @defgroup FLASH_Exported_Types + * @{ + */ + +/** + * @brief FLASH Status + */ + +typedef enum +{ + FLASH_BUSY = 1, + FLASH_ERROR_PG, + FLASH_ERROR_WRP, + FLASH_COMPLETE, + FLASH_TIMEOUT +}FLASH_Status; + +/** + * @} + */ + +/** @defgroup FLASH_Exported_Constants + * @{ + */ + +/** @defgroup Flash_Latency + * @{ + */ + +#define FLASH_Latency_0 ((uint32_t)0x00000000) /*!< FLASH Zero Latency cycle */ +#define FLASH_Latency_1 ((uint32_t)0x00000001) /*!< FLASH One Latency cycle */ +#define FLASH_Latency_2 ((uint32_t)0x00000002) /*!< FLASH Two Latency cycles */ +#define IS_FLASH_LATENCY(LATENCY) (((LATENCY) == FLASH_Latency_0) || \ + ((LATENCY) == FLASH_Latency_1) || \ + ((LATENCY) == FLASH_Latency_2)) +/** + * @} + */ + +/** @defgroup Half_Cycle_Enable_Disable + * @{ + */ + +#define FLASH_HalfCycleAccess_Enable ((uint32_t)0x00000008) /*!< FLASH Half Cycle Enable */ +#define FLASH_HalfCycleAccess_Disable ((uint32_t)0x00000000) /*!< FLASH Half Cycle Disable */ +#define IS_FLASH_HALFCYCLEACCESS_STATE(STATE) (((STATE) == FLASH_HalfCycleAccess_Enable) || \ + ((STATE) == FLASH_HalfCycleAccess_Disable)) +/** + * @} + */ + +/** @defgroup Prefetch_Buffer_Enable_Disable + * @{ + */ + +#define FLASH_PrefetchBuffer_Enable ((uint32_t)0x00000010) /*!< FLASH Prefetch Buffer Enable */ +#define FLASH_PrefetchBuffer_Disable ((uint32_t)0x00000000) /*!< FLASH Prefetch Buffer Disable */ +#define IS_FLASH_PREFETCHBUFFER_STATE(STATE) (((STATE) == FLASH_PrefetchBuffer_Enable) || \ + ((STATE) == FLASH_PrefetchBuffer_Disable)) +/** + * @} + */ + +/** @defgroup Option_Bytes_Write_Protection + * @{ + */ + +/* Values to be used with STM32 Low and Medium density devices */ +#define FLASH_WRProt_Pages0to3 ((uint32_t)0x00000001) /*!< STM32 Low and Medium density devices: Write protection of page 0 to 3 */ +#define FLASH_WRProt_Pages4to7 ((uint32_t)0x00000002) /*!< STM32 Low and Medium density devices: Write protection of page 4 to 7 */ +#define FLASH_WRProt_Pages8to11 ((uint32_t)0x00000004) /*!< STM32 Low and Medium density devices: Write protection of page 8 to 11 */ +#define FLASH_WRProt_Pages12to15 ((uint32_t)0x00000008) /*!< STM32 Low and Medium density devices: Write protection of page 12 to 15 */ +#define FLASH_WRProt_Pages16to19 ((uint32_t)0x00000010) /*!< STM32 Low and Medium density devices: Write protection of page 16 to 19 */ +#define FLASH_WRProt_Pages20to23 ((uint32_t)0x00000020) /*!< STM32 Low and Medium density devices: Write protection of page 20 to 23 */ +#define FLASH_WRProt_Pages24to27 ((uint32_t)0x00000040) /*!< STM32 Low and Medium density devices: Write protection of page 24 to 27 */ +#define FLASH_WRProt_Pages28to31 ((uint32_t)0x00000080) /*!< STM32 Low and Medium density devices: Write protection of page 28 to 31 */ + +/* Values to be used with STM32 Medium-density devices */ +#define FLASH_WRProt_Pages32to35 ((uint32_t)0x00000100) /*!< STM32 Medium-density devices: Write protection of page 32 to 35 */ +#define FLASH_WRProt_Pages36to39 ((uint32_t)0x00000200) /*!< STM32 Medium-density devices: Write protection of page 36 to 39 */ +#define FLASH_WRProt_Pages40to43 ((uint32_t)0x00000400) /*!< STM32 Medium-density devices: Write protection of page 40 to 43 */ +#define FLASH_WRProt_Pages44to47 ((uint32_t)0x00000800) /*!< STM32 Medium-density devices: Write protection of page 44 to 47 */ +#define FLASH_WRProt_Pages48to51 ((uint32_t)0x00001000) /*!< STM32 Medium-density devices: Write protection of page 48 to 51 */ +#define FLASH_WRProt_Pages52to55 ((uint32_t)0x00002000) /*!< STM32 Medium-density devices: Write protection of page 52 to 55 */ +#define FLASH_WRProt_Pages56to59 ((uint32_t)0x00004000) /*!< STM32 Medium-density devices: Write protection of page 56 to 59 */ +#define FLASH_WRProt_Pages60to63 ((uint32_t)0x00008000) /*!< STM32 Medium-density devices: Write protection of page 60 to 63 */ +#define FLASH_WRProt_Pages64to67 ((uint32_t)0x00010000) /*!< STM32 Medium-density devices: Write protection of page 64 to 67 */ +#define FLASH_WRProt_Pages68to71 ((uint32_t)0x00020000) /*!< STM32 Medium-density devices: Write protection of page 68 to 71 */ +#define FLASH_WRProt_Pages72to75 ((uint32_t)0x00040000) /*!< STM32 Medium-density devices: Write protection of page 72 to 75 */ +#define FLASH_WRProt_Pages76to79 ((uint32_t)0x00080000) /*!< STM32 Medium-density devices: Write protection of page 76 to 79 */ +#define FLASH_WRProt_Pages80to83 ((uint32_t)0x00100000) /*!< STM32 Medium-density devices: Write protection of page 80 to 83 */ +#define FLASH_WRProt_Pages84to87 ((uint32_t)0x00200000) /*!< STM32 Medium-density devices: Write protection of page 84 to 87 */ +#define FLASH_WRProt_Pages88to91 ((uint32_t)0x00400000) /*!< STM32 Medium-density devices: Write protection of page 88 to 91 */ +#define FLASH_WRProt_Pages92to95 ((uint32_t)0x00800000) /*!< STM32 Medium-density devices: Write protection of page 92 to 95 */ +#define FLASH_WRProt_Pages96to99 ((uint32_t)0x01000000) /*!< STM32 Medium-density devices: Write protection of page 96 to 99 */ +#define FLASH_WRProt_Pages100to103 ((uint32_t)0x02000000) /*!< STM32 Medium-density devices: Write protection of page 100 to 103 */ +#define FLASH_WRProt_Pages104to107 ((uint32_t)0x04000000) /*!< STM32 Medium-density devices: Write protection of page 104 to 107 */ +#define FLASH_WRProt_Pages108to111 ((uint32_t)0x08000000) /*!< STM32 Medium-density devices: Write protection of page 108 to 111 */ +#define FLASH_WRProt_Pages112to115 ((uint32_t)0x10000000) /*!< STM32 Medium-density devices: Write protection of page 112 to 115 */ +#define FLASH_WRProt_Pages116to119 ((uint32_t)0x20000000) /*!< STM32 Medium-density devices: Write protection of page 115 to 119 */ +#define FLASH_WRProt_Pages120to123 ((uint32_t)0x40000000) /*!< STM32 Medium-density devices: Write protection of page 120 to 123 */ +#define FLASH_WRProt_Pages124to127 ((uint32_t)0x80000000) /*!< STM32 Medium-density devices: Write protection of page 124 to 127 */ + +/* Values to be used with STM32 High-density and STM32F10X Connectivity line devices */ +#define FLASH_WRProt_Pages0to1 ((uint32_t)0x00000001) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 0 to 1 */ +#define FLASH_WRProt_Pages2to3 ((uint32_t)0x00000002) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 2 to 3 */ +#define FLASH_WRProt_Pages4to5 ((uint32_t)0x00000004) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 4 to 5 */ +#define FLASH_WRProt_Pages6to7 ((uint32_t)0x00000008) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 6 to 7 */ +#define FLASH_WRProt_Pages8to9 ((uint32_t)0x00000010) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 8 to 9 */ +#define FLASH_WRProt_Pages10to11 ((uint32_t)0x00000020) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 10 to 11 */ +#define FLASH_WRProt_Pages12to13 ((uint32_t)0x00000040) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 12 to 13 */ +#define FLASH_WRProt_Pages14to15 ((uint32_t)0x00000080) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 14 to 15 */ +#define FLASH_WRProt_Pages16to17 ((uint32_t)0x00000100) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 16 to 17 */ +#define FLASH_WRProt_Pages18to19 ((uint32_t)0x00000200) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 18 to 19 */ +#define FLASH_WRProt_Pages20to21 ((uint32_t)0x00000400) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 20 to 21 */ +#define FLASH_WRProt_Pages22to23 ((uint32_t)0x00000800) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 22 to 23 */ +#define FLASH_WRProt_Pages24to25 ((uint32_t)0x00001000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 24 to 25 */ +#define FLASH_WRProt_Pages26to27 ((uint32_t)0x00002000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 26 to 27 */ +#define FLASH_WRProt_Pages28to29 ((uint32_t)0x00004000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 28 to 29 */ +#define FLASH_WRProt_Pages30to31 ((uint32_t)0x00008000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 30 to 31 */ +#define FLASH_WRProt_Pages32to33 ((uint32_t)0x00010000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 32 to 33 */ +#define FLASH_WRProt_Pages34to35 ((uint32_t)0x00020000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 34 to 35 */ +#define FLASH_WRProt_Pages36to37 ((uint32_t)0x00040000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 36 to 37 */ +#define FLASH_WRProt_Pages38to39 ((uint32_t)0x00080000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 38 to 39 */ +#define FLASH_WRProt_Pages40to41 ((uint32_t)0x00100000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 40 to 41 */ +#define FLASH_WRProt_Pages42to43 ((uint32_t)0x00200000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 42 to 43 */ +#define FLASH_WRProt_Pages44to45 ((uint32_t)0x00400000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 44 to 45 */ +#define FLASH_WRProt_Pages46to47 ((uint32_t)0x00800000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 46 to 47 */ +#define FLASH_WRProt_Pages48to49 ((uint32_t)0x01000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 48 to 49 */ +#define FLASH_WRProt_Pages50to51 ((uint32_t)0x02000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 50 to 51 */ +#define FLASH_WRProt_Pages52to53 ((uint32_t)0x04000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 52 to 53 */ +#define FLASH_WRProt_Pages54to55 ((uint32_t)0x08000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 54 to 55 */ +#define FLASH_WRProt_Pages56to57 ((uint32_t)0x10000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 56 to 57 */ +#define FLASH_WRProt_Pages58to59 ((uint32_t)0x20000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 58 to 59 */ +#define FLASH_WRProt_Pages60to61 ((uint32_t)0x40000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 60 to 61 */ +#define FLASH_WRProt_Pages62to127 ((uint32_t)0x80000000) /*!< STM32 Connectivity line devices: Write protection of page 62 to 127 */ +#define FLASH_WRProt_Pages62to255 ((uint32_t)0x80000000) /*!< STM32 Medium-density devices: Write protection of page 62 to 255 */ +#define FLASH_WRProt_Pages62to511 ((uint32_t)0x80000000) /*!< STM32 XL-density devices: Write protection of page 62 to 511 */ + +#define FLASH_WRProt_AllPages ((uint32_t)0xFFFFFFFF) /*!< Write protection of all Pages */ + +#define IS_FLASH_WRPROT_PAGE(PAGE) (((PAGE) != 0x00000000)) + +#define IS_FLASH_ADDRESS(ADDRESS) (((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x080FFFFF)) + +#define IS_OB_DATA_ADDRESS(ADDRESS) (((ADDRESS) == 0x1FFFF804) || ((ADDRESS) == 0x1FFFF806)) + +/** + * @} + */ + +/** @defgroup Option_Bytes_IWatchdog + * @{ + */ + +#define OB_IWDG_SW ((uint16_t)0x0001) /*!< Software IWDG selected */ +#define OB_IWDG_HW ((uint16_t)0x0000) /*!< Hardware IWDG selected */ +#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW)) + +/** + * @} + */ + +/** @defgroup Option_Bytes_nRST_STOP + * @{ + */ + +#define OB_STOP_NoRST ((uint16_t)0x0002) /*!< No reset generated when entering in STOP */ +#define OB_STOP_RST ((uint16_t)0x0000) /*!< Reset generated when entering in STOP */ +#define IS_OB_STOP_SOURCE(SOURCE) (((SOURCE) == OB_STOP_NoRST) || ((SOURCE) == OB_STOP_RST)) + +/** + * @} + */ + +/** @defgroup Option_Bytes_nRST_STDBY + * @{ + */ + +#define OB_STDBY_NoRST ((uint16_t)0x0004) /*!< No reset generated when entering in STANDBY */ +#define OB_STDBY_RST ((uint16_t)0x0000) /*!< Reset generated when entering in STANDBY */ +#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NoRST) || ((SOURCE) == OB_STDBY_RST)) + +#ifdef STM32F10X_XL +/** + * @} + */ +/** @defgroup FLASH_Boot + * @{ + */ +#define FLASH_BOOT_Bank1 ((uint16_t)0x0000) /*!< At startup, if boot pins are set in boot from user Flash position + and this parameter is selected the device will boot from Bank1(Default) */ +#define FLASH_BOOT_Bank2 ((uint16_t)0x0001) /*!< At startup, if boot pins are set in boot from user Flash position + and this parameter is selected the device will boot from Bank 2 or Bank 1, + depending on the activation of the bank */ +#define IS_FLASH_BOOT(BOOT) (((BOOT) == FLASH_BOOT_Bank1) || ((BOOT) == FLASH_BOOT_Bank2)) +#endif +/** + * @} + */ +/** @defgroup FLASH_Interrupts + * @{ + */ +#ifdef STM32F10X_XL +#define FLASH_IT_BANK2_ERROR ((uint32_t)0x80000400) /*!< FPEC BANK2 error interrupt source */ +#define FLASH_IT_BANK2_EOP ((uint32_t)0x80001000) /*!< End of FLASH BANK2 Operation Interrupt source */ + +#define FLASH_IT_BANK1_ERROR FLASH_IT_ERROR /*!< FPEC BANK1 error interrupt source */ +#define FLASH_IT_BANK1_EOP FLASH_IT_EOP /*!< End of FLASH BANK1 Operation Interrupt source */ + +#define FLASH_IT_ERROR ((uint32_t)0x00000400) /*!< FPEC BANK1 error interrupt source */ +#define FLASH_IT_EOP ((uint32_t)0x00001000) /*!< End of FLASH BANK1 Operation Interrupt source */ +#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0x7FFFEBFF) == 0x00000000) && (((IT) != 0x00000000))) +#else +#define FLASH_IT_ERROR ((uint32_t)0x00000400) /*!< FPEC error interrupt source */ +#define FLASH_IT_EOP ((uint32_t)0x00001000) /*!< End of FLASH Operation Interrupt source */ +#define FLASH_IT_BANK1_ERROR FLASH_IT_ERROR /*!< FPEC BANK1 error interrupt source */ +#define FLASH_IT_BANK1_EOP FLASH_IT_EOP /*!< End of FLASH BANK1 Operation Interrupt source */ + +#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0xFFFFEBFF) == 0x00000000) && (((IT) != 0x00000000))) +#endif + +/** + * @} + */ + +/** @defgroup FLASH_Flags + * @{ + */ +#ifdef STM32F10X_XL +#define FLASH_FLAG_BANK2_BSY ((uint32_t)0x80000001) /*!< FLASH BANK2 Busy flag */ +#define FLASH_FLAG_BANK2_EOP ((uint32_t)0x80000020) /*!< FLASH BANK2 End of Operation flag */ +#define FLASH_FLAG_BANK2_PGERR ((uint32_t)0x80000004) /*!< FLASH BANK2 Program error flag */ +#define FLASH_FLAG_BANK2_WRPRTERR ((uint32_t)0x80000010) /*!< FLASH BANK2 Write protected error flag */ + +#define FLASH_FLAG_BANK1_BSY FLASH_FLAG_BSY /*!< FLASH BANK1 Busy flag*/ +#define FLASH_FLAG_BANK1_EOP FLASH_FLAG_EOP /*!< FLASH BANK1 End of Operation flag */ +#define FLASH_FLAG_BANK1_PGERR FLASH_FLAG_PGERR /*!< FLASH BANK1 Program error flag */ +#define FLASH_FLAG_BANK1_WRPRTERR FLASH_FLAG_WRPRTERR /*!< FLASH BANK1 Write protected error flag */ + +#define FLASH_FLAG_BSY ((uint32_t)0x00000001) /*!< FLASH Busy flag */ +#define FLASH_FLAG_EOP ((uint32_t)0x00000020) /*!< FLASH End of Operation flag */ +#define FLASH_FLAG_PGERR ((uint32_t)0x00000004) /*!< FLASH Program error flag */ +#define FLASH_FLAG_WRPRTERR ((uint32_t)0x00000010) /*!< FLASH Write protected error flag */ +#define FLASH_FLAG_OPTERR ((uint32_t)0x00000001) /*!< FLASH Option Byte error flag */ + +#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0x7FFFFFCA) == 0x00000000) && ((FLAG) != 0x00000000)) +#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \ + ((FLAG) == FLASH_FLAG_PGERR) || ((FLAG) == FLASH_FLAG_WRPRTERR) || \ + ((FLAG) == FLASH_FLAG_OPTERR)|| \ + ((FLAG) == FLASH_FLAG_BANK1_BSY) || ((FLAG) == FLASH_FLAG_BANK1_EOP) || \ + ((FLAG) == FLASH_FLAG_BANK1_PGERR) || ((FLAG) == FLASH_FLAG_BANK1_WRPRTERR) || \ + ((FLAG) == FLASH_FLAG_BANK2_BSY) || ((FLAG) == FLASH_FLAG_BANK2_EOP) || \ + ((FLAG) == FLASH_FLAG_BANK2_PGERR) || ((FLAG) == FLASH_FLAG_BANK2_WRPRTERR)) +#else +#define FLASH_FLAG_BSY ((uint32_t)0x00000001) /*!< FLASH Busy flag */ +#define FLASH_FLAG_EOP ((uint32_t)0x00000020) /*!< FLASH End of Operation flag */ +#define FLASH_FLAG_PGERR ((uint32_t)0x00000004) /*!< FLASH Program error flag */ +#define FLASH_FLAG_WRPRTERR ((uint32_t)0x00000010) /*!< FLASH Write protected error flag */ +#define FLASH_FLAG_OPTERR ((uint32_t)0x00000001) /*!< FLASH Option Byte error flag */ + +#define FLASH_FLAG_BANK1_BSY FLASH_FLAG_BSY /*!< FLASH BANK1 Busy flag*/ +#define FLASH_FLAG_BANK1_EOP FLASH_FLAG_EOP /*!< FLASH BANK1 End of Operation flag */ +#define FLASH_FLAG_BANK1_PGERR FLASH_FLAG_PGERR /*!< FLASH BANK1 Program error flag */ +#define FLASH_FLAG_BANK1_WRPRTERR FLASH_FLAG_WRPRTERR /*!< FLASH BANK1 Write protected error flag */ + +#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFCA) == 0x00000000) && ((FLAG) != 0x00000000)) +#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \ + ((FLAG) == FLASH_FLAG_PGERR) || ((FLAG) == FLASH_FLAG_WRPRTERR) || \ + ((FLAG) == FLASH_FLAG_BANK1_BSY) || ((FLAG) == FLASH_FLAG_BANK1_EOP) || \ + ((FLAG) == FLASH_FLAG_BANK1_PGERR) || ((FLAG) == FLASH_FLAG_BANK1_WRPRTERR) || \ + ((FLAG) == FLASH_FLAG_OPTERR)) +#endif + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup FLASH_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup FLASH_Exported_Functions + * @{ + */ + +/*------------ Functions used for all STM32F10x devices -----*/ +void FLASH_SetLatency(uint32_t FLASH_Latency); +void FLASH_HalfCycleAccessCmd(uint32_t FLASH_HalfCycleAccess); +void FLASH_PrefetchBufferCmd(uint32_t FLASH_PrefetchBuffer); +void FLASH_Unlock(void); +void FLASH_Lock(void); +FLASH_Status FLASH_ErasePage(uint32_t Page_Address); +FLASH_Status FLASH_EraseAllPages(void); +FLASH_Status FLASH_EraseOptionBytes(void); +FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data); +FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data); +FLASH_Status FLASH_ProgramOptionByteData(uint32_t Address, uint8_t Data); +FLASH_Status FLASH_EnableWriteProtection(uint32_t FLASH_Pages); +FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState); +FLASH_Status FLASH_UserOptionByteConfig(uint16_t OB_IWDG, uint16_t OB_STOP, uint16_t OB_STDBY); +uint32_t FLASH_GetUserOptionByte(void); +uint32_t FLASH_GetWriteProtectionOptionByte(void); +FlagStatus FLASH_GetReadOutProtectionStatus(void); +FlagStatus FLASH_GetPrefetchBufferStatus(void); +void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState); +FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG); +void FLASH_ClearFlag(uint32_t FLASH_FLAG); +FLASH_Status FLASH_GetStatus(void); +FLASH_Status FLASH_WaitForLastOperation(uint32_t Timeout); + +/*------------ New function used for all STM32F10x devices -----*/ +void FLASH_UnlockBank1(void); +void FLASH_LockBank1(void); +FLASH_Status FLASH_EraseAllBank1Pages(void); +FLASH_Status FLASH_GetBank1Status(void); +FLASH_Status FLASH_WaitForLastBank1Operation(uint32_t Timeout); + +#ifdef STM32F10X_XL +/*---- New Functions used only with STM32F10x_XL density devices -----*/ +void FLASH_UnlockBank2(void); +void FLASH_LockBank2(void); +FLASH_Status FLASH_EraseAllBank2Pages(void); +FLASH_Status FLASH_GetBank2Status(void); +FLASH_Status FLASH_WaitForLastBank2Operation(uint32_t Timeout); +FLASH_Status FLASH_BootConfig(uint16_t FLASH_BOOT); +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_FLASH_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h new file mode 100644 index 0000000..6e1769d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h @@ -0,0 +1,733 @@ +/** + ****************************************************************************** + * @file stm32f10x_fsmc.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the FSMC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_FSMC_H +#define __STM32F10x_FSMC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup FSMC + * @{ + */ + +/** @defgroup FSMC_Exported_Types + * @{ + */ + +/** + * @brief Timing parameters For NOR/SRAM Banks + */ + +typedef struct +{ + uint32_t FSMC_AddressSetupTime; /*!< Defines the number of HCLK cycles to configure + the duration of the address setup time. + This parameter can be a value between 0 and 0xF. + @note: It is not used with synchronous NOR Flash memories. */ + + uint32_t FSMC_AddressHoldTime; /*!< Defines the number of HCLK cycles to configure + the duration of the address hold time. + This parameter can be a value between 0 and 0xF. + @note: It is not used with synchronous NOR Flash memories.*/ + + uint32_t FSMC_DataSetupTime; /*!< Defines the number of HCLK cycles to configure + the duration of the data setup time. + This parameter can be a value between 0 and 0xFF. + @note: It is used for SRAMs, ROMs and asynchronous multiplexed NOR Flash memories. */ + + uint32_t FSMC_BusTurnAroundDuration; /*!< Defines the number of HCLK cycles to configure + the duration of the bus turnaround. + This parameter can be a value between 0 and 0xF. + @note: It is only used for multiplexed NOR Flash memories. */ + + uint32_t FSMC_CLKDivision; /*!< Defines the period of CLK clock output signal, expressed in number of HCLK cycles. + This parameter can be a value between 1 and 0xF. + @note: This parameter is not used for asynchronous NOR Flash, SRAM or ROM accesses. */ + + uint32_t FSMC_DataLatency; /*!< Defines the number of memory clock cycles to issue + to the memory before getting the first data. + The value of this parameter depends on the memory type as shown below: + - It must be set to 0 in case of a CRAM + - It is don't care in asynchronous NOR, SRAM or ROM accesses + - It may assume a value between 0 and 0xF in NOR Flash memories + with synchronous burst mode enable */ + + uint32_t FSMC_AccessMode; /*!< Specifies the asynchronous access mode. + This parameter can be a value of @ref FSMC_Access_Mode */ +}FSMC_NORSRAMTimingInitTypeDef; + +/** + * @brief FSMC NOR/SRAM Init structure definition + */ + +typedef struct +{ + uint32_t FSMC_Bank; /*!< Specifies the NOR/SRAM memory bank that will be used. + This parameter can be a value of @ref FSMC_NORSRAM_Bank */ + + uint32_t FSMC_DataAddressMux; /*!< Specifies whether the address and data values are + multiplexed on the databus or not. + This parameter can be a value of @ref FSMC_Data_Address_Bus_Multiplexing */ + + uint32_t FSMC_MemoryType; /*!< Specifies the type of external memory attached to + the corresponding memory bank. + This parameter can be a value of @ref FSMC_Memory_Type */ + + uint32_t FSMC_MemoryDataWidth; /*!< Specifies the external memory device width. + This parameter can be a value of @ref FSMC_Data_Width */ + + uint32_t FSMC_BurstAccessMode; /*!< Enables or disables the burst access mode for Flash memory, + valid only with synchronous burst Flash memories. + This parameter can be a value of @ref FSMC_Burst_Access_Mode */ + + uint32_t FSMC_AsynchronousWait; /*!< Enables or disables wait signal during asynchronous transfers, + valid only with asynchronous Flash memories. + This parameter can be a value of @ref FSMC_AsynchronousWait */ + + uint32_t FSMC_WaitSignalPolarity; /*!< Specifies the wait signal polarity, valid only when accessing + the Flash memory in burst mode. + This parameter can be a value of @ref FSMC_Wait_Signal_Polarity */ + + uint32_t FSMC_WrapMode; /*!< Enables or disables the Wrapped burst access mode for Flash + memory, valid only when accessing Flash memories in burst mode. + This parameter can be a value of @ref FSMC_Wrap_Mode */ + + uint32_t FSMC_WaitSignalActive; /*!< Specifies if the wait signal is asserted by the memory one + clock cycle before the wait state or during the wait state, + valid only when accessing memories in burst mode. + This parameter can be a value of @ref FSMC_Wait_Timing */ + + uint32_t FSMC_WriteOperation; /*!< Enables or disables the write operation in the selected bank by the FSMC. + This parameter can be a value of @ref FSMC_Write_Operation */ + + uint32_t FSMC_WaitSignal; /*!< Enables or disables the wait-state insertion via wait + signal, valid for Flash memory access in burst mode. + This parameter can be a value of @ref FSMC_Wait_Signal */ + + uint32_t FSMC_ExtendedMode; /*!< Enables or disables the extended mode. + This parameter can be a value of @ref FSMC_Extended_Mode */ + + uint32_t FSMC_WriteBurst; /*!< Enables or disables the write burst operation. + This parameter can be a value of @ref FSMC_Write_Burst */ + + FSMC_NORSRAMTimingInitTypeDef* FSMC_ReadWriteTimingStruct; /*!< Timing Parameters for write and read access if the ExtendedMode is not used*/ + + FSMC_NORSRAMTimingInitTypeDef* FSMC_WriteTimingStruct; /*!< Timing Parameters for write access if the ExtendedMode is used*/ +}FSMC_NORSRAMInitTypeDef; + +/** + * @brief Timing parameters For FSMC NAND and PCCARD Banks + */ + +typedef struct +{ + uint32_t FSMC_SetupTime; /*!< Defines the number of HCLK cycles to setup address before + the command assertion for NAND-Flash read or write access + to common/Attribute or I/O memory space (depending on + the memory space timing to be configured). + This parameter can be a value between 0 and 0xFF.*/ + + uint32_t FSMC_WaitSetupTime; /*!< Defines the minimum number of HCLK cycles to assert the + command for NAND-Flash read or write access to + common/Attribute or I/O memory space (depending on the + memory space timing to be configured). + This parameter can be a number between 0x00 and 0xFF */ + + uint32_t FSMC_HoldSetupTime; /*!< Defines the number of HCLK clock cycles to hold address + (and data for write access) after the command deassertion + for NAND-Flash read or write access to common/Attribute + or I/O memory space (depending on the memory space timing + to be configured). + This parameter can be a number between 0x00 and 0xFF */ + + uint32_t FSMC_HiZSetupTime; /*!< Defines the number of HCLK clock cycles during which the + databus is kept in HiZ after the start of a NAND-Flash + write access to common/Attribute or I/O memory space (depending + on the memory space timing to be configured). + This parameter can be a number between 0x00 and 0xFF */ +}FSMC_NAND_PCCARDTimingInitTypeDef; + +/** + * @brief FSMC NAND Init structure definition + */ + +typedef struct +{ + uint32_t FSMC_Bank; /*!< Specifies the NAND memory bank that will be used. + This parameter can be a value of @ref FSMC_NAND_Bank */ + + uint32_t FSMC_Waitfeature; /*!< Enables or disables the Wait feature for the NAND Memory Bank. + This parameter can be any value of @ref FSMC_Wait_feature */ + + uint32_t FSMC_MemoryDataWidth; /*!< Specifies the external memory device width. + This parameter can be any value of @ref FSMC_Data_Width */ + + uint32_t FSMC_ECC; /*!< Enables or disables the ECC computation. + This parameter can be any value of @ref FSMC_ECC */ + + uint32_t FSMC_ECCPageSize; /*!< Defines the page size for the extended ECC. + This parameter can be any value of @ref FSMC_ECC_Page_Size */ + + uint32_t FSMC_TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between CLE low and RE low. + This parameter can be a value between 0 and 0xFF. */ + + uint32_t FSMC_TARSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between ALE low and RE low. + This parameter can be a number between 0x0 and 0xFF */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct; /*!< FSMC Common Space Timing */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct; /*!< FSMC Attribute Space Timing */ +}FSMC_NANDInitTypeDef; + +/** + * @brief FSMC PCCARD Init structure definition + */ + +typedef struct +{ + uint32_t FSMC_Waitfeature; /*!< Enables or disables the Wait feature for the Memory Bank. + This parameter can be any value of @ref FSMC_Wait_feature */ + + uint32_t FSMC_TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between CLE low and RE low. + This parameter can be a value between 0 and 0xFF. */ + + uint32_t FSMC_TARSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between ALE low and RE low. + This parameter can be a number between 0x0 and 0xFF */ + + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct; /*!< FSMC Common Space Timing */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct; /*!< FSMC Attribute Space Timing */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_IOSpaceTimingStruct; /*!< FSMC IO Space Timing */ +}FSMC_PCCARDInitTypeDef; + +/** + * @} + */ + +/** @defgroup FSMC_Exported_Constants + * @{ + */ + +/** @defgroup FSMC_NORSRAM_Bank + * @{ + */ +#define FSMC_Bank1_NORSRAM1 ((uint32_t)0x00000000) +#define FSMC_Bank1_NORSRAM2 ((uint32_t)0x00000002) +#define FSMC_Bank1_NORSRAM3 ((uint32_t)0x00000004) +#define FSMC_Bank1_NORSRAM4 ((uint32_t)0x00000006) +/** + * @} + */ + +/** @defgroup FSMC_NAND_Bank + * @{ + */ +#define FSMC_Bank2_NAND ((uint32_t)0x00000010) +#define FSMC_Bank3_NAND ((uint32_t)0x00000100) +/** + * @} + */ + +/** @defgroup FSMC_PCCARD_Bank + * @{ + */ +#define FSMC_Bank4_PCCARD ((uint32_t)0x00001000) +/** + * @} + */ + +#define IS_FSMC_NORSRAM_BANK(BANK) (((BANK) == FSMC_Bank1_NORSRAM1) || \ + ((BANK) == FSMC_Bank1_NORSRAM2) || \ + ((BANK) == FSMC_Bank1_NORSRAM3) || \ + ((BANK) == FSMC_Bank1_NORSRAM4)) + +#define IS_FSMC_NAND_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \ + ((BANK) == FSMC_Bank3_NAND)) + +#define IS_FSMC_GETFLAG_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \ + ((BANK) == FSMC_Bank3_NAND) || \ + ((BANK) == FSMC_Bank4_PCCARD)) + +#define IS_FSMC_IT_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \ + ((BANK) == FSMC_Bank3_NAND) || \ + ((BANK) == FSMC_Bank4_PCCARD)) + +/** @defgroup NOR_SRAM_Controller + * @{ + */ + +/** @defgroup FSMC_Data_Address_Bus_Multiplexing + * @{ + */ + +#define FSMC_DataAddressMux_Disable ((uint32_t)0x00000000) +#define FSMC_DataAddressMux_Enable ((uint32_t)0x00000002) +#define IS_FSMC_MUX(MUX) (((MUX) == FSMC_DataAddressMux_Disable) || \ + ((MUX) == FSMC_DataAddressMux_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_Memory_Type + * @{ + */ + +#define FSMC_MemoryType_SRAM ((uint32_t)0x00000000) +#define FSMC_MemoryType_PSRAM ((uint32_t)0x00000004) +#define FSMC_MemoryType_NOR ((uint32_t)0x00000008) +#define IS_FSMC_MEMORY(MEMORY) (((MEMORY) == FSMC_MemoryType_SRAM) || \ + ((MEMORY) == FSMC_MemoryType_PSRAM)|| \ + ((MEMORY) == FSMC_MemoryType_NOR)) + +/** + * @} + */ + +/** @defgroup FSMC_Data_Width + * @{ + */ + +#define FSMC_MemoryDataWidth_8b ((uint32_t)0x00000000) +#define FSMC_MemoryDataWidth_16b ((uint32_t)0x00000010) +#define IS_FSMC_MEMORY_WIDTH(WIDTH) (((WIDTH) == FSMC_MemoryDataWidth_8b) || \ + ((WIDTH) == FSMC_MemoryDataWidth_16b)) + +/** + * @} + */ + +/** @defgroup FSMC_Burst_Access_Mode + * @{ + */ + +#define FSMC_BurstAccessMode_Disable ((uint32_t)0x00000000) +#define FSMC_BurstAccessMode_Enable ((uint32_t)0x00000100) +#define IS_FSMC_BURSTMODE(STATE) (((STATE) == FSMC_BurstAccessMode_Disable) || \ + ((STATE) == FSMC_BurstAccessMode_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_AsynchronousWait + * @{ + */ +#define FSMC_AsynchronousWait_Disable ((uint32_t)0x00000000) +#define FSMC_AsynchronousWait_Enable ((uint32_t)0x00008000) +#define IS_FSMC_ASYNWAIT(STATE) (((STATE) == FSMC_AsynchronousWait_Disable) || \ + ((STATE) == FSMC_AsynchronousWait_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_Wait_Signal_Polarity + * @{ + */ + +#define FSMC_WaitSignalPolarity_Low ((uint32_t)0x00000000) +#define FSMC_WaitSignalPolarity_High ((uint32_t)0x00000200) +#define IS_FSMC_WAIT_POLARITY(POLARITY) (((POLARITY) == FSMC_WaitSignalPolarity_Low) || \ + ((POLARITY) == FSMC_WaitSignalPolarity_High)) + +/** + * @} + */ + +/** @defgroup FSMC_Wrap_Mode + * @{ + */ + +#define FSMC_WrapMode_Disable ((uint32_t)0x00000000) +#define FSMC_WrapMode_Enable ((uint32_t)0x00000400) +#define IS_FSMC_WRAP_MODE(MODE) (((MODE) == FSMC_WrapMode_Disable) || \ + ((MODE) == FSMC_WrapMode_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_Wait_Timing + * @{ + */ + +#define FSMC_WaitSignalActive_BeforeWaitState ((uint32_t)0x00000000) +#define FSMC_WaitSignalActive_DuringWaitState ((uint32_t)0x00000800) +#define IS_FSMC_WAIT_SIGNAL_ACTIVE(ACTIVE) (((ACTIVE) == FSMC_WaitSignalActive_BeforeWaitState) || \ + ((ACTIVE) == FSMC_WaitSignalActive_DuringWaitState)) + +/** + * @} + */ + +/** @defgroup FSMC_Write_Operation + * @{ + */ + +#define FSMC_WriteOperation_Disable ((uint32_t)0x00000000) +#define FSMC_WriteOperation_Enable ((uint32_t)0x00001000) +#define IS_FSMC_WRITE_OPERATION(OPERATION) (((OPERATION) == FSMC_WriteOperation_Disable) || \ + ((OPERATION) == FSMC_WriteOperation_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_Wait_Signal + * @{ + */ + +#define FSMC_WaitSignal_Disable ((uint32_t)0x00000000) +#define FSMC_WaitSignal_Enable ((uint32_t)0x00002000) +#define IS_FSMC_WAITE_SIGNAL(SIGNAL) (((SIGNAL) == FSMC_WaitSignal_Disable) || \ + ((SIGNAL) == FSMC_WaitSignal_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_Extended_Mode + * @{ + */ + +#define FSMC_ExtendedMode_Disable ((uint32_t)0x00000000) +#define FSMC_ExtendedMode_Enable ((uint32_t)0x00004000) + +#define IS_FSMC_EXTENDED_MODE(MODE) (((MODE) == FSMC_ExtendedMode_Disable) || \ + ((MODE) == FSMC_ExtendedMode_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_Write_Burst + * @{ + */ + +#define FSMC_WriteBurst_Disable ((uint32_t)0x00000000) +#define FSMC_WriteBurst_Enable ((uint32_t)0x00080000) +#define IS_FSMC_WRITE_BURST(BURST) (((BURST) == FSMC_WriteBurst_Disable) || \ + ((BURST) == FSMC_WriteBurst_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_Address_Setup_Time + * @{ + */ + +#define IS_FSMC_ADDRESS_SETUP_TIME(TIME) ((TIME) <= 0xF) + +/** + * @} + */ + +/** @defgroup FSMC_Address_Hold_Time + * @{ + */ + +#define IS_FSMC_ADDRESS_HOLD_TIME(TIME) ((TIME) <= 0xF) + +/** + * @} + */ + +/** @defgroup FSMC_Data_Setup_Time + * @{ + */ + +#define IS_FSMC_DATASETUP_TIME(TIME) (((TIME) > 0) && ((TIME) <= 0xFF)) + +/** + * @} + */ + +/** @defgroup FSMC_Bus_Turn_around_Duration + * @{ + */ + +#define IS_FSMC_TURNAROUND_TIME(TIME) ((TIME) <= 0xF) + +/** + * @} + */ + +/** @defgroup FSMC_CLK_Division + * @{ + */ + +#define IS_FSMC_CLK_DIV(DIV) ((DIV) <= 0xF) + +/** + * @} + */ + +/** @defgroup FSMC_Data_Latency + * @{ + */ + +#define IS_FSMC_DATA_LATENCY(LATENCY) ((LATENCY) <= 0xF) + +/** + * @} + */ + +/** @defgroup FSMC_Access_Mode + * @{ + */ + +#define FSMC_AccessMode_A ((uint32_t)0x00000000) +#define FSMC_AccessMode_B ((uint32_t)0x10000000) +#define FSMC_AccessMode_C ((uint32_t)0x20000000) +#define FSMC_AccessMode_D ((uint32_t)0x30000000) +#define IS_FSMC_ACCESS_MODE(MODE) (((MODE) == FSMC_AccessMode_A) || \ + ((MODE) == FSMC_AccessMode_B) || \ + ((MODE) == FSMC_AccessMode_C) || \ + ((MODE) == FSMC_AccessMode_D)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup NAND_PCCARD_Controller + * @{ + */ + +/** @defgroup FSMC_Wait_feature + * @{ + */ + +#define FSMC_Waitfeature_Disable ((uint32_t)0x00000000) +#define FSMC_Waitfeature_Enable ((uint32_t)0x00000002) +#define IS_FSMC_WAIT_FEATURE(FEATURE) (((FEATURE) == FSMC_Waitfeature_Disable) || \ + ((FEATURE) == FSMC_Waitfeature_Enable)) + +/** + * @} + */ + + +/** @defgroup FSMC_ECC + * @{ + */ + +#define FSMC_ECC_Disable ((uint32_t)0x00000000) +#define FSMC_ECC_Enable ((uint32_t)0x00000040) +#define IS_FSMC_ECC_STATE(STATE) (((STATE) == FSMC_ECC_Disable) || \ + ((STATE) == FSMC_ECC_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_ECC_Page_Size + * @{ + */ + +#define FSMC_ECCPageSize_256Bytes ((uint32_t)0x00000000) +#define FSMC_ECCPageSize_512Bytes ((uint32_t)0x00020000) +#define FSMC_ECCPageSize_1024Bytes ((uint32_t)0x00040000) +#define FSMC_ECCPageSize_2048Bytes ((uint32_t)0x00060000) +#define FSMC_ECCPageSize_4096Bytes ((uint32_t)0x00080000) +#define FSMC_ECCPageSize_8192Bytes ((uint32_t)0x000A0000) +#define IS_FSMC_ECCPAGE_SIZE(SIZE) (((SIZE) == FSMC_ECCPageSize_256Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_512Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_1024Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_2048Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_4096Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_8192Bytes)) + +/** + * @} + */ + +/** @defgroup FSMC_TCLR_Setup_Time + * @{ + */ + +#define IS_FSMC_TCLR_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_TAR_Setup_Time + * @{ + */ + +#define IS_FSMC_TAR_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_Setup_Time + * @{ + */ + +#define IS_FSMC_SETUP_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_Wait_Setup_Time + * @{ + */ + +#define IS_FSMC_WAIT_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_Hold_Setup_Time + * @{ + */ + +#define IS_FSMC_HOLD_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_HiZ_Setup_Time + * @{ + */ + +#define IS_FSMC_HIZ_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_Interrupt_sources + * @{ + */ + +#define FSMC_IT_RisingEdge ((uint32_t)0x00000008) +#define FSMC_IT_Level ((uint32_t)0x00000010) +#define FSMC_IT_FallingEdge ((uint32_t)0x00000020) +#define IS_FSMC_IT(IT) ((((IT) & (uint32_t)0xFFFFFFC7) == 0x00000000) && ((IT) != 0x00000000)) +#define IS_FSMC_GET_IT(IT) (((IT) == FSMC_IT_RisingEdge) || \ + ((IT) == FSMC_IT_Level) || \ + ((IT) == FSMC_IT_FallingEdge)) +/** + * @} + */ + +/** @defgroup FSMC_Flags + * @{ + */ + +#define FSMC_FLAG_RisingEdge ((uint32_t)0x00000001) +#define FSMC_FLAG_Level ((uint32_t)0x00000002) +#define FSMC_FLAG_FallingEdge ((uint32_t)0x00000004) +#define FSMC_FLAG_FEMPT ((uint32_t)0x00000040) +#define IS_FSMC_GET_FLAG(FLAG) (((FLAG) == FSMC_FLAG_RisingEdge) || \ + ((FLAG) == FSMC_FLAG_Level) || \ + ((FLAG) == FSMC_FLAG_FallingEdge) || \ + ((FLAG) == FSMC_FLAG_FEMPT)) + +#define IS_FSMC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFF8) == 0x00000000) && ((FLAG) != 0x00000000)) + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup FSMC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup FSMC_Exported_Functions + * @{ + */ + +void FSMC_NORSRAMDeInit(uint32_t FSMC_Bank); +void FSMC_NANDDeInit(uint32_t FSMC_Bank); +void FSMC_PCCARDDeInit(void); +void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct); +void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct); +void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct); +void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct); +void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct); +void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct); +void FSMC_NORSRAMCmd(uint32_t FSMC_Bank, FunctionalState NewState); +void FSMC_NANDCmd(uint32_t FSMC_Bank, FunctionalState NewState); +void FSMC_PCCARDCmd(FunctionalState NewState); +void FSMC_NANDECCCmd(uint32_t FSMC_Bank, FunctionalState NewState); +uint32_t FSMC_GetECC(uint32_t FSMC_Bank); +void FSMC_ITConfig(uint32_t FSMC_Bank, uint32_t FSMC_IT, FunctionalState NewState); +FlagStatus FSMC_GetFlagStatus(uint32_t FSMC_Bank, uint32_t FSMC_FLAG); +void FSMC_ClearFlag(uint32_t FSMC_Bank, uint32_t FSMC_FLAG); +ITStatus FSMC_GetITStatus(uint32_t FSMC_Bank, uint32_t FSMC_IT); +void FSMC_ClearITPendingBit(uint32_t FSMC_Bank, uint32_t FSMC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_FSMC_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h new file mode 100644 index 0000000..dd28da8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h @@ -0,0 +1,385 @@ +/** + ****************************************************************************** + * @file stm32f10x_gpio.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the GPIO + * firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_GPIO_H +#define __STM32F10x_GPIO_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup GPIO + * @{ + */ + +/** @defgroup GPIO_Exported_Types + * @{ + */ + +#define IS_GPIO_ALL_PERIPH(PERIPH) (((PERIPH) == GPIOA) || \ + ((PERIPH) == GPIOB) || \ + ((PERIPH) == GPIOC) || \ + ((PERIPH) == GPIOD) || \ + ((PERIPH) == GPIOE) || \ + ((PERIPH) == GPIOF) || \ + ((PERIPH) == GPIOG)) + +/** + * @brief Output Maximum frequency selection + */ + +typedef enum +{ + GPIO_Speed_10MHz = 1, + GPIO_Speed_2MHz, + GPIO_Speed_50MHz +}GPIOSpeed_TypeDef; +#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_Speed_10MHz) || ((SPEED) == GPIO_Speed_2MHz) || \ + ((SPEED) == GPIO_Speed_50MHz)) + +/** + * @brief Configuration Mode enumeration + */ + +typedef enum +{ GPIO_Mode_AIN = 0x0, + GPIO_Mode_IN_FLOATING = 0x04, + GPIO_Mode_IPD = 0x28, + GPIO_Mode_IPU = 0x48, + GPIO_Mode_Out_OD = 0x14, + GPIO_Mode_Out_PP = 0x10, + GPIO_Mode_AF_OD = 0x1C, + GPIO_Mode_AF_PP = 0x18 +}GPIOMode_TypeDef; + +#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_Mode_AIN) || ((MODE) == GPIO_Mode_IN_FLOATING) || \ + ((MODE) == GPIO_Mode_IPD) || ((MODE) == GPIO_Mode_IPU) || \ + ((MODE) == GPIO_Mode_Out_OD) || ((MODE) == GPIO_Mode_Out_PP) || \ + ((MODE) == GPIO_Mode_AF_OD) || ((MODE) == GPIO_Mode_AF_PP)) + +/** + * @brief GPIO Init structure definition + */ + +typedef struct +{ + uint16_t GPIO_Pin; /*!< Specifies the GPIO pins to be configured. + This parameter can be any value of @ref GPIO_pins_define */ + + GPIOSpeed_TypeDef GPIO_Speed; /*!< Specifies the speed for the selected pins. + This parameter can be a value of @ref GPIOSpeed_TypeDef */ + + GPIOMode_TypeDef GPIO_Mode; /*!< Specifies the operating mode for the selected pins. + This parameter can be a value of @ref GPIOMode_TypeDef */ +}GPIO_InitTypeDef; + + +/** + * @brief Bit_SET and Bit_RESET enumeration + */ + +typedef enum +{ Bit_RESET = 0, + Bit_SET +}BitAction; + +#define IS_GPIO_BIT_ACTION(ACTION) (((ACTION) == Bit_RESET) || ((ACTION) == Bit_SET)) + +/** + * @} + */ + +/** @defgroup GPIO_Exported_Constants + * @{ + */ + +/** @defgroup GPIO_pins_define + * @{ + */ + +#define GPIO_Pin_0 ((uint16_t)0x0001) /*!< Pin 0 selected */ +#define GPIO_Pin_1 ((uint16_t)0x0002) /*!< Pin 1 selected */ +#define GPIO_Pin_2 ((uint16_t)0x0004) /*!< Pin 2 selected */ +#define GPIO_Pin_3 ((uint16_t)0x0008) /*!< Pin 3 selected */ +#define GPIO_Pin_4 ((uint16_t)0x0010) /*!< Pin 4 selected */ +#define GPIO_Pin_5 ((uint16_t)0x0020) /*!< Pin 5 selected */ +#define GPIO_Pin_6 ((uint16_t)0x0040) /*!< Pin 6 selected */ +#define GPIO_Pin_7 ((uint16_t)0x0080) /*!< Pin 7 selected */ +#define GPIO_Pin_8 ((uint16_t)0x0100) /*!< Pin 8 selected */ +#define GPIO_Pin_9 ((uint16_t)0x0200) /*!< Pin 9 selected */ +#define GPIO_Pin_10 ((uint16_t)0x0400) /*!< Pin 10 selected */ +#define GPIO_Pin_11 ((uint16_t)0x0800) /*!< Pin 11 selected */ +#define GPIO_Pin_12 ((uint16_t)0x1000) /*!< Pin 12 selected */ +#define GPIO_Pin_13 ((uint16_t)0x2000) /*!< Pin 13 selected */ +#define GPIO_Pin_14 ((uint16_t)0x4000) /*!< Pin 14 selected */ +#define GPIO_Pin_15 ((uint16_t)0x8000) /*!< Pin 15 selected */ +#define GPIO_Pin_All ((uint16_t)0xFFFF) /*!< All pins selected */ + +#define IS_GPIO_PIN(PIN) ((((PIN) & (uint16_t)0x00) == 0x00) && ((PIN) != (uint16_t)0x00)) + +#define IS_GET_GPIO_PIN(PIN) (((PIN) == GPIO_Pin_0) || \ + ((PIN) == GPIO_Pin_1) || \ + ((PIN) == GPIO_Pin_2) || \ + ((PIN) == GPIO_Pin_3) || \ + ((PIN) == GPIO_Pin_4) || \ + ((PIN) == GPIO_Pin_5) || \ + ((PIN) == GPIO_Pin_6) || \ + ((PIN) == GPIO_Pin_7) || \ + ((PIN) == GPIO_Pin_8) || \ + ((PIN) == GPIO_Pin_9) || \ + ((PIN) == GPIO_Pin_10) || \ + ((PIN) == GPIO_Pin_11) || \ + ((PIN) == GPIO_Pin_12) || \ + ((PIN) == GPIO_Pin_13) || \ + ((PIN) == GPIO_Pin_14) || \ + ((PIN) == GPIO_Pin_15)) + +/** + * @} + */ + +/** @defgroup GPIO_Remap_define + * @{ + */ + +#define GPIO_Remap_SPI1 ((uint32_t)0x00000001) /*!< SPI1 Alternate Function mapping */ +#define GPIO_Remap_I2C1 ((uint32_t)0x00000002) /*!< I2C1 Alternate Function mapping */ +#define GPIO_Remap_USART1 ((uint32_t)0x00000004) /*!< USART1 Alternate Function mapping */ +#define GPIO_Remap_USART2 ((uint32_t)0x00000008) /*!< USART2 Alternate Function mapping */ +#define GPIO_PartialRemap_USART3 ((uint32_t)0x00140010) /*!< USART3 Partial Alternate Function mapping */ +#define GPIO_FullRemap_USART3 ((uint32_t)0x00140030) /*!< USART3 Full Alternate Function mapping */ +#define GPIO_PartialRemap_TIM1 ((uint32_t)0x00160040) /*!< TIM1 Partial Alternate Function mapping */ +#define GPIO_FullRemap_TIM1 ((uint32_t)0x001600C0) /*!< TIM1 Full Alternate Function mapping */ +#define GPIO_PartialRemap1_TIM2 ((uint32_t)0x00180100) /*!< TIM2 Partial1 Alternate Function mapping */ +#define GPIO_PartialRemap2_TIM2 ((uint32_t)0x00180200) /*!< TIM2 Partial2 Alternate Function mapping */ +#define GPIO_FullRemap_TIM2 ((uint32_t)0x00180300) /*!< TIM2 Full Alternate Function mapping */ +#define GPIO_PartialRemap_TIM3 ((uint32_t)0x001A0800) /*!< TIM3 Partial Alternate Function mapping */ +#define GPIO_FullRemap_TIM3 ((uint32_t)0x001A0C00) /*!< TIM3 Full Alternate Function mapping */ +#define GPIO_Remap_TIM4 ((uint32_t)0x00001000) /*!< TIM4 Alternate Function mapping */ +#define GPIO_Remap1_CAN1 ((uint32_t)0x001D4000) /*!< CAN1 Alternate Function mapping */ +#define GPIO_Remap2_CAN1 ((uint32_t)0x001D6000) /*!< CAN1 Alternate Function mapping */ +#define GPIO_Remap_PD01 ((uint32_t)0x00008000) /*!< PD01 Alternate Function mapping */ +#define GPIO_Remap_TIM5CH4_LSI ((uint32_t)0x00200001) /*!< LSI connected to TIM5 Channel4 input capture for calibration */ +#define GPIO_Remap_ADC1_ETRGINJ ((uint32_t)0x00200002) /*!< ADC1 External Trigger Injected Conversion remapping */ +#define GPIO_Remap_ADC1_ETRGREG ((uint32_t)0x00200004) /*!< ADC1 External Trigger Regular Conversion remapping */ +#define GPIO_Remap_ADC2_ETRGINJ ((uint32_t)0x00200008) /*!< ADC2 External Trigger Injected Conversion remapping */ +#define GPIO_Remap_ADC2_ETRGREG ((uint32_t)0x00200010) /*!< ADC2 External Trigger Regular Conversion remapping */ +#define GPIO_Remap_ETH ((uint32_t)0x00200020) /*!< Ethernet remapping (only for Connectivity line devices) */ +#define GPIO_Remap_CAN2 ((uint32_t)0x00200040) /*!< CAN2 remapping (only for Connectivity line devices) */ +#define GPIO_Remap_SWJ_NoJTRST ((uint32_t)0x00300100) /*!< Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST */ +#define GPIO_Remap_SWJ_JTAGDisable ((uint32_t)0x00300200) /*!< JTAG-DP Disabled and SW-DP Enabled */ +#define GPIO_Remap_SWJ_Disable ((uint32_t)0x00300400) /*!< Full SWJ Disabled (JTAG-DP + SW-DP) */ +#define GPIO_Remap_SPI3 ((uint32_t)0x00201100) /*!< SPI3/I2S3 Alternate Function mapping (only for Connectivity line devices) */ +#define GPIO_Remap_TIM2ITR1_PTP_SOF ((uint32_t)0x00202000) /*!< Ethernet PTP output or USB OTG SOF (Start of Frame) connected + to TIM2 Internal Trigger 1 for calibration + (only for Connectivity line devices) */ +#define GPIO_Remap_PTP_PPS ((uint32_t)0x00204000) /*!< Ethernet MAC PPS_PTS output on PB05 (only for Connectivity line devices) */ + +#define GPIO_Remap_TIM15 ((uint32_t)0x80000001) /*!< TIM15 Alternate Function mapping (only for Value line devices) */ +#define GPIO_Remap_TIM16 ((uint32_t)0x80000002) /*!< TIM16 Alternate Function mapping (only for Value line devices) */ +#define GPIO_Remap_TIM17 ((uint32_t)0x80000004) /*!< TIM17 Alternate Function mapping (only for Value line devices) */ +#define GPIO_Remap_CEC ((uint32_t)0x80000008) /*!< CEC Alternate Function mapping (only for Value line devices) */ +#define GPIO_Remap_TIM1_DMA ((uint32_t)0x80000010) /*!< TIM1 DMA requests mapping (only for Value line devices) */ + +#define GPIO_Remap_TIM9 ((uint32_t)0x80000020) /*!< TIM9 Alternate Function mapping (only for XL-density devices) */ +#define GPIO_Remap_TIM10 ((uint32_t)0x80000040) /*!< TIM10 Alternate Function mapping (only for XL-density devices) */ +#define GPIO_Remap_TIM11 ((uint32_t)0x80000080) /*!< TIM11 Alternate Function mapping (only for XL-density devices) */ +#define GPIO_Remap_TIM13 ((uint32_t)0x80000100) /*!< TIM13 Alternate Function mapping (only for High density Value line and XL-density devices) */ +#define GPIO_Remap_TIM14 ((uint32_t)0x80000200) /*!< TIM14 Alternate Function mapping (only for High density Value line and XL-density devices) */ +#define GPIO_Remap_FSMC_NADV ((uint32_t)0x80000400) /*!< FSMC_NADV Alternate Function mapping (only for High density Value line and XL-density devices) */ + +#define GPIO_Remap_TIM67_DAC_DMA ((uint32_t)0x80000800) /*!< TIM6/TIM7 and DAC DMA requests remapping (only for High density Value line devices) */ +#define GPIO_Remap_TIM12 ((uint32_t)0x80001000) /*!< TIM12 Alternate Function mapping (only for High density Value line devices) */ +#define GPIO_Remap_MISC ((uint32_t)0x80002000) /*!< Miscellaneous Remap (DMA2 Channel5 Position and DAC Trigger remapping, + only for High density Value line devices) */ + +#define IS_GPIO_REMAP(REMAP) (((REMAP) == GPIO_Remap_SPI1) || ((REMAP) == GPIO_Remap_I2C1) || \ + ((REMAP) == GPIO_Remap_USART1) || ((REMAP) == GPIO_Remap_USART2) || \ + ((REMAP) == GPIO_PartialRemap_USART3) || ((REMAP) == GPIO_FullRemap_USART3) || \ + ((REMAP) == GPIO_PartialRemap_TIM1) || ((REMAP) == GPIO_FullRemap_TIM1) || \ + ((REMAP) == GPIO_PartialRemap1_TIM2) || ((REMAP) == GPIO_PartialRemap2_TIM2) || \ + ((REMAP) == GPIO_FullRemap_TIM2) || ((REMAP) == GPIO_PartialRemap_TIM3) || \ + ((REMAP) == GPIO_FullRemap_TIM3) || ((REMAP) == GPIO_Remap_TIM4) || \ + ((REMAP) == GPIO_Remap1_CAN1) || ((REMAP) == GPIO_Remap2_CAN1) || \ + ((REMAP) == GPIO_Remap_PD01) || ((REMAP) == GPIO_Remap_TIM5CH4_LSI) || \ + ((REMAP) == GPIO_Remap_ADC1_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC1_ETRGREG) || \ + ((REMAP) == GPIO_Remap_ADC2_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC2_ETRGREG) || \ + ((REMAP) == GPIO_Remap_ETH) ||((REMAP) == GPIO_Remap_CAN2) || \ + ((REMAP) == GPIO_Remap_SWJ_NoJTRST) || ((REMAP) == GPIO_Remap_SWJ_JTAGDisable) || \ + ((REMAP) == GPIO_Remap_SWJ_Disable)|| ((REMAP) == GPIO_Remap_SPI3) || \ + ((REMAP) == GPIO_Remap_TIM2ITR1_PTP_SOF) || ((REMAP) == GPIO_Remap_PTP_PPS) || \ + ((REMAP) == GPIO_Remap_TIM15) || ((REMAP) == GPIO_Remap_TIM16) || \ + ((REMAP) == GPIO_Remap_TIM17) || ((REMAP) == GPIO_Remap_CEC) || \ + ((REMAP) == GPIO_Remap_TIM1_DMA) || ((REMAP) == GPIO_Remap_TIM9) || \ + ((REMAP) == GPIO_Remap_TIM10) || ((REMAP) == GPIO_Remap_TIM11) || \ + ((REMAP) == GPIO_Remap_TIM13) || ((REMAP) == GPIO_Remap_TIM14) || \ + ((REMAP) == GPIO_Remap_FSMC_NADV) || ((REMAP) == GPIO_Remap_TIM67_DAC_DMA) || \ + ((REMAP) == GPIO_Remap_TIM12) || ((REMAP) == GPIO_Remap_MISC)) + +/** + * @} + */ + +/** @defgroup GPIO_Port_Sources + * @{ + */ + +#define GPIO_PortSourceGPIOA ((uint8_t)0x00) +#define GPIO_PortSourceGPIOB ((uint8_t)0x01) +#define GPIO_PortSourceGPIOC ((uint8_t)0x02) +#define GPIO_PortSourceGPIOD ((uint8_t)0x03) +#define GPIO_PortSourceGPIOE ((uint8_t)0x04) +#define GPIO_PortSourceGPIOF ((uint8_t)0x05) +#define GPIO_PortSourceGPIOG ((uint8_t)0x06) +#define IS_GPIO_EVENTOUT_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOB) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOC) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOD) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOE)) + +#define IS_GPIO_EXTI_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOB) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOC) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOD) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOE) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOF) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOG)) + +/** + * @} + */ + +/** @defgroup GPIO_Pin_sources + * @{ + */ + +#define GPIO_PinSource0 ((uint8_t)0x00) +#define GPIO_PinSource1 ((uint8_t)0x01) +#define GPIO_PinSource2 ((uint8_t)0x02) +#define GPIO_PinSource3 ((uint8_t)0x03) +#define GPIO_PinSource4 ((uint8_t)0x04) +#define GPIO_PinSource5 ((uint8_t)0x05) +#define GPIO_PinSource6 ((uint8_t)0x06) +#define GPIO_PinSource7 ((uint8_t)0x07) +#define GPIO_PinSource8 ((uint8_t)0x08) +#define GPIO_PinSource9 ((uint8_t)0x09) +#define GPIO_PinSource10 ((uint8_t)0x0A) +#define GPIO_PinSource11 ((uint8_t)0x0B) +#define GPIO_PinSource12 ((uint8_t)0x0C) +#define GPIO_PinSource13 ((uint8_t)0x0D) +#define GPIO_PinSource14 ((uint8_t)0x0E) +#define GPIO_PinSource15 ((uint8_t)0x0F) + +#define IS_GPIO_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == GPIO_PinSource0) || \ + ((PINSOURCE) == GPIO_PinSource1) || \ + ((PINSOURCE) == GPIO_PinSource2) || \ + ((PINSOURCE) == GPIO_PinSource3) || \ + ((PINSOURCE) == GPIO_PinSource4) || \ + ((PINSOURCE) == GPIO_PinSource5) || \ + ((PINSOURCE) == GPIO_PinSource6) || \ + ((PINSOURCE) == GPIO_PinSource7) || \ + ((PINSOURCE) == GPIO_PinSource8) || \ + ((PINSOURCE) == GPIO_PinSource9) || \ + ((PINSOURCE) == GPIO_PinSource10) || \ + ((PINSOURCE) == GPIO_PinSource11) || \ + ((PINSOURCE) == GPIO_PinSource12) || \ + ((PINSOURCE) == GPIO_PinSource13) || \ + ((PINSOURCE) == GPIO_PinSource14) || \ + ((PINSOURCE) == GPIO_PinSource15)) + +/** + * @} + */ + +/** @defgroup Ethernet_Media_Interface + * @{ + */ +#define GPIO_ETH_MediaInterface_MII ((u32)0x00000000) +#define GPIO_ETH_MediaInterface_RMII ((u32)0x00000001) + +#define IS_GPIO_ETH_MEDIA_INTERFACE(INTERFACE) (((INTERFACE) == GPIO_ETH_MediaInterface_MII) || \ + ((INTERFACE) == GPIO_ETH_MediaInterface_RMII)) + +/** + * @} + */ +/** + * @} + */ + +/** @defgroup GPIO_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup GPIO_Exported_Functions + * @{ + */ + +void GPIO_DeInit(GPIO_TypeDef* GPIOx); +void GPIO_AFIODeInit(void); +void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct); +void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct); +uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx); +uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx); +void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal); +void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal); +void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource); +void GPIO_EventOutputCmd(FunctionalState NewState); +void GPIO_PinRemapConfig(uint32_t GPIO_Remap, FunctionalState NewState); +void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource); +void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_GPIO_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h new file mode 100644 index 0000000..60e4b14 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h @@ -0,0 +1,684 @@ +/** + ****************************************************************************** + * @file stm32f10x_i2c.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the I2C firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_I2C_H +#define __STM32F10x_I2C_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup I2C + * @{ + */ + +/** @defgroup I2C_Exported_Types + * @{ + */ + +/** + * @brief I2C Init structure definition + */ + +typedef struct +{ + uint32_t I2C_ClockSpeed; /*!< Specifies the clock frequency. + This parameter must be set to a value lower than 400kHz */ + + uint16_t I2C_Mode; /*!< Specifies the I2C mode. + This parameter can be a value of @ref I2C_mode */ + + uint16_t I2C_DutyCycle; /*!< Specifies the I2C fast mode duty cycle. + This parameter can be a value of @ref I2C_duty_cycle_in_fast_mode */ + + uint16_t I2C_OwnAddress1; /*!< Specifies the first device own address. + This parameter can be a 7-bit or 10-bit address. */ + + uint16_t I2C_Ack; /*!< Enables or disables the acknowledgement. + This parameter can be a value of @ref I2C_acknowledgement */ + + uint16_t I2C_AcknowledgedAddress; /*!< Specifies if 7-bit or 10-bit address is acknowledged. + This parameter can be a value of @ref I2C_acknowledged_address */ +}I2C_InitTypeDef; + +/** + * @} + */ + + +/** @defgroup I2C_Exported_Constants + * @{ + */ + +#define IS_I2C_ALL_PERIPH(PERIPH) (((PERIPH) == I2C1) || \ + ((PERIPH) == I2C2)) +/** @defgroup I2C_mode + * @{ + */ + +#define I2C_Mode_I2C ((uint16_t)0x0000) +#define I2C_Mode_SMBusDevice ((uint16_t)0x0002) +#define I2C_Mode_SMBusHost ((uint16_t)0x000A) +#define IS_I2C_MODE(MODE) (((MODE) == I2C_Mode_I2C) || \ + ((MODE) == I2C_Mode_SMBusDevice) || \ + ((MODE) == I2C_Mode_SMBusHost)) +/** + * @} + */ + +/** @defgroup I2C_duty_cycle_in_fast_mode + * @{ + */ + +#define I2C_DutyCycle_16_9 ((uint16_t)0x4000) /*!< I2C fast mode Tlow/Thigh = 16/9 */ +#define I2C_DutyCycle_2 ((uint16_t)0xBFFF) /*!< I2C fast mode Tlow/Thigh = 2 */ +#define IS_I2C_DUTY_CYCLE(CYCLE) (((CYCLE) == I2C_DutyCycle_16_9) || \ + ((CYCLE) == I2C_DutyCycle_2)) +/** + * @} + */ + +/** @defgroup I2C_acknowledgement + * @{ + */ + +#define I2C_Ack_Enable ((uint16_t)0x0400) +#define I2C_Ack_Disable ((uint16_t)0x0000) +#define IS_I2C_ACK_STATE(STATE) (((STATE) == I2C_Ack_Enable) || \ + ((STATE) == I2C_Ack_Disable)) +/** + * @} + */ + +/** @defgroup I2C_transfer_direction + * @{ + */ + +#define I2C_Direction_Transmitter ((uint8_t)0x00) +#define I2C_Direction_Receiver ((uint8_t)0x01) +#define IS_I2C_DIRECTION(DIRECTION) (((DIRECTION) == I2C_Direction_Transmitter) || \ + ((DIRECTION) == I2C_Direction_Receiver)) +/** + * @} + */ + +/** @defgroup I2C_acknowledged_address + * @{ + */ + +#define I2C_AcknowledgedAddress_7bit ((uint16_t)0x4000) +#define I2C_AcknowledgedAddress_10bit ((uint16_t)0xC000) +#define IS_I2C_ACKNOWLEDGE_ADDRESS(ADDRESS) (((ADDRESS) == I2C_AcknowledgedAddress_7bit) || \ + ((ADDRESS) == I2C_AcknowledgedAddress_10bit)) +/** + * @} + */ + +/** @defgroup I2C_registers + * @{ + */ + +#define I2C_Register_CR1 ((uint8_t)0x00) +#define I2C_Register_CR2 ((uint8_t)0x04) +#define I2C_Register_OAR1 ((uint8_t)0x08) +#define I2C_Register_OAR2 ((uint8_t)0x0C) +#define I2C_Register_DR ((uint8_t)0x10) +#define I2C_Register_SR1 ((uint8_t)0x14) +#define I2C_Register_SR2 ((uint8_t)0x18) +#define I2C_Register_CCR ((uint8_t)0x1C) +#define I2C_Register_TRISE ((uint8_t)0x20) +#define IS_I2C_REGISTER(REGISTER) (((REGISTER) == I2C_Register_CR1) || \ + ((REGISTER) == I2C_Register_CR2) || \ + ((REGISTER) == I2C_Register_OAR1) || \ + ((REGISTER) == I2C_Register_OAR2) || \ + ((REGISTER) == I2C_Register_DR) || \ + ((REGISTER) == I2C_Register_SR1) || \ + ((REGISTER) == I2C_Register_SR2) || \ + ((REGISTER) == I2C_Register_CCR) || \ + ((REGISTER) == I2C_Register_TRISE)) +/** + * @} + */ + +/** @defgroup I2C_SMBus_alert_pin_level + * @{ + */ + +#define I2C_SMBusAlert_Low ((uint16_t)0x2000) +#define I2C_SMBusAlert_High ((uint16_t)0xDFFF) +#define IS_I2C_SMBUS_ALERT(ALERT) (((ALERT) == I2C_SMBusAlert_Low) || \ + ((ALERT) == I2C_SMBusAlert_High)) +/** + * @} + */ + +/** @defgroup I2C_PEC_position + * @{ + */ + +#define I2C_PECPosition_Next ((uint16_t)0x0800) +#define I2C_PECPosition_Current ((uint16_t)0xF7FF) +#define IS_I2C_PEC_POSITION(POSITION) (((POSITION) == I2C_PECPosition_Next) || \ + ((POSITION) == I2C_PECPosition_Current)) +/** + * @} + */ + +/** @defgroup I2C_NCAK_position + * @{ + */ + +#define I2C_NACKPosition_Next ((uint16_t)0x0800) +#define I2C_NACKPosition_Current ((uint16_t)0xF7FF) +#define IS_I2C_NACK_POSITION(POSITION) (((POSITION) == I2C_NACKPosition_Next) || \ + ((POSITION) == I2C_NACKPosition_Current)) +/** + * @} + */ + +/** @defgroup I2C_interrupts_definition + * @{ + */ + +#define I2C_IT_BUF ((uint16_t)0x0400) +#define I2C_IT_EVT ((uint16_t)0x0200) +#define I2C_IT_ERR ((uint16_t)0x0100) +#define IS_I2C_CONFIG_IT(IT) ((((IT) & (uint16_t)0xF8FF) == 0x00) && ((IT) != 0x00)) +/** + * @} + */ + +/** @defgroup I2C_interrupts_definition + * @{ + */ + +#define I2C_IT_SMBALERT ((uint32_t)0x01008000) +#define I2C_IT_TIMEOUT ((uint32_t)0x01004000) +#define I2C_IT_PECERR ((uint32_t)0x01001000) +#define I2C_IT_OVR ((uint32_t)0x01000800) +#define I2C_IT_AF ((uint32_t)0x01000400) +#define I2C_IT_ARLO ((uint32_t)0x01000200) +#define I2C_IT_BERR ((uint32_t)0x01000100) +#define I2C_IT_TXE ((uint32_t)0x06000080) +#define I2C_IT_RXNE ((uint32_t)0x06000040) +#define I2C_IT_STOPF ((uint32_t)0x02000010) +#define I2C_IT_ADD10 ((uint32_t)0x02000008) +#define I2C_IT_BTF ((uint32_t)0x02000004) +#define I2C_IT_ADDR ((uint32_t)0x02000002) +#define I2C_IT_SB ((uint32_t)0x02000001) + +#define IS_I2C_CLEAR_IT(IT) ((((IT) & (uint16_t)0x20FF) == 0x00) && ((IT) != (uint16_t)0x00)) + +#define IS_I2C_GET_IT(IT) (((IT) == I2C_IT_SMBALERT) || ((IT) == I2C_IT_TIMEOUT) || \ + ((IT) == I2C_IT_PECERR) || ((IT) == I2C_IT_OVR) || \ + ((IT) == I2C_IT_AF) || ((IT) == I2C_IT_ARLO) || \ + ((IT) == I2C_IT_BERR) || ((IT) == I2C_IT_TXE) || \ + ((IT) == I2C_IT_RXNE) || ((IT) == I2C_IT_STOPF) || \ + ((IT) == I2C_IT_ADD10) || ((IT) == I2C_IT_BTF) || \ + ((IT) == I2C_IT_ADDR) || ((IT) == I2C_IT_SB)) +/** + * @} + */ + +/** @defgroup I2C_flags_definition + * @{ + */ + +/** + * @brief SR2 register flags + */ + +#define I2C_FLAG_DUALF ((uint32_t)0x00800000) +#define I2C_FLAG_SMBHOST ((uint32_t)0x00400000) +#define I2C_FLAG_SMBDEFAULT ((uint32_t)0x00200000) +#define I2C_FLAG_GENCALL ((uint32_t)0x00100000) +#define I2C_FLAG_TRA ((uint32_t)0x00040000) +#define I2C_FLAG_BUSY ((uint32_t)0x00020000) +#define I2C_FLAG_MSL ((uint32_t)0x00010000) + +/** + * @brief SR1 register flags + */ + +#define I2C_FLAG_SMBALERT ((uint32_t)0x10008000) +#define I2C_FLAG_TIMEOUT ((uint32_t)0x10004000) +#define I2C_FLAG_PECERR ((uint32_t)0x10001000) +#define I2C_FLAG_OVR ((uint32_t)0x10000800) +#define I2C_FLAG_AF ((uint32_t)0x10000400) +#define I2C_FLAG_ARLO ((uint32_t)0x10000200) +#define I2C_FLAG_BERR ((uint32_t)0x10000100) +#define I2C_FLAG_TXE ((uint32_t)0x10000080) +#define I2C_FLAG_RXNE ((uint32_t)0x10000040) +#define I2C_FLAG_STOPF ((uint32_t)0x10000010) +#define I2C_FLAG_ADD10 ((uint32_t)0x10000008) +#define I2C_FLAG_BTF ((uint32_t)0x10000004) +#define I2C_FLAG_ADDR ((uint32_t)0x10000002) +#define I2C_FLAG_SB ((uint32_t)0x10000001) + +#define IS_I2C_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0x20FF) == 0x00) && ((FLAG) != (uint16_t)0x00)) + +#define IS_I2C_GET_FLAG(FLAG) (((FLAG) == I2C_FLAG_DUALF) || ((FLAG) == I2C_FLAG_SMBHOST) || \ + ((FLAG) == I2C_FLAG_SMBDEFAULT) || ((FLAG) == I2C_FLAG_GENCALL) || \ + ((FLAG) == I2C_FLAG_TRA) || ((FLAG) == I2C_FLAG_BUSY) || \ + ((FLAG) == I2C_FLAG_MSL) || ((FLAG) == I2C_FLAG_SMBALERT) || \ + ((FLAG) == I2C_FLAG_TIMEOUT) || ((FLAG) == I2C_FLAG_PECERR) || \ + ((FLAG) == I2C_FLAG_OVR) || ((FLAG) == I2C_FLAG_AF) || \ + ((FLAG) == I2C_FLAG_ARLO) || ((FLAG) == I2C_FLAG_BERR) || \ + ((FLAG) == I2C_FLAG_TXE) || ((FLAG) == I2C_FLAG_RXNE) || \ + ((FLAG) == I2C_FLAG_STOPF) || ((FLAG) == I2C_FLAG_ADD10) || \ + ((FLAG) == I2C_FLAG_BTF) || ((FLAG) == I2C_FLAG_ADDR) || \ + ((FLAG) == I2C_FLAG_SB)) +/** + * @} + */ + +/** @defgroup I2C_Events + * @{ + */ + +/*======================================== + + I2C Master Events (Events grouped in order of communication) + ==========================================*/ +/** + * @brief Communication start + * + * After sending the START condition (I2C_GenerateSTART() function) the master + * has to wait for this event. It means that the Start condition has been correctly + * released on the I2C bus (the bus is free, no other devices is communicating). + * + */ +/* --EV5 */ +#define I2C_EVENT_MASTER_MODE_SELECT ((uint32_t)0x00030001) /* BUSY, MSL and SB flag */ + +/** + * @brief Address Acknowledge + * + * After checking on EV5 (start condition correctly released on the bus), the + * master sends the address of the slave(s) with which it will communicate + * (I2C_Send7bitAddress() function, it also determines the direction of the communication: + * Master transmitter or Receiver). Then the master has to wait that a slave acknowledges + * his address. If an acknowledge is sent on the bus, one of the following events will + * be set: + * + * 1) In case of Master Receiver (7-bit addressing): the I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED + * event is set. + * + * 2) In case of Master Transmitter (7-bit addressing): the I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED + * is set + * + * 3) In case of 10-Bit addressing mode, the master (just after generating the START + * and checking on EV5) has to send the header of 10-bit addressing mode (I2C_SendData() + * function). Then master should wait on EV9. It means that the 10-bit addressing + * header has been correctly sent on the bus. Then master should send the second part of + * the 10-bit address (LSB) using the function I2C_Send7bitAddress(). Then master + * should wait for event EV6. + * + */ + +/* --EV6 */ +#define I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED ((uint32_t)0x00070082) /* BUSY, MSL, ADDR, TXE and TRA flags */ +#define I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED ((uint32_t)0x00030002) /* BUSY, MSL and ADDR flags */ +/* --EV9 */ +#define I2C_EVENT_MASTER_MODE_ADDRESS10 ((uint32_t)0x00030008) /* BUSY, MSL and ADD10 flags */ + +/** + * @brief Communication events + * + * If a communication is established (START condition generated and slave address + * acknowledged) then the master has to check on one of the following events for + * communication procedures: + * + * 1) Master Receiver mode: The master has to wait on the event EV7 then to read + * the data received from the slave (I2C_ReceiveData() function). + * + * 2) Master Transmitter mode: The master has to send data (I2C_SendData() + * function) then to wait on event EV8 or EV8_2. + * These two events are similar: + * - EV8 means that the data has been written in the data register and is + * being shifted out. + * - EV8_2 means that the data has been physically shifted out and output + * on the bus. + * In most cases, using EV8 is sufficient for the application. + * Using EV8_2 leads to a slower communication but ensure more reliable test. + * EV8_2 is also more suitable than EV8 for testing on the last data transmission + * (before Stop condition generation). + * + * @note In case the user software does not guarantee that this event EV7 is + * managed before the current byte end of transfer, then user may check on EV7 + * and BTF flag at the same time (ie. (I2C_EVENT_MASTER_BYTE_RECEIVED | I2C_FLAG_BTF)). + * In this case the communication may be slower. + * + */ + +/* Master RECEIVER mode -----------------------------*/ +/* --EV7 */ +#define I2C_EVENT_MASTER_BYTE_RECEIVED ((uint32_t)0x00030040) /* BUSY, MSL and RXNE flags */ + +/* Master TRANSMITTER mode --------------------------*/ +/* --EV8 */ +#define I2C_EVENT_MASTER_BYTE_TRANSMITTING ((uint32_t)0x00070080) /* TRA, BUSY, MSL, TXE flags */ +/* --EV8_2 */ +#define I2C_EVENT_MASTER_BYTE_TRANSMITTED ((uint32_t)0x00070084) /* TRA, BUSY, MSL, TXE and BTF flags */ + + +/*======================================== + + I2C Slave Events (Events grouped in order of communication) + ==========================================*/ + +/** + * @brief Communication start events + * + * Wait on one of these events at the start of the communication. It means that + * the I2C peripheral detected a Start condition on the bus (generated by master + * device) followed by the peripheral address. The peripheral generates an ACK + * condition on the bus (if the acknowledge feature is enabled through function + * I2C_AcknowledgeConfig()) and the events listed above are set : + * + * 1) In normal case (only one address managed by the slave), when the address + * sent by the master matches the own address of the peripheral (configured by + * I2C_OwnAddress1 field) the I2C_EVENT_SLAVE_XXX_ADDRESS_MATCHED event is set + * (where XXX could be TRANSMITTER or RECEIVER). + * + * 2) In case the address sent by the master matches the second address of the + * peripheral (configured by the function I2C_OwnAddress2Config() and enabled + * by the function I2C_DualAddressCmd()) the events I2C_EVENT_SLAVE_XXX_SECONDADDRESS_MATCHED + * (where XXX could be TRANSMITTER or RECEIVER) are set. + * + * 3) In case the address sent by the master is General Call (address 0x00) and + * if the General Call is enabled for the peripheral (using function I2C_GeneralCallCmd()) + * the following event is set I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED. + * + */ + +/* --EV1 (all the events below are variants of EV1) */ +/* 1) Case of One Single Address managed by the slave */ +#define I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED ((uint32_t)0x00020002) /* BUSY and ADDR flags */ +#define I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED ((uint32_t)0x00060082) /* TRA, BUSY, TXE and ADDR flags */ + +/* 2) Case of Dual address managed by the slave */ +#define I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED ((uint32_t)0x00820000) /* DUALF and BUSY flags */ +#define I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED ((uint32_t)0x00860080) /* DUALF, TRA, BUSY and TXE flags */ + +/* 3) Case of General Call enabled for the slave */ +#define I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED ((uint32_t)0x00120000) /* GENCALL and BUSY flags */ + +/** + * @brief Communication events + * + * Wait on one of these events when EV1 has already been checked and: + * + * - Slave RECEIVER mode: + * - EV2: When the application is expecting a data byte to be received. + * - EV4: When the application is expecting the end of the communication: master + * sends a stop condition and data transmission is stopped. + * + * - Slave Transmitter mode: + * - EV3: When a byte has been transmitted by the slave and the application is expecting + * the end of the byte transmission. The two events I2C_EVENT_SLAVE_BYTE_TRANSMITTED and + * I2C_EVENT_SLAVE_BYTE_TRANSMITTING are similar. The second one can optionally be + * used when the user software doesn't guarantee the EV3 is managed before the + * current byte end of transfer. + * - EV3_2: When the master sends a NACK in order to tell slave that data transmission + * shall end (before sending the STOP condition). In this case slave has to stop sending + * data bytes and expect a Stop condition on the bus. + * + * @note In case the user software does not guarantee that the event EV2 is + * managed before the current byte end of transfer, then user may check on EV2 + * and BTF flag at the same time (ie. (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_BTF)). + * In this case the communication may be slower. + * + */ + +/* Slave RECEIVER mode --------------------------*/ +/* --EV2 */ +#define I2C_EVENT_SLAVE_BYTE_RECEIVED ((uint32_t)0x00020040) /* BUSY and RXNE flags */ +/* --EV4 */ +#define I2C_EVENT_SLAVE_STOP_DETECTED ((uint32_t)0x00000010) /* STOPF flag */ + +/* Slave TRANSMITTER mode -----------------------*/ +/* --EV3 */ +#define I2C_EVENT_SLAVE_BYTE_TRANSMITTED ((uint32_t)0x00060084) /* TRA, BUSY, TXE and BTF flags */ +#define I2C_EVENT_SLAVE_BYTE_TRANSMITTING ((uint32_t)0x00060080) /* TRA, BUSY and TXE flags */ +/* --EV3_2 */ +#define I2C_EVENT_SLAVE_ACK_FAILURE ((uint32_t)0x00000400) /* AF flag */ + +/*=========================== End of Events Description ==========================================*/ + +#define IS_I2C_EVENT(EVENT) (((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_BYTE_RECEIVED) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF)) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL)) || \ + ((EVENT) == I2C_EVENT_SLAVE_BYTE_TRANSMITTED) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF)) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL)) || \ + ((EVENT) == I2C_EVENT_SLAVE_STOP_DETECTED) || \ + ((EVENT) == I2C_EVENT_MASTER_MODE_SELECT) || \ + ((EVENT) == I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED) || \ + ((EVENT) == I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED) || \ + ((EVENT) == I2C_EVENT_MASTER_BYTE_RECEIVED) || \ + ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTED) || \ + ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTING) || \ + ((EVENT) == I2C_EVENT_MASTER_MODE_ADDRESS10) || \ + ((EVENT) == I2C_EVENT_SLAVE_ACK_FAILURE)) +/** + * @} + */ + +/** @defgroup I2C_own_address1 + * @{ + */ + +#define IS_I2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x3FF) +/** + * @} + */ + +/** @defgroup I2C_clock_speed + * @{ + */ + +#define IS_I2C_CLOCK_SPEED(SPEED) (((SPEED) >= 0x1) && ((SPEED) <= 400000)) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup I2C_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup I2C_Exported_Functions + * @{ + */ + +void I2C_DeInit(I2C_TypeDef* I2Cx); +void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct); +void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct); +void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address); +void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState); +void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data); +uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx); +void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction); +uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register); +void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_NACKPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_NACKPosition); +void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert); +void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition); +void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState); +uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx); +void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle); + +/** + * @brief + **************************************************************************************** + * + * I2C State Monitoring Functions + * + **************************************************************************************** + * This I2C driver provides three different ways for I2C state monitoring + * depending on the application requirements and constraints: + * + * + * 1) Basic state monitoring: + * Using I2C_CheckEvent() function: + * It compares the status registers (SR1 and SR2) content to a given event + * (can be the combination of one or more flags). + * It returns SUCCESS if the current status includes the given flags + * and returns ERROR if one or more flags are missing in the current status. + * - When to use: + * - This function is suitable for most applications as well as for startup + * activity since the events are fully described in the product reference manual + * (RM0008). + * - It is also suitable for users who need to define their own events. + * - Limitations: + * - If an error occurs (ie. error flags are set besides to the monitored flags), + * the I2C_CheckEvent() function may return SUCCESS despite the communication + * hold or corrupted real state. + * In this case, it is advised to use error interrupts to monitor the error + * events and handle them in the interrupt IRQ handler. + * + * @note + * For error management, it is advised to use the following functions: + * - I2C_ITConfig() to configure and enable the error interrupts (I2C_IT_ERR). + * - I2Cx_ER_IRQHandler() which is called when the error interrupt occurs. + * Where x is the peripheral instance (I2C1, I2C2 ...) + * - I2C_GetFlagStatus() or I2C_GetITStatus() to be called into I2Cx_ER_IRQHandler() + * in order to determine which error occurred. + * - I2C_ClearFlag() or I2C_ClearITPendingBit() and/or I2C_SoftwareResetCmd() + * and/or I2C_GenerateStop() in order to clear the error flag and source, + * and return to correct communication status. + * + * + * 2) Advanced state monitoring: + * Using the function I2C_GetLastEvent() which returns the image of both status + * registers in a single word (uint32_t) (Status Register 2 value is shifted left + * by 16 bits and concatenated to Status Register 1). + * - When to use: + * - This function is suitable for the same applications above but it allows to + * overcome the limitations of I2C_GetFlagStatus() function (see below). + * The returned value could be compared to events already defined in the + * library (stm32f10x_i2c.h) or to custom values defined by user. + * - This function is suitable when multiple flags are monitored at the same time. + * - At the opposite of I2C_CheckEvent() function, this function allows user to + * choose when an event is accepted (when all events flags are set and no + * other flags are set or just when the needed flags are set like + * I2C_CheckEvent() function). + * - Limitations: + * - User may need to define his own events. + * - Same remark concerning the error management is applicable for this + * function if user decides to check only regular communication flags (and + * ignores error flags). + * + * + * 3) Flag-based state monitoring: + * Using the function I2C_GetFlagStatus() which simply returns the status of + * one single flag (ie. I2C_FLAG_RXNE ...). + * - When to use: + * - This function could be used for specific applications or in debug phase. + * - It is suitable when only one flag checking is needed (most I2C events + * are monitored through multiple flags). + * - Limitations: + * - When calling this function, the Status register is accessed. Some flags are + * cleared when the status register is accessed. So checking the status + * of one Flag, may clear other ones. + * - Function may need to be called twice or more in order to monitor one + * single event. + * + */ + +/** + * + * 1) Basic state monitoring + ******************************************************************************* + */ +ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT); +/** + * + * 2) Advanced state monitoring + ******************************************************************************* + */ +uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx); +/** + * + * 3) Flag-based state monitoring + ******************************************************************************* + */ +FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG); +/** + * + ******************************************************************************* + */ + +void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG); +ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT); +void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_I2C_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h new file mode 100644 index 0000000..25b0bb5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h @@ -0,0 +1,140 @@ +/** + ****************************************************************************** + * @file stm32f10x_iwdg.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the IWDG + * firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_IWDG_H +#define __STM32F10x_IWDG_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup IWDG + * @{ + */ + +/** @defgroup IWDG_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Exported_Constants + * @{ + */ + +/** @defgroup IWDG_WriteAccess + * @{ + */ + +#define IWDG_WriteAccess_Enable ((uint16_t)0x5555) +#define IWDG_WriteAccess_Disable ((uint16_t)0x0000) +#define IS_IWDG_WRITE_ACCESS(ACCESS) (((ACCESS) == IWDG_WriteAccess_Enable) || \ + ((ACCESS) == IWDG_WriteAccess_Disable)) +/** + * @} + */ + +/** @defgroup IWDG_prescaler + * @{ + */ + +#define IWDG_Prescaler_4 ((uint8_t)0x00) +#define IWDG_Prescaler_8 ((uint8_t)0x01) +#define IWDG_Prescaler_16 ((uint8_t)0x02) +#define IWDG_Prescaler_32 ((uint8_t)0x03) +#define IWDG_Prescaler_64 ((uint8_t)0x04) +#define IWDG_Prescaler_128 ((uint8_t)0x05) +#define IWDG_Prescaler_256 ((uint8_t)0x06) +#define IS_IWDG_PRESCALER(PRESCALER) (((PRESCALER) == IWDG_Prescaler_4) || \ + ((PRESCALER) == IWDG_Prescaler_8) || \ + ((PRESCALER) == IWDG_Prescaler_16) || \ + ((PRESCALER) == IWDG_Prescaler_32) || \ + ((PRESCALER) == IWDG_Prescaler_64) || \ + ((PRESCALER) == IWDG_Prescaler_128)|| \ + ((PRESCALER) == IWDG_Prescaler_256)) +/** + * @} + */ + +/** @defgroup IWDG_Flag + * @{ + */ + +#define IWDG_FLAG_PVU ((uint16_t)0x0001) +#define IWDG_FLAG_RVU ((uint16_t)0x0002) +#define IS_IWDG_FLAG(FLAG) (((FLAG) == IWDG_FLAG_PVU) || ((FLAG) == IWDG_FLAG_RVU)) +#define IS_IWDG_RELOAD(RELOAD) ((RELOAD) <= 0xFFF) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup IWDG_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Exported_Functions + * @{ + */ + +void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess); +void IWDG_SetPrescaler(uint8_t IWDG_Prescaler); +void IWDG_SetReload(uint16_t Reload); +void IWDG_ReloadCounter(void); +void IWDG_Enable(void); +FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_IWDG_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h new file mode 100644 index 0000000..1c025e2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h @@ -0,0 +1,156 @@ +/** + ****************************************************************************** + * @file stm32f10x_pwr.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the PWR firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_PWR_H +#define __STM32F10x_PWR_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup PWR + * @{ + */ + +/** @defgroup PWR_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Exported_Constants + * @{ + */ + +/** @defgroup PVD_detection_level + * @{ + */ + +#define PWR_PVDLevel_2V2 ((uint32_t)0x00000000) +#define PWR_PVDLevel_2V3 ((uint32_t)0x00000020) +#define PWR_PVDLevel_2V4 ((uint32_t)0x00000040) +#define PWR_PVDLevel_2V5 ((uint32_t)0x00000060) +#define PWR_PVDLevel_2V6 ((uint32_t)0x00000080) +#define PWR_PVDLevel_2V7 ((uint32_t)0x000000A0) +#define PWR_PVDLevel_2V8 ((uint32_t)0x000000C0) +#define PWR_PVDLevel_2V9 ((uint32_t)0x000000E0) +#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLevel_2V2) || ((LEVEL) == PWR_PVDLevel_2V3)|| \ + ((LEVEL) == PWR_PVDLevel_2V4) || ((LEVEL) == PWR_PVDLevel_2V5)|| \ + ((LEVEL) == PWR_PVDLevel_2V6) || ((LEVEL) == PWR_PVDLevel_2V7)|| \ + ((LEVEL) == PWR_PVDLevel_2V8) || ((LEVEL) == PWR_PVDLevel_2V9)) +/** + * @} + */ + +/** @defgroup Regulator_state_is_STOP_mode + * @{ + */ + +#define PWR_Regulator_ON ((uint32_t)0x00000000) +#define PWR_Regulator_LowPower ((uint32_t)0x00000001) +#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_Regulator_ON) || \ + ((REGULATOR) == PWR_Regulator_LowPower)) +/** + * @} + */ + +/** @defgroup STOP_mode_entry + * @{ + */ + +#define PWR_STOPEntry_WFI ((uint8_t)0x01) +#define PWR_STOPEntry_WFE ((uint8_t)0x02) +#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPEntry_WFI) || ((ENTRY) == PWR_STOPEntry_WFE)) + +/** + * @} + */ + +/** @defgroup PWR_Flag + * @{ + */ + +#define PWR_FLAG_WU ((uint32_t)0x00000001) +#define PWR_FLAG_SB ((uint32_t)0x00000002) +#define PWR_FLAG_PVDO ((uint32_t)0x00000004) +#define IS_PWR_GET_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB) || \ + ((FLAG) == PWR_FLAG_PVDO)) + +#define IS_PWR_CLEAR_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB)) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup PWR_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Exported_Functions + * @{ + */ + +void PWR_DeInit(void); +void PWR_BackupAccessCmd(FunctionalState NewState); +void PWR_PVDCmd(FunctionalState NewState); +void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel); +void PWR_WakeUpPinCmd(FunctionalState NewState); +void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry); +void PWR_EnterSTANDBYMode(void); +FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG); +void PWR_ClearFlag(uint32_t PWR_FLAG); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_PWR_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h new file mode 100644 index 0000000..1149c34 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h @@ -0,0 +1,727 @@ +/** + ****************************************************************************** + * @file stm32f10x_rcc.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the RCC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_RCC_H +#define __STM32F10x_RCC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup RCC + * @{ + */ + +/** @defgroup RCC_Exported_Types + * @{ + */ + +typedef struct +{ + uint32_t SYSCLK_Frequency; /*!< returns SYSCLK clock frequency expressed in Hz */ + uint32_t HCLK_Frequency; /*!< returns HCLK clock frequency expressed in Hz */ + uint32_t PCLK1_Frequency; /*!< returns PCLK1 clock frequency expressed in Hz */ + uint32_t PCLK2_Frequency; /*!< returns PCLK2 clock frequency expressed in Hz */ + uint32_t ADCCLK_Frequency; /*!< returns ADCCLK clock frequency expressed in Hz */ +}RCC_ClocksTypeDef; + +/** + * @} + */ + +/** @defgroup RCC_Exported_Constants + * @{ + */ + +/** @defgroup HSE_configuration + * @{ + */ + +#define RCC_HSE_OFF ((uint32_t)0x00000000) +#define RCC_HSE_ON ((uint32_t)0x00010000) +#define RCC_HSE_Bypass ((uint32_t)0x00040000) +#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \ + ((HSE) == RCC_HSE_Bypass)) + +/** + * @} + */ + +/** @defgroup PLL_entry_clock_source + * @{ + */ + +#define RCC_PLLSource_HSI_Div2 ((uint32_t)0x00000000) + +#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) && !defined (STM32F10X_CL) + #define RCC_PLLSource_HSE_Div1 ((uint32_t)0x00010000) + #define RCC_PLLSource_HSE_Div2 ((uint32_t)0x00030000) + #define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \ + ((SOURCE) == RCC_PLLSource_HSE_Div1) || \ + ((SOURCE) == RCC_PLLSource_HSE_Div2)) +#else + #define RCC_PLLSource_PREDIV1 ((uint32_t)0x00010000) + #define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \ + ((SOURCE) == RCC_PLLSource_PREDIV1)) +#endif /* STM32F10X_CL */ + +/** + * @} + */ + +/** @defgroup PLL_multiplication_factor + * @{ + */ +#ifndef STM32F10X_CL + #define RCC_PLLMul_2 ((uint32_t)0x00000000) + #define RCC_PLLMul_3 ((uint32_t)0x00040000) + #define RCC_PLLMul_4 ((uint32_t)0x00080000) + #define RCC_PLLMul_5 ((uint32_t)0x000C0000) + #define RCC_PLLMul_6 ((uint32_t)0x00100000) + #define RCC_PLLMul_7 ((uint32_t)0x00140000) + #define RCC_PLLMul_8 ((uint32_t)0x00180000) + #define RCC_PLLMul_9 ((uint32_t)0x001C0000) + #define RCC_PLLMul_10 ((uint32_t)0x00200000) + #define RCC_PLLMul_11 ((uint32_t)0x00240000) + #define RCC_PLLMul_12 ((uint32_t)0x00280000) + #define RCC_PLLMul_13 ((uint32_t)0x002C0000) + #define RCC_PLLMul_14 ((uint32_t)0x00300000) + #define RCC_PLLMul_15 ((uint32_t)0x00340000) + #define RCC_PLLMul_16 ((uint32_t)0x00380000) + #define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_2) || ((MUL) == RCC_PLLMul_3) || \ + ((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \ + ((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \ + ((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \ + ((MUL) == RCC_PLLMul_10) || ((MUL) == RCC_PLLMul_11) || \ + ((MUL) == RCC_PLLMul_12) || ((MUL) == RCC_PLLMul_13) || \ + ((MUL) == RCC_PLLMul_14) || ((MUL) == RCC_PLLMul_15) || \ + ((MUL) == RCC_PLLMul_16)) + +#else + #define RCC_PLLMul_4 ((uint32_t)0x00080000) + #define RCC_PLLMul_5 ((uint32_t)0x000C0000) + #define RCC_PLLMul_6 ((uint32_t)0x00100000) + #define RCC_PLLMul_7 ((uint32_t)0x00140000) + #define RCC_PLLMul_8 ((uint32_t)0x00180000) + #define RCC_PLLMul_9 ((uint32_t)0x001C0000) + #define RCC_PLLMul_6_5 ((uint32_t)0x00340000) + + #define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \ + ((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \ + ((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \ + ((MUL) == RCC_PLLMul_6_5)) +#endif /* STM32F10X_CL */ +/** + * @} + */ + +/** @defgroup PREDIV1_division_factor + * @{ + */ +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) + #define RCC_PREDIV1_Div1 ((uint32_t)0x00000000) + #define RCC_PREDIV1_Div2 ((uint32_t)0x00000001) + #define RCC_PREDIV1_Div3 ((uint32_t)0x00000002) + #define RCC_PREDIV1_Div4 ((uint32_t)0x00000003) + #define RCC_PREDIV1_Div5 ((uint32_t)0x00000004) + #define RCC_PREDIV1_Div6 ((uint32_t)0x00000005) + #define RCC_PREDIV1_Div7 ((uint32_t)0x00000006) + #define RCC_PREDIV1_Div8 ((uint32_t)0x00000007) + #define RCC_PREDIV1_Div9 ((uint32_t)0x00000008) + #define RCC_PREDIV1_Div10 ((uint32_t)0x00000009) + #define RCC_PREDIV1_Div11 ((uint32_t)0x0000000A) + #define RCC_PREDIV1_Div12 ((uint32_t)0x0000000B) + #define RCC_PREDIV1_Div13 ((uint32_t)0x0000000C) + #define RCC_PREDIV1_Div14 ((uint32_t)0x0000000D) + #define RCC_PREDIV1_Div15 ((uint32_t)0x0000000E) + #define RCC_PREDIV1_Div16 ((uint32_t)0x0000000F) + + #define IS_RCC_PREDIV1(PREDIV1) (((PREDIV1) == RCC_PREDIV1_Div1) || ((PREDIV1) == RCC_PREDIV1_Div2) || \ + ((PREDIV1) == RCC_PREDIV1_Div3) || ((PREDIV1) == RCC_PREDIV1_Div4) || \ + ((PREDIV1) == RCC_PREDIV1_Div5) || ((PREDIV1) == RCC_PREDIV1_Div6) || \ + ((PREDIV1) == RCC_PREDIV1_Div7) || ((PREDIV1) == RCC_PREDIV1_Div8) || \ + ((PREDIV1) == RCC_PREDIV1_Div9) || ((PREDIV1) == RCC_PREDIV1_Div10) || \ + ((PREDIV1) == RCC_PREDIV1_Div11) || ((PREDIV1) == RCC_PREDIV1_Div12) || \ + ((PREDIV1) == RCC_PREDIV1_Div13) || ((PREDIV1) == RCC_PREDIV1_Div14) || \ + ((PREDIV1) == RCC_PREDIV1_Div15) || ((PREDIV1) == RCC_PREDIV1_Div16)) +#endif +/** + * @} + */ + + +/** @defgroup PREDIV1_clock_source + * @{ + */ +#ifdef STM32F10X_CL +/* PREDIV1 clock source (for STM32 connectivity line devices) */ + #define RCC_PREDIV1_Source_HSE ((uint32_t)0x00000000) + #define RCC_PREDIV1_Source_PLL2 ((uint32_t)0x00010000) + + #define IS_RCC_PREDIV1_SOURCE(SOURCE) (((SOURCE) == RCC_PREDIV1_Source_HSE) || \ + ((SOURCE) == RCC_PREDIV1_Source_PLL2)) +#elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/* PREDIV1 clock source (for STM32 Value line devices) */ + #define RCC_PREDIV1_Source_HSE ((uint32_t)0x00000000) + + #define IS_RCC_PREDIV1_SOURCE(SOURCE) (((SOURCE) == RCC_PREDIV1_Source_HSE)) +#endif +/** + * @} + */ + +#ifdef STM32F10X_CL +/** @defgroup PREDIV2_division_factor + * @{ + */ + + #define RCC_PREDIV2_Div1 ((uint32_t)0x00000000) + #define RCC_PREDIV2_Div2 ((uint32_t)0x00000010) + #define RCC_PREDIV2_Div3 ((uint32_t)0x00000020) + #define RCC_PREDIV2_Div4 ((uint32_t)0x00000030) + #define RCC_PREDIV2_Div5 ((uint32_t)0x00000040) + #define RCC_PREDIV2_Div6 ((uint32_t)0x00000050) + #define RCC_PREDIV2_Div7 ((uint32_t)0x00000060) + #define RCC_PREDIV2_Div8 ((uint32_t)0x00000070) + #define RCC_PREDIV2_Div9 ((uint32_t)0x00000080) + #define RCC_PREDIV2_Div10 ((uint32_t)0x00000090) + #define RCC_PREDIV2_Div11 ((uint32_t)0x000000A0) + #define RCC_PREDIV2_Div12 ((uint32_t)0x000000B0) + #define RCC_PREDIV2_Div13 ((uint32_t)0x000000C0) + #define RCC_PREDIV2_Div14 ((uint32_t)0x000000D0) + #define RCC_PREDIV2_Div15 ((uint32_t)0x000000E0) + #define RCC_PREDIV2_Div16 ((uint32_t)0x000000F0) + + #define IS_RCC_PREDIV2(PREDIV2) (((PREDIV2) == RCC_PREDIV2_Div1) || ((PREDIV2) == RCC_PREDIV2_Div2) || \ + ((PREDIV2) == RCC_PREDIV2_Div3) || ((PREDIV2) == RCC_PREDIV2_Div4) || \ + ((PREDIV2) == RCC_PREDIV2_Div5) || ((PREDIV2) == RCC_PREDIV2_Div6) || \ + ((PREDIV2) == RCC_PREDIV2_Div7) || ((PREDIV2) == RCC_PREDIV2_Div8) || \ + ((PREDIV2) == RCC_PREDIV2_Div9) || ((PREDIV2) == RCC_PREDIV2_Div10) || \ + ((PREDIV2) == RCC_PREDIV2_Div11) || ((PREDIV2) == RCC_PREDIV2_Div12) || \ + ((PREDIV2) == RCC_PREDIV2_Div13) || ((PREDIV2) == RCC_PREDIV2_Div14) || \ + ((PREDIV2) == RCC_PREDIV2_Div15) || ((PREDIV2) == RCC_PREDIV2_Div16)) +/** + * @} + */ + + +/** @defgroup PLL2_multiplication_factor + * @{ + */ + + #define RCC_PLL2Mul_8 ((uint32_t)0x00000600) + #define RCC_PLL2Mul_9 ((uint32_t)0x00000700) + #define RCC_PLL2Mul_10 ((uint32_t)0x00000800) + #define RCC_PLL2Mul_11 ((uint32_t)0x00000900) + #define RCC_PLL2Mul_12 ((uint32_t)0x00000A00) + #define RCC_PLL2Mul_13 ((uint32_t)0x00000B00) + #define RCC_PLL2Mul_14 ((uint32_t)0x00000C00) + #define RCC_PLL2Mul_16 ((uint32_t)0x00000E00) + #define RCC_PLL2Mul_20 ((uint32_t)0x00000F00) + + #define IS_RCC_PLL2_MUL(MUL) (((MUL) == RCC_PLL2Mul_8) || ((MUL) == RCC_PLL2Mul_9) || \ + ((MUL) == RCC_PLL2Mul_10) || ((MUL) == RCC_PLL2Mul_11) || \ + ((MUL) == RCC_PLL2Mul_12) || ((MUL) == RCC_PLL2Mul_13) || \ + ((MUL) == RCC_PLL2Mul_14) || ((MUL) == RCC_PLL2Mul_16) || \ + ((MUL) == RCC_PLL2Mul_20)) +/** + * @} + */ + + +/** @defgroup PLL3_multiplication_factor + * @{ + */ + + #define RCC_PLL3Mul_8 ((uint32_t)0x00006000) + #define RCC_PLL3Mul_9 ((uint32_t)0x00007000) + #define RCC_PLL3Mul_10 ((uint32_t)0x00008000) + #define RCC_PLL3Mul_11 ((uint32_t)0x00009000) + #define RCC_PLL3Mul_12 ((uint32_t)0x0000A000) + #define RCC_PLL3Mul_13 ((uint32_t)0x0000B000) + #define RCC_PLL3Mul_14 ((uint32_t)0x0000C000) + #define RCC_PLL3Mul_16 ((uint32_t)0x0000E000) + #define RCC_PLL3Mul_20 ((uint32_t)0x0000F000) + + #define IS_RCC_PLL3_MUL(MUL) (((MUL) == RCC_PLL3Mul_8) || ((MUL) == RCC_PLL3Mul_9) || \ + ((MUL) == RCC_PLL3Mul_10) || ((MUL) == RCC_PLL3Mul_11) || \ + ((MUL) == RCC_PLL3Mul_12) || ((MUL) == RCC_PLL3Mul_13) || \ + ((MUL) == RCC_PLL3Mul_14) || ((MUL) == RCC_PLL3Mul_16) || \ + ((MUL) == RCC_PLL3Mul_20)) +/** + * @} + */ + +#endif /* STM32F10X_CL */ + + +/** @defgroup System_clock_source + * @{ + */ + +#define RCC_SYSCLKSource_HSI ((uint32_t)0x00000000) +#define RCC_SYSCLKSource_HSE ((uint32_t)0x00000001) +#define RCC_SYSCLKSource_PLLCLK ((uint32_t)0x00000002) +#define IS_RCC_SYSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSource_HSI) || \ + ((SOURCE) == RCC_SYSCLKSource_HSE) || \ + ((SOURCE) == RCC_SYSCLKSource_PLLCLK)) +/** + * @} + */ + +/** @defgroup AHB_clock_source + * @{ + */ + +#define RCC_SYSCLK_Div1 ((uint32_t)0x00000000) +#define RCC_SYSCLK_Div2 ((uint32_t)0x00000080) +#define RCC_SYSCLK_Div4 ((uint32_t)0x00000090) +#define RCC_SYSCLK_Div8 ((uint32_t)0x000000A0) +#define RCC_SYSCLK_Div16 ((uint32_t)0x000000B0) +#define RCC_SYSCLK_Div64 ((uint32_t)0x000000C0) +#define RCC_SYSCLK_Div128 ((uint32_t)0x000000D0) +#define RCC_SYSCLK_Div256 ((uint32_t)0x000000E0) +#define RCC_SYSCLK_Div512 ((uint32_t)0x000000F0) +#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_Div1) || ((HCLK) == RCC_SYSCLK_Div2) || \ + ((HCLK) == RCC_SYSCLK_Div4) || ((HCLK) == RCC_SYSCLK_Div8) || \ + ((HCLK) == RCC_SYSCLK_Div16) || ((HCLK) == RCC_SYSCLK_Div64) || \ + ((HCLK) == RCC_SYSCLK_Div128) || ((HCLK) == RCC_SYSCLK_Div256) || \ + ((HCLK) == RCC_SYSCLK_Div512)) +/** + * @} + */ + +/** @defgroup APB1_APB2_clock_source + * @{ + */ + +#define RCC_HCLK_Div1 ((uint32_t)0x00000000) +#define RCC_HCLK_Div2 ((uint32_t)0x00000400) +#define RCC_HCLK_Div4 ((uint32_t)0x00000500) +#define RCC_HCLK_Div8 ((uint32_t)0x00000600) +#define RCC_HCLK_Div16 ((uint32_t)0x00000700) +#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_Div1) || ((PCLK) == RCC_HCLK_Div2) || \ + ((PCLK) == RCC_HCLK_Div4) || ((PCLK) == RCC_HCLK_Div8) || \ + ((PCLK) == RCC_HCLK_Div16)) +/** + * @} + */ + +/** @defgroup RCC_Interrupt_source + * @{ + */ + +#define RCC_IT_LSIRDY ((uint8_t)0x01) +#define RCC_IT_LSERDY ((uint8_t)0x02) +#define RCC_IT_HSIRDY ((uint8_t)0x04) +#define RCC_IT_HSERDY ((uint8_t)0x08) +#define RCC_IT_PLLRDY ((uint8_t)0x10) +#define RCC_IT_CSS ((uint8_t)0x80) + +#ifndef STM32F10X_CL + #define IS_RCC_IT(IT) ((((IT) & (uint8_t)0xE0) == 0x00) && ((IT) != 0x00)) + #define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \ + ((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \ + ((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS)) + #define IS_RCC_CLEAR_IT(IT) ((((IT) & (uint8_t)0x60) == 0x00) && ((IT) != 0x00)) +#else + #define RCC_IT_PLL2RDY ((uint8_t)0x20) + #define RCC_IT_PLL3RDY ((uint8_t)0x40) + #define IS_RCC_IT(IT) ((((IT) & (uint8_t)0x80) == 0x00) && ((IT) != 0x00)) + #define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \ + ((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \ + ((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS) || \ + ((IT) == RCC_IT_PLL2RDY) || ((IT) == RCC_IT_PLL3RDY)) + #define IS_RCC_CLEAR_IT(IT) ((IT) != 0x00) +#endif /* STM32F10X_CL */ + + +/** + * @} + */ + +#ifndef STM32F10X_CL +/** @defgroup USB_Device_clock_source + * @{ + */ + + #define RCC_USBCLKSource_PLLCLK_1Div5 ((uint8_t)0x00) + #define RCC_USBCLKSource_PLLCLK_Div1 ((uint8_t)0x01) + + #define IS_RCC_USBCLK_SOURCE(SOURCE) (((SOURCE) == RCC_USBCLKSource_PLLCLK_1Div5) || \ + ((SOURCE) == RCC_USBCLKSource_PLLCLK_Div1)) +/** + * @} + */ +#else +/** @defgroup USB_OTG_FS_clock_source + * @{ + */ + #define RCC_OTGFSCLKSource_PLLVCO_Div3 ((uint8_t)0x00) + #define RCC_OTGFSCLKSource_PLLVCO_Div2 ((uint8_t)0x01) + + #define IS_RCC_OTGFSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_OTGFSCLKSource_PLLVCO_Div3) || \ + ((SOURCE) == RCC_OTGFSCLKSource_PLLVCO_Div2)) +/** + * @} + */ +#endif /* STM32F10X_CL */ + + +#ifdef STM32F10X_CL +/** @defgroup I2S2_clock_source + * @{ + */ + #define RCC_I2S2CLKSource_SYSCLK ((uint8_t)0x00) + #define RCC_I2S2CLKSource_PLL3_VCO ((uint8_t)0x01) + + #define IS_RCC_I2S2CLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S2CLKSource_SYSCLK) || \ + ((SOURCE) == RCC_I2S2CLKSource_PLL3_VCO)) +/** + * @} + */ + +/** @defgroup I2S3_clock_source + * @{ + */ + #define RCC_I2S3CLKSource_SYSCLK ((uint8_t)0x00) + #define RCC_I2S3CLKSource_PLL3_VCO ((uint8_t)0x01) + + #define IS_RCC_I2S3CLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S3CLKSource_SYSCLK) || \ + ((SOURCE) == RCC_I2S3CLKSource_PLL3_VCO)) +/** + * @} + */ +#endif /* STM32F10X_CL */ + + +/** @defgroup ADC_clock_source + * @{ + */ + +#define RCC_PCLK2_Div2 ((uint32_t)0x00000000) +#define RCC_PCLK2_Div4 ((uint32_t)0x00004000) +#define RCC_PCLK2_Div6 ((uint32_t)0x00008000) +#define RCC_PCLK2_Div8 ((uint32_t)0x0000C000) +#define IS_RCC_ADCCLK(ADCCLK) (((ADCCLK) == RCC_PCLK2_Div2) || ((ADCCLK) == RCC_PCLK2_Div4) || \ + ((ADCCLK) == RCC_PCLK2_Div6) || ((ADCCLK) == RCC_PCLK2_Div8)) +/** + * @} + */ + +/** @defgroup LSE_configuration + * @{ + */ + +#define RCC_LSE_OFF ((uint8_t)0x00) +#define RCC_LSE_ON ((uint8_t)0x01) +#define RCC_LSE_Bypass ((uint8_t)0x04) +#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \ + ((LSE) == RCC_LSE_Bypass)) +/** + * @} + */ + +/** @defgroup RTC_clock_source + * @{ + */ + +#define RCC_RTCCLKSource_LSE ((uint32_t)0x00000100) +#define RCC_RTCCLKSource_LSI ((uint32_t)0x00000200) +#define RCC_RTCCLKSource_HSE_Div128 ((uint32_t)0x00000300) +#define IS_RCC_RTCCLK_SOURCE(SOURCE) (((SOURCE) == RCC_RTCCLKSource_LSE) || \ + ((SOURCE) == RCC_RTCCLKSource_LSI) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div128)) +/** + * @} + */ + +/** @defgroup AHB_peripheral + * @{ + */ + +#define RCC_AHBPeriph_DMA1 ((uint32_t)0x00000001) +#define RCC_AHBPeriph_DMA2 ((uint32_t)0x00000002) +#define RCC_AHBPeriph_SRAM ((uint32_t)0x00000004) +#define RCC_AHBPeriph_FLITF ((uint32_t)0x00000010) +#define RCC_AHBPeriph_CRC ((uint32_t)0x00000040) + +#ifndef STM32F10X_CL + #define RCC_AHBPeriph_FSMC ((uint32_t)0x00000100) + #define RCC_AHBPeriph_SDIO ((uint32_t)0x00000400) + #define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFAA8) == 0x00) && ((PERIPH) != 0x00)) +#else + #define RCC_AHBPeriph_OTG_FS ((uint32_t)0x00001000) + #define RCC_AHBPeriph_ETH_MAC ((uint32_t)0x00004000) + #define RCC_AHBPeriph_ETH_MAC_Tx ((uint32_t)0x00008000) + #define RCC_AHBPeriph_ETH_MAC_Rx ((uint32_t)0x00010000) + + #define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFE2FA8) == 0x00) && ((PERIPH) != 0x00)) + #define IS_RCC_AHB_PERIPH_RESET(PERIPH) ((((PERIPH) & 0xFFFFAFFF) == 0x00) && ((PERIPH) != 0x00)) +#endif /* STM32F10X_CL */ +/** + * @} + */ + +/** @defgroup APB2_peripheral + * @{ + */ + +#define RCC_APB2Periph_AFIO ((uint32_t)0x00000001) +#define RCC_APB2Periph_GPIOA ((uint32_t)0x00000004) +#define RCC_APB2Periph_GPIOB ((uint32_t)0x00000008) +#define RCC_APB2Periph_GPIOC ((uint32_t)0x00000010) +#define RCC_APB2Periph_GPIOD ((uint32_t)0x00000020) +#define RCC_APB2Periph_GPIOE ((uint32_t)0x00000040) +#define RCC_APB2Periph_GPIOF ((uint32_t)0x00000080) +#define RCC_APB2Periph_GPIOG ((uint32_t)0x00000100) +#define RCC_APB2Periph_ADC1 ((uint32_t)0x00000200) +#define RCC_APB2Periph_ADC2 ((uint32_t)0x00000400) +#define RCC_APB2Periph_TIM1 ((uint32_t)0x00000800) +#define RCC_APB2Periph_SPI1 ((uint32_t)0x00001000) +#define RCC_APB2Periph_TIM8 ((uint32_t)0x00002000) +#define RCC_APB2Periph_USART1 ((uint32_t)0x00004000) +#define RCC_APB2Periph_ADC3 ((uint32_t)0x00008000) +#define RCC_APB2Periph_TIM15 ((uint32_t)0x00010000) +#define RCC_APB2Periph_TIM16 ((uint32_t)0x00020000) +#define RCC_APB2Periph_TIM17 ((uint32_t)0x00040000) +#define RCC_APB2Periph_TIM9 ((uint32_t)0x00080000) +#define RCC_APB2Periph_TIM10 ((uint32_t)0x00100000) +#define RCC_APB2Periph_TIM11 ((uint32_t)0x00200000) + +#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xFFC00002) == 0x00) && ((PERIPH) != 0x00)) +/** + * @} + */ + +/** @defgroup APB1_peripheral + * @{ + */ + +#define RCC_APB1Periph_TIM2 ((uint32_t)0x00000001) +#define RCC_APB1Periph_TIM3 ((uint32_t)0x00000002) +#define RCC_APB1Periph_TIM4 ((uint32_t)0x00000004) +#define RCC_APB1Periph_TIM5 ((uint32_t)0x00000008) +#define RCC_APB1Periph_TIM6 ((uint32_t)0x00000010) +#define RCC_APB1Periph_TIM7 ((uint32_t)0x00000020) +#define RCC_APB1Periph_TIM12 ((uint32_t)0x00000040) +#define RCC_APB1Periph_TIM13 ((uint32_t)0x00000080) +#define RCC_APB1Periph_TIM14 ((uint32_t)0x00000100) +#define RCC_APB1Periph_WWDG ((uint32_t)0x00000800) +#define RCC_APB1Periph_SPI2 ((uint32_t)0x00004000) +#define RCC_APB1Periph_SPI3 ((uint32_t)0x00008000) +#define RCC_APB1Periph_USART2 ((uint32_t)0x00020000) +#define RCC_APB1Periph_USART3 ((uint32_t)0x00040000) +#define RCC_APB1Periph_UART4 ((uint32_t)0x00080000) +#define RCC_APB1Periph_UART5 ((uint32_t)0x00100000) +#define RCC_APB1Periph_I2C1 ((uint32_t)0x00200000) +#define RCC_APB1Periph_I2C2 ((uint32_t)0x00400000) +#define RCC_APB1Periph_USB ((uint32_t)0x00800000) +#define RCC_APB1Periph_CAN1 ((uint32_t)0x02000000) +#define RCC_APB1Periph_CAN2 ((uint32_t)0x04000000) +#define RCC_APB1Periph_BKP ((uint32_t)0x08000000) +#define RCC_APB1Periph_PWR ((uint32_t)0x10000000) +#define RCC_APB1Periph_DAC ((uint32_t)0x20000000) +#define RCC_APB1Periph_CEC ((uint32_t)0x40000000) + +#define IS_RCC_APB1_PERIPH(PERIPH) ((((PERIPH) & 0x81013600) == 0x00) && ((PERIPH) != 0x00)) + +/** + * @} + */ + +/** @defgroup Clock_source_to_output_on_MCO_pin + * @{ + */ + +#define RCC_MCO_NoClock ((uint8_t)0x00) +#define RCC_MCO_SYSCLK ((uint8_t)0x04) +#define RCC_MCO_HSI ((uint8_t)0x05) +#define RCC_MCO_HSE ((uint8_t)0x06) +#define RCC_MCO_PLLCLK_Div2 ((uint8_t)0x07) + +#ifndef STM32F10X_CL + #define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \ + ((MCO) == RCC_MCO_SYSCLK) || ((MCO) == RCC_MCO_HSE) || \ + ((MCO) == RCC_MCO_PLLCLK_Div2)) +#else + #define RCC_MCO_PLL2CLK ((uint8_t)0x08) + #define RCC_MCO_PLL3CLK_Div2 ((uint8_t)0x09) + #define RCC_MCO_XT1 ((uint8_t)0x0A) + #define RCC_MCO_PLL3CLK ((uint8_t)0x0B) + + #define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \ + ((MCO) == RCC_MCO_SYSCLK) || ((MCO) == RCC_MCO_HSE) || \ + ((MCO) == RCC_MCO_PLLCLK_Div2) || ((MCO) == RCC_MCO_PLL2CLK) || \ + ((MCO) == RCC_MCO_PLL3CLK_Div2) || ((MCO) == RCC_MCO_XT1) || \ + ((MCO) == RCC_MCO_PLL3CLK)) +#endif /* STM32F10X_CL */ + +/** + * @} + */ + +/** @defgroup RCC_Flag + * @{ + */ + +#define RCC_FLAG_HSIRDY ((uint8_t)0x21) +#define RCC_FLAG_HSERDY ((uint8_t)0x31) +#define RCC_FLAG_PLLRDY ((uint8_t)0x39) +#define RCC_FLAG_LSERDY ((uint8_t)0x41) +#define RCC_FLAG_LSIRDY ((uint8_t)0x61) +#define RCC_FLAG_PINRST ((uint8_t)0x7A) +#define RCC_FLAG_PORRST ((uint8_t)0x7B) +#define RCC_FLAG_SFTRST ((uint8_t)0x7C) +#define RCC_FLAG_IWDGRST ((uint8_t)0x7D) +#define RCC_FLAG_WWDGRST ((uint8_t)0x7E) +#define RCC_FLAG_LPWRRST ((uint8_t)0x7F) + +#ifndef STM32F10X_CL + #define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \ + ((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \ + ((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \ + ((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \ + ((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \ + ((FLAG) == RCC_FLAG_LPWRRST)) +#else + #define RCC_FLAG_PLL2RDY ((uint8_t)0x3B) + #define RCC_FLAG_PLL3RDY ((uint8_t)0x3D) + #define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \ + ((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \ + ((FLAG) == RCC_FLAG_PLL2RDY) || ((FLAG) == RCC_FLAG_PLL3RDY) || \ + ((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \ + ((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \ + ((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \ + ((FLAG) == RCC_FLAG_LPWRRST)) +#endif /* STM32F10X_CL */ + +#define IS_RCC_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1F) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup RCC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup RCC_Exported_Functions + * @{ + */ + +void RCC_DeInit(void); +void RCC_HSEConfig(uint32_t RCC_HSE); +ErrorStatus RCC_WaitForHSEStartUp(void); +void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue); +void RCC_HSICmd(FunctionalState NewState); +void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul); +void RCC_PLLCmd(FunctionalState NewState); + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) + void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Source, uint32_t RCC_PREDIV1_Div); +#endif + +#ifdef STM32F10X_CL + void RCC_PREDIV2Config(uint32_t RCC_PREDIV2_Div); + void RCC_PLL2Config(uint32_t RCC_PLL2Mul); + void RCC_PLL2Cmd(FunctionalState NewState); + void RCC_PLL3Config(uint32_t RCC_PLL3Mul); + void RCC_PLL3Cmd(FunctionalState NewState); +#endif /* STM32F10X_CL */ + +void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource); +uint8_t RCC_GetSYSCLKSource(void); +void RCC_HCLKConfig(uint32_t RCC_SYSCLK); +void RCC_PCLK1Config(uint32_t RCC_HCLK); +void RCC_PCLK2Config(uint32_t RCC_HCLK); +void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState); + +#ifndef STM32F10X_CL + void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource); +#else + void RCC_OTGFSCLKConfig(uint32_t RCC_OTGFSCLKSource); +#endif /* STM32F10X_CL */ + +void RCC_ADCCLKConfig(uint32_t RCC_PCLK2); + +#ifdef STM32F10X_CL + void RCC_I2S2CLKConfig(uint32_t RCC_I2S2CLKSource); + void RCC_I2S3CLKConfig(uint32_t RCC_I2S3CLKSource); +#endif /* STM32F10X_CL */ + +void RCC_LSEConfig(uint8_t RCC_LSE); +void RCC_LSICmd(FunctionalState NewState); +void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource); +void RCC_RTCCLKCmd(FunctionalState NewState); +void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks); +void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState); +void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState); +void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState); + +#ifdef STM32F10X_CL +void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState); +#endif /* STM32F10X_CL */ + +void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState); +void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState); +void RCC_BackupResetCmd(FunctionalState NewState); +void RCC_ClockSecuritySystemCmd(FunctionalState NewState); +void RCC_MCOConfig(uint8_t RCC_MCO); +FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG); +void RCC_ClearFlag(void); +ITStatus RCC_GetITStatus(uint8_t RCC_IT); +void RCC_ClearITPendingBit(uint8_t RCC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_RCC_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h new file mode 100644 index 0000000..fd8beb5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h @@ -0,0 +1,135 @@ +/** + ****************************************************************************** + * @file stm32f10x_rtc.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the RTC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_RTC_H +#define __STM32F10x_RTC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup RTC + * @{ + */ + +/** @defgroup RTC_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup RTC_Exported_Constants + * @{ + */ + +/** @defgroup RTC_interrupts_define + * @{ + */ + +#define RTC_IT_OW ((uint16_t)0x0004) /*!< Overflow interrupt */ +#define RTC_IT_ALR ((uint16_t)0x0002) /*!< Alarm interrupt */ +#define RTC_IT_SEC ((uint16_t)0x0001) /*!< Second interrupt */ +#define IS_RTC_IT(IT) ((((IT) & (uint16_t)0xFFF8) == 0x00) && ((IT) != 0x00)) +#define IS_RTC_GET_IT(IT) (((IT) == RTC_IT_OW) || ((IT) == RTC_IT_ALR) || \ + ((IT) == RTC_IT_SEC)) +/** + * @} + */ + +/** @defgroup RTC_interrupts_flags + * @{ + */ + +#define RTC_FLAG_RTOFF ((uint16_t)0x0020) /*!< RTC Operation OFF flag */ +#define RTC_FLAG_RSF ((uint16_t)0x0008) /*!< Registers Synchronized flag */ +#define RTC_FLAG_OW ((uint16_t)0x0004) /*!< Overflow flag */ +#define RTC_FLAG_ALR ((uint16_t)0x0002) /*!< Alarm flag */ +#define RTC_FLAG_SEC ((uint16_t)0x0001) /*!< Second flag */ +#define IS_RTC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFFF0) == 0x00) && ((FLAG) != 0x00)) +#define IS_RTC_GET_FLAG(FLAG) (((FLAG) == RTC_FLAG_RTOFF) || ((FLAG) == RTC_FLAG_RSF) || \ + ((FLAG) == RTC_FLAG_OW) || ((FLAG) == RTC_FLAG_ALR) || \ + ((FLAG) == RTC_FLAG_SEC)) +#define IS_RTC_PRESCALER(PRESCALER) ((PRESCALER) <= 0xFFFFF) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup RTC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup RTC_Exported_Functions + * @{ + */ + +void RTC_ITConfig(uint16_t RTC_IT, FunctionalState NewState); +void RTC_EnterConfigMode(void); +void RTC_ExitConfigMode(void); +uint32_t RTC_GetCounter(void); +void RTC_SetCounter(uint32_t CounterValue); +void RTC_SetPrescaler(uint32_t PrescalerValue); +void RTC_SetAlarm(uint32_t AlarmValue); +uint32_t RTC_GetDivider(void); +void RTC_WaitForLastTask(void); +void RTC_WaitForSynchro(void); +FlagStatus RTC_GetFlagStatus(uint16_t RTC_FLAG); +void RTC_ClearFlag(uint16_t RTC_FLAG); +ITStatus RTC_GetITStatus(uint16_t RTC_IT); +void RTC_ClearITPendingBit(uint16_t RTC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_RTC_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h new file mode 100644 index 0000000..81c058a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h @@ -0,0 +1,531 @@ +/** + ****************************************************************************** + * @file stm32f10x_sdio.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the SDIO firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_SDIO_H +#define __STM32F10x_SDIO_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup SDIO + * @{ + */ + +/** @defgroup SDIO_Exported_Types + * @{ + */ + +typedef struct +{ + uint32_t SDIO_ClockEdge; /*!< Specifies the clock transition on which the bit capture is made. + This parameter can be a value of @ref SDIO_Clock_Edge */ + + uint32_t SDIO_ClockBypass; /*!< Specifies whether the SDIO Clock divider bypass is + enabled or disabled. + This parameter can be a value of @ref SDIO_Clock_Bypass */ + + uint32_t SDIO_ClockPowerSave; /*!< Specifies whether SDIO Clock output is enabled or + disabled when the bus is idle. + This parameter can be a value of @ref SDIO_Clock_Power_Save */ + + uint32_t SDIO_BusWide; /*!< Specifies the SDIO bus width. + This parameter can be a value of @ref SDIO_Bus_Wide */ + + uint32_t SDIO_HardwareFlowControl; /*!< Specifies whether the SDIO hardware flow control is enabled or disabled. + This parameter can be a value of @ref SDIO_Hardware_Flow_Control */ + + uint8_t SDIO_ClockDiv; /*!< Specifies the clock frequency of the SDIO controller. + This parameter can be a value between 0x00 and 0xFF. */ + +} SDIO_InitTypeDef; + +typedef struct +{ + uint32_t SDIO_Argument; /*!< Specifies the SDIO command argument which is sent + to a card as part of a command message. If a command + contains an argument, it must be loaded into this register + before writing the command to the command register */ + + uint32_t SDIO_CmdIndex; /*!< Specifies the SDIO command index. It must be lower than 0x40. */ + + uint32_t SDIO_Response; /*!< Specifies the SDIO response type. + This parameter can be a value of @ref SDIO_Response_Type */ + + uint32_t SDIO_Wait; /*!< Specifies whether SDIO wait-for-interrupt request is enabled or disabled. + This parameter can be a value of @ref SDIO_Wait_Interrupt_State */ + + uint32_t SDIO_CPSM; /*!< Specifies whether SDIO Command path state machine (CPSM) + is enabled or disabled. + This parameter can be a value of @ref SDIO_CPSM_State */ +} SDIO_CmdInitTypeDef; + +typedef struct +{ + uint32_t SDIO_DataTimeOut; /*!< Specifies the data timeout period in card bus clock periods. */ + + uint32_t SDIO_DataLength; /*!< Specifies the number of data bytes to be transferred. */ + + uint32_t SDIO_DataBlockSize; /*!< Specifies the data block size for block transfer. + This parameter can be a value of @ref SDIO_Data_Block_Size */ + + uint32_t SDIO_TransferDir; /*!< Specifies the data transfer direction, whether the transfer + is a read or write. + This parameter can be a value of @ref SDIO_Transfer_Direction */ + + uint32_t SDIO_TransferMode; /*!< Specifies whether data transfer is in stream or block mode. + This parameter can be a value of @ref SDIO_Transfer_Type */ + + uint32_t SDIO_DPSM; /*!< Specifies whether SDIO Data path state machine (DPSM) + is enabled or disabled. + This parameter can be a value of @ref SDIO_DPSM_State */ +} SDIO_DataInitTypeDef; + +/** + * @} + */ + +/** @defgroup SDIO_Exported_Constants + * @{ + */ + +/** @defgroup SDIO_Clock_Edge + * @{ + */ + +#define SDIO_ClockEdge_Rising ((uint32_t)0x00000000) +#define SDIO_ClockEdge_Falling ((uint32_t)0x00002000) +#define IS_SDIO_CLOCK_EDGE(EDGE) (((EDGE) == SDIO_ClockEdge_Rising) || \ + ((EDGE) == SDIO_ClockEdge_Falling)) +/** + * @} + */ + +/** @defgroup SDIO_Clock_Bypass + * @{ + */ + +#define SDIO_ClockBypass_Disable ((uint32_t)0x00000000) +#define SDIO_ClockBypass_Enable ((uint32_t)0x00000400) +#define IS_SDIO_CLOCK_BYPASS(BYPASS) (((BYPASS) == SDIO_ClockBypass_Disable) || \ + ((BYPASS) == SDIO_ClockBypass_Enable)) +/** + * @} + */ + +/** @defgroup SDIO_Clock_Power_Save + * @{ + */ + +#define SDIO_ClockPowerSave_Disable ((uint32_t)0x00000000) +#define SDIO_ClockPowerSave_Enable ((uint32_t)0x00000200) +#define IS_SDIO_CLOCK_POWER_SAVE(SAVE) (((SAVE) == SDIO_ClockPowerSave_Disable) || \ + ((SAVE) == SDIO_ClockPowerSave_Enable)) +/** + * @} + */ + +/** @defgroup SDIO_Bus_Wide + * @{ + */ + +#define SDIO_BusWide_1b ((uint32_t)0x00000000) +#define SDIO_BusWide_4b ((uint32_t)0x00000800) +#define SDIO_BusWide_8b ((uint32_t)0x00001000) +#define IS_SDIO_BUS_WIDE(WIDE) (((WIDE) == SDIO_BusWide_1b) || ((WIDE) == SDIO_BusWide_4b) || \ + ((WIDE) == SDIO_BusWide_8b)) + +/** + * @} + */ + +/** @defgroup SDIO_Hardware_Flow_Control + * @{ + */ + +#define SDIO_HardwareFlowControl_Disable ((uint32_t)0x00000000) +#define SDIO_HardwareFlowControl_Enable ((uint32_t)0x00004000) +#define IS_SDIO_HARDWARE_FLOW_CONTROL(CONTROL) (((CONTROL) == SDIO_HardwareFlowControl_Disable) || \ + ((CONTROL) == SDIO_HardwareFlowControl_Enable)) +/** + * @} + */ + +/** @defgroup SDIO_Power_State + * @{ + */ + +#define SDIO_PowerState_OFF ((uint32_t)0x00000000) +#define SDIO_PowerState_ON ((uint32_t)0x00000003) +#define IS_SDIO_POWER_STATE(STATE) (((STATE) == SDIO_PowerState_OFF) || ((STATE) == SDIO_PowerState_ON)) +/** + * @} + */ + + +/** @defgroup SDIO_Interrupt_sources + * @{ + */ + +#define SDIO_IT_CCRCFAIL ((uint32_t)0x00000001) +#define SDIO_IT_DCRCFAIL ((uint32_t)0x00000002) +#define SDIO_IT_CTIMEOUT ((uint32_t)0x00000004) +#define SDIO_IT_DTIMEOUT ((uint32_t)0x00000008) +#define SDIO_IT_TXUNDERR ((uint32_t)0x00000010) +#define SDIO_IT_RXOVERR ((uint32_t)0x00000020) +#define SDIO_IT_CMDREND ((uint32_t)0x00000040) +#define SDIO_IT_CMDSENT ((uint32_t)0x00000080) +#define SDIO_IT_DATAEND ((uint32_t)0x00000100) +#define SDIO_IT_STBITERR ((uint32_t)0x00000200) +#define SDIO_IT_DBCKEND ((uint32_t)0x00000400) +#define SDIO_IT_CMDACT ((uint32_t)0x00000800) +#define SDIO_IT_TXACT ((uint32_t)0x00001000) +#define SDIO_IT_RXACT ((uint32_t)0x00002000) +#define SDIO_IT_TXFIFOHE ((uint32_t)0x00004000) +#define SDIO_IT_RXFIFOHF ((uint32_t)0x00008000) +#define SDIO_IT_TXFIFOF ((uint32_t)0x00010000) +#define SDIO_IT_RXFIFOF ((uint32_t)0x00020000) +#define SDIO_IT_TXFIFOE ((uint32_t)0x00040000) +#define SDIO_IT_RXFIFOE ((uint32_t)0x00080000) +#define SDIO_IT_TXDAVL ((uint32_t)0x00100000) +#define SDIO_IT_RXDAVL ((uint32_t)0x00200000) +#define SDIO_IT_SDIOIT ((uint32_t)0x00400000) +#define SDIO_IT_CEATAEND ((uint32_t)0x00800000) +#define IS_SDIO_IT(IT) ((((IT) & (uint32_t)0xFF000000) == 0x00) && ((IT) != (uint32_t)0x00)) +/** + * @} + */ + +/** @defgroup SDIO_Command_Index + * @{ + */ + +#define IS_SDIO_CMD_INDEX(INDEX) ((INDEX) < 0x40) +/** + * @} + */ + +/** @defgroup SDIO_Response_Type + * @{ + */ + +#define SDIO_Response_No ((uint32_t)0x00000000) +#define SDIO_Response_Short ((uint32_t)0x00000040) +#define SDIO_Response_Long ((uint32_t)0x000000C0) +#define IS_SDIO_RESPONSE(RESPONSE) (((RESPONSE) == SDIO_Response_No) || \ + ((RESPONSE) == SDIO_Response_Short) || \ + ((RESPONSE) == SDIO_Response_Long)) +/** + * @} + */ + +/** @defgroup SDIO_Wait_Interrupt_State + * @{ + */ + +#define SDIO_Wait_No ((uint32_t)0x00000000) /*!< SDIO No Wait, TimeOut is enabled */ +#define SDIO_Wait_IT ((uint32_t)0x00000100) /*!< SDIO Wait Interrupt Request */ +#define SDIO_Wait_Pend ((uint32_t)0x00000200) /*!< SDIO Wait End of transfer */ +#define IS_SDIO_WAIT(WAIT) (((WAIT) == SDIO_Wait_No) || ((WAIT) == SDIO_Wait_IT) || \ + ((WAIT) == SDIO_Wait_Pend)) +/** + * @} + */ + +/** @defgroup SDIO_CPSM_State + * @{ + */ + +#define SDIO_CPSM_Disable ((uint32_t)0x00000000) +#define SDIO_CPSM_Enable ((uint32_t)0x00000400) +#define IS_SDIO_CPSM(CPSM) (((CPSM) == SDIO_CPSM_Enable) || ((CPSM) == SDIO_CPSM_Disable)) +/** + * @} + */ + +/** @defgroup SDIO_Response_Registers + * @{ + */ + +#define SDIO_RESP1 ((uint32_t)0x00000000) +#define SDIO_RESP2 ((uint32_t)0x00000004) +#define SDIO_RESP3 ((uint32_t)0x00000008) +#define SDIO_RESP4 ((uint32_t)0x0000000C) +#define IS_SDIO_RESP(RESP) (((RESP) == SDIO_RESP1) || ((RESP) == SDIO_RESP2) || \ + ((RESP) == SDIO_RESP3) || ((RESP) == SDIO_RESP4)) +/** + * @} + */ + +/** @defgroup SDIO_Data_Length + * @{ + */ + +#define IS_SDIO_DATA_LENGTH(LENGTH) ((LENGTH) <= 0x01FFFFFF) +/** + * @} + */ + +/** @defgroup SDIO_Data_Block_Size + * @{ + */ + +#define SDIO_DataBlockSize_1b ((uint32_t)0x00000000) +#define SDIO_DataBlockSize_2b ((uint32_t)0x00000010) +#define SDIO_DataBlockSize_4b ((uint32_t)0x00000020) +#define SDIO_DataBlockSize_8b ((uint32_t)0x00000030) +#define SDIO_DataBlockSize_16b ((uint32_t)0x00000040) +#define SDIO_DataBlockSize_32b ((uint32_t)0x00000050) +#define SDIO_DataBlockSize_64b ((uint32_t)0x00000060) +#define SDIO_DataBlockSize_128b ((uint32_t)0x00000070) +#define SDIO_DataBlockSize_256b ((uint32_t)0x00000080) +#define SDIO_DataBlockSize_512b ((uint32_t)0x00000090) +#define SDIO_DataBlockSize_1024b ((uint32_t)0x000000A0) +#define SDIO_DataBlockSize_2048b ((uint32_t)0x000000B0) +#define SDIO_DataBlockSize_4096b ((uint32_t)0x000000C0) +#define SDIO_DataBlockSize_8192b ((uint32_t)0x000000D0) +#define SDIO_DataBlockSize_16384b ((uint32_t)0x000000E0) +#define IS_SDIO_BLOCK_SIZE(SIZE) (((SIZE) == SDIO_DataBlockSize_1b) || \ + ((SIZE) == SDIO_DataBlockSize_2b) || \ + ((SIZE) == SDIO_DataBlockSize_4b) || \ + ((SIZE) == SDIO_DataBlockSize_8b) || \ + ((SIZE) == SDIO_DataBlockSize_16b) || \ + ((SIZE) == SDIO_DataBlockSize_32b) || \ + ((SIZE) == SDIO_DataBlockSize_64b) || \ + ((SIZE) == SDIO_DataBlockSize_128b) || \ + ((SIZE) == SDIO_DataBlockSize_256b) || \ + ((SIZE) == SDIO_DataBlockSize_512b) || \ + ((SIZE) == SDIO_DataBlockSize_1024b) || \ + ((SIZE) == SDIO_DataBlockSize_2048b) || \ + ((SIZE) == SDIO_DataBlockSize_4096b) || \ + ((SIZE) == SDIO_DataBlockSize_8192b) || \ + ((SIZE) == SDIO_DataBlockSize_16384b)) +/** + * @} + */ + +/** @defgroup SDIO_Transfer_Direction + * @{ + */ + +#define SDIO_TransferDir_ToCard ((uint32_t)0x00000000) +#define SDIO_TransferDir_ToSDIO ((uint32_t)0x00000002) +#define IS_SDIO_TRANSFER_DIR(DIR) (((DIR) == SDIO_TransferDir_ToCard) || \ + ((DIR) == SDIO_TransferDir_ToSDIO)) +/** + * @} + */ + +/** @defgroup SDIO_Transfer_Type + * @{ + */ + +#define SDIO_TransferMode_Block ((uint32_t)0x00000000) +#define SDIO_TransferMode_Stream ((uint32_t)0x00000004) +#define IS_SDIO_TRANSFER_MODE(MODE) (((MODE) == SDIO_TransferMode_Stream) || \ + ((MODE) == SDIO_TransferMode_Block)) +/** + * @} + */ + +/** @defgroup SDIO_DPSM_State + * @{ + */ + +#define SDIO_DPSM_Disable ((uint32_t)0x00000000) +#define SDIO_DPSM_Enable ((uint32_t)0x00000001) +#define IS_SDIO_DPSM(DPSM) (((DPSM) == SDIO_DPSM_Enable) || ((DPSM) == SDIO_DPSM_Disable)) +/** + * @} + */ + +/** @defgroup SDIO_Flags + * @{ + */ + +#define SDIO_FLAG_CCRCFAIL ((uint32_t)0x00000001) +#define SDIO_FLAG_DCRCFAIL ((uint32_t)0x00000002) +#define SDIO_FLAG_CTIMEOUT ((uint32_t)0x00000004) +#define SDIO_FLAG_DTIMEOUT ((uint32_t)0x00000008) +#define SDIO_FLAG_TXUNDERR ((uint32_t)0x00000010) +#define SDIO_FLAG_RXOVERR ((uint32_t)0x00000020) +#define SDIO_FLAG_CMDREND ((uint32_t)0x00000040) +#define SDIO_FLAG_CMDSENT ((uint32_t)0x00000080) +#define SDIO_FLAG_DATAEND ((uint32_t)0x00000100) +#define SDIO_FLAG_STBITERR ((uint32_t)0x00000200) +#define SDIO_FLAG_DBCKEND ((uint32_t)0x00000400) +#define SDIO_FLAG_CMDACT ((uint32_t)0x00000800) +#define SDIO_FLAG_TXACT ((uint32_t)0x00001000) +#define SDIO_FLAG_RXACT ((uint32_t)0x00002000) +#define SDIO_FLAG_TXFIFOHE ((uint32_t)0x00004000) +#define SDIO_FLAG_RXFIFOHF ((uint32_t)0x00008000) +#define SDIO_FLAG_TXFIFOF ((uint32_t)0x00010000) +#define SDIO_FLAG_RXFIFOF ((uint32_t)0x00020000) +#define SDIO_FLAG_TXFIFOE ((uint32_t)0x00040000) +#define SDIO_FLAG_RXFIFOE ((uint32_t)0x00080000) +#define SDIO_FLAG_TXDAVL ((uint32_t)0x00100000) +#define SDIO_FLAG_RXDAVL ((uint32_t)0x00200000) +#define SDIO_FLAG_SDIOIT ((uint32_t)0x00400000) +#define SDIO_FLAG_CEATAEND ((uint32_t)0x00800000) +#define IS_SDIO_FLAG(FLAG) (((FLAG) == SDIO_FLAG_CCRCFAIL) || \ + ((FLAG) == SDIO_FLAG_DCRCFAIL) || \ + ((FLAG) == SDIO_FLAG_CTIMEOUT) || \ + ((FLAG) == SDIO_FLAG_DTIMEOUT) || \ + ((FLAG) == SDIO_FLAG_TXUNDERR) || \ + ((FLAG) == SDIO_FLAG_RXOVERR) || \ + ((FLAG) == SDIO_FLAG_CMDREND) || \ + ((FLAG) == SDIO_FLAG_CMDSENT) || \ + ((FLAG) == SDIO_FLAG_DATAEND) || \ + ((FLAG) == SDIO_FLAG_STBITERR) || \ + ((FLAG) == SDIO_FLAG_DBCKEND) || \ + ((FLAG) == SDIO_FLAG_CMDACT) || \ + ((FLAG) == SDIO_FLAG_TXACT) || \ + ((FLAG) == SDIO_FLAG_RXACT) || \ + ((FLAG) == SDIO_FLAG_TXFIFOHE) || \ + ((FLAG) == SDIO_FLAG_RXFIFOHF) || \ + ((FLAG) == SDIO_FLAG_TXFIFOF) || \ + ((FLAG) == SDIO_FLAG_RXFIFOF) || \ + ((FLAG) == SDIO_FLAG_TXFIFOE) || \ + ((FLAG) == SDIO_FLAG_RXFIFOE) || \ + ((FLAG) == SDIO_FLAG_TXDAVL) || \ + ((FLAG) == SDIO_FLAG_RXDAVL) || \ + ((FLAG) == SDIO_FLAG_SDIOIT) || \ + ((FLAG) == SDIO_FLAG_CEATAEND)) + +#define IS_SDIO_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFF3FF800) == 0x00) && ((FLAG) != (uint32_t)0x00)) + +#define IS_SDIO_GET_IT(IT) (((IT) == SDIO_IT_CCRCFAIL) || \ + ((IT) == SDIO_IT_DCRCFAIL) || \ + ((IT) == SDIO_IT_CTIMEOUT) || \ + ((IT) == SDIO_IT_DTIMEOUT) || \ + ((IT) == SDIO_IT_TXUNDERR) || \ + ((IT) == SDIO_IT_RXOVERR) || \ + ((IT) == SDIO_IT_CMDREND) || \ + ((IT) == SDIO_IT_CMDSENT) || \ + ((IT) == SDIO_IT_DATAEND) || \ + ((IT) == SDIO_IT_STBITERR) || \ + ((IT) == SDIO_IT_DBCKEND) || \ + ((IT) == SDIO_IT_CMDACT) || \ + ((IT) == SDIO_IT_TXACT) || \ + ((IT) == SDIO_IT_RXACT) || \ + ((IT) == SDIO_IT_TXFIFOHE) || \ + ((IT) == SDIO_IT_RXFIFOHF) || \ + ((IT) == SDIO_IT_TXFIFOF) || \ + ((IT) == SDIO_IT_RXFIFOF) || \ + ((IT) == SDIO_IT_TXFIFOE) || \ + ((IT) == SDIO_IT_RXFIFOE) || \ + ((IT) == SDIO_IT_TXDAVL) || \ + ((IT) == SDIO_IT_RXDAVL) || \ + ((IT) == SDIO_IT_SDIOIT) || \ + ((IT) == SDIO_IT_CEATAEND)) + +#define IS_SDIO_CLEAR_IT(IT) ((((IT) & (uint32_t)0xFF3FF800) == 0x00) && ((IT) != (uint32_t)0x00)) + +/** + * @} + */ + +/** @defgroup SDIO_Read_Wait_Mode + * @{ + */ + +#define SDIO_ReadWaitMode_CLK ((uint32_t)0x00000001) +#define SDIO_ReadWaitMode_DATA2 ((uint32_t)0x00000000) +#define IS_SDIO_READWAIT_MODE(MODE) (((MODE) == SDIO_ReadWaitMode_CLK) || \ + ((MODE) == SDIO_ReadWaitMode_DATA2)) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup SDIO_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup SDIO_Exported_Functions + * @{ + */ + +void SDIO_DeInit(void); +void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct); +void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct); +void SDIO_ClockCmd(FunctionalState NewState); +void SDIO_SetPowerState(uint32_t SDIO_PowerState); +uint32_t SDIO_GetPowerState(void); +void SDIO_ITConfig(uint32_t SDIO_IT, FunctionalState NewState); +void SDIO_DMACmd(FunctionalState NewState); +void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct); +void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct); +uint8_t SDIO_GetCommandResponse(void); +uint32_t SDIO_GetResponse(uint32_t SDIO_RESP); +void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct); +void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct); +uint32_t SDIO_GetDataCounter(void); +uint32_t SDIO_ReadData(void); +void SDIO_WriteData(uint32_t Data); +uint32_t SDIO_GetFIFOCount(void); +void SDIO_StartSDIOReadWait(FunctionalState NewState); +void SDIO_StopSDIOReadWait(FunctionalState NewState); +void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode); +void SDIO_SetSDIOOperation(FunctionalState NewState); +void SDIO_SendSDIOSuspendCmd(FunctionalState NewState); +void SDIO_CommandCompletionCmd(FunctionalState NewState); +void SDIO_CEATAITCmd(FunctionalState NewState); +void SDIO_SendCEATACmd(FunctionalState NewState); +FlagStatus SDIO_GetFlagStatus(uint32_t SDIO_FLAG); +void SDIO_ClearFlag(uint32_t SDIO_FLAG); +ITStatus SDIO_GetITStatus(uint32_t SDIO_IT); +void SDIO_ClearITPendingBit(uint32_t SDIO_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_SDIO_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h new file mode 100644 index 0000000..23cc26d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h @@ -0,0 +1,487 @@ +/** + ****************************************************************************** + * @file stm32f10x_spi.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the SPI firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_SPI_H +#define __STM32F10x_SPI_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup SPI + * @{ + */ + +/** @defgroup SPI_Exported_Types + * @{ + */ + +/** + * @brief SPI Init structure definition + */ + +typedef struct +{ + uint16_t SPI_Direction; /*!< Specifies the SPI unidirectional or bidirectional data mode. + This parameter can be a value of @ref SPI_data_direction */ + + uint16_t SPI_Mode; /*!< Specifies the SPI operating mode. + This parameter can be a value of @ref SPI_mode */ + + uint16_t SPI_DataSize; /*!< Specifies the SPI data size. + This parameter can be a value of @ref SPI_data_size */ + + uint16_t SPI_CPOL; /*!< Specifies the serial clock steady state. + This parameter can be a value of @ref SPI_Clock_Polarity */ + + uint16_t SPI_CPHA; /*!< Specifies the clock active edge for the bit capture. + This parameter can be a value of @ref SPI_Clock_Phase */ + + uint16_t SPI_NSS; /*!< Specifies whether the NSS signal is managed by + hardware (NSS pin) or by software using the SSI bit. + This parameter can be a value of @ref SPI_Slave_Select_management */ + + uint16_t SPI_BaudRatePrescaler; /*!< Specifies the Baud Rate prescaler value which will be + used to configure the transmit and receive SCK clock. + This parameter can be a value of @ref SPI_BaudRate_Prescaler. + @note The communication clock is derived from the master + clock. The slave clock does not need to be set. */ + + uint16_t SPI_FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit. + This parameter can be a value of @ref SPI_MSB_LSB_transmission */ + + uint16_t SPI_CRCPolynomial; /*!< Specifies the polynomial used for the CRC calculation. */ +}SPI_InitTypeDef; + +/** + * @brief I2S Init structure definition + */ + +typedef struct +{ + + uint16_t I2S_Mode; /*!< Specifies the I2S operating mode. + This parameter can be a value of @ref I2S_Mode */ + + uint16_t I2S_Standard; /*!< Specifies the standard used for the I2S communication. + This parameter can be a value of @ref I2S_Standard */ + + uint16_t I2S_DataFormat; /*!< Specifies the data format for the I2S communication. + This parameter can be a value of @ref I2S_Data_Format */ + + uint16_t I2S_MCLKOutput; /*!< Specifies whether the I2S MCLK output is enabled or not. + This parameter can be a value of @ref I2S_MCLK_Output */ + + uint32_t I2S_AudioFreq; /*!< Specifies the frequency selected for the I2S communication. + This parameter can be a value of @ref I2S_Audio_Frequency */ + + uint16_t I2S_CPOL; /*!< Specifies the idle state of the I2S clock. + This parameter can be a value of @ref I2S_Clock_Polarity */ +}I2S_InitTypeDef; + +/** + * @} + */ + +/** @defgroup SPI_Exported_Constants + * @{ + */ + +#define IS_SPI_ALL_PERIPH(PERIPH) (((PERIPH) == SPI1) || \ + ((PERIPH) == SPI2) || \ + ((PERIPH) == SPI3)) + +#define IS_SPI_23_PERIPH(PERIPH) (((PERIPH) == SPI2) || \ + ((PERIPH) == SPI3)) + +/** @defgroup SPI_data_direction + * @{ + */ + +#define SPI_Direction_2Lines_FullDuplex ((uint16_t)0x0000) +#define SPI_Direction_2Lines_RxOnly ((uint16_t)0x0400) +#define SPI_Direction_1Line_Rx ((uint16_t)0x8000) +#define SPI_Direction_1Line_Tx ((uint16_t)0xC000) +#define IS_SPI_DIRECTION_MODE(MODE) (((MODE) == SPI_Direction_2Lines_FullDuplex) || \ + ((MODE) == SPI_Direction_2Lines_RxOnly) || \ + ((MODE) == SPI_Direction_1Line_Rx) || \ + ((MODE) == SPI_Direction_1Line_Tx)) +/** + * @} + */ + +/** @defgroup SPI_mode + * @{ + */ + +#define SPI_Mode_Master ((uint16_t)0x0104) +#define SPI_Mode_Slave ((uint16_t)0x0000) +#define IS_SPI_MODE(MODE) (((MODE) == SPI_Mode_Master) || \ + ((MODE) == SPI_Mode_Slave)) +/** + * @} + */ + +/** @defgroup SPI_data_size + * @{ + */ + +#define SPI_DataSize_16b ((uint16_t)0x0800) +#define SPI_DataSize_8b ((uint16_t)0x0000) +#define IS_SPI_DATASIZE(DATASIZE) (((DATASIZE) == SPI_DataSize_16b) || \ + ((DATASIZE) == SPI_DataSize_8b)) +/** + * @} + */ + +/** @defgroup SPI_Clock_Polarity + * @{ + */ + +#define SPI_CPOL_Low ((uint16_t)0x0000) +#define SPI_CPOL_High ((uint16_t)0x0002) +#define IS_SPI_CPOL(CPOL) (((CPOL) == SPI_CPOL_Low) || \ + ((CPOL) == SPI_CPOL_High)) +/** + * @} + */ + +/** @defgroup SPI_Clock_Phase + * @{ + */ + +#define SPI_CPHA_1Edge ((uint16_t)0x0000) +#define SPI_CPHA_2Edge ((uint16_t)0x0001) +#define IS_SPI_CPHA(CPHA) (((CPHA) == SPI_CPHA_1Edge) || \ + ((CPHA) == SPI_CPHA_2Edge)) +/** + * @} + */ + +/** @defgroup SPI_Slave_Select_management + * @{ + */ + +#define SPI_NSS_Soft ((uint16_t)0x0200) +#define SPI_NSS_Hard ((uint16_t)0x0000) +#define IS_SPI_NSS(NSS) (((NSS) == SPI_NSS_Soft) || \ + ((NSS) == SPI_NSS_Hard)) +/** + * @} + */ + +/** @defgroup SPI_BaudRate_Prescaler + * @{ + */ + +#define SPI_BaudRatePrescaler_2 ((uint16_t)0x0000) +#define SPI_BaudRatePrescaler_4 ((uint16_t)0x0008) +#define SPI_BaudRatePrescaler_8 ((uint16_t)0x0010) +#define SPI_BaudRatePrescaler_16 ((uint16_t)0x0018) +#define SPI_BaudRatePrescaler_32 ((uint16_t)0x0020) +#define SPI_BaudRatePrescaler_64 ((uint16_t)0x0028) +#define SPI_BaudRatePrescaler_128 ((uint16_t)0x0030) +#define SPI_BaudRatePrescaler_256 ((uint16_t)0x0038) +#define IS_SPI_BAUDRATE_PRESCALER(PRESCALER) (((PRESCALER) == SPI_BaudRatePrescaler_2) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_4) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_8) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_16) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_32) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_64) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_128) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_256)) +/** + * @} + */ + +/** @defgroup SPI_MSB_LSB_transmission + * @{ + */ + +#define SPI_FirstBit_MSB ((uint16_t)0x0000) +#define SPI_FirstBit_LSB ((uint16_t)0x0080) +#define IS_SPI_FIRST_BIT(BIT) (((BIT) == SPI_FirstBit_MSB) || \ + ((BIT) == SPI_FirstBit_LSB)) +/** + * @} + */ + +/** @defgroup I2S_Mode + * @{ + */ + +#define I2S_Mode_SlaveTx ((uint16_t)0x0000) +#define I2S_Mode_SlaveRx ((uint16_t)0x0100) +#define I2S_Mode_MasterTx ((uint16_t)0x0200) +#define I2S_Mode_MasterRx ((uint16_t)0x0300) +#define IS_I2S_MODE(MODE) (((MODE) == I2S_Mode_SlaveTx) || \ + ((MODE) == I2S_Mode_SlaveRx) || \ + ((MODE) == I2S_Mode_MasterTx) || \ + ((MODE) == I2S_Mode_MasterRx) ) +/** + * @} + */ + +/** @defgroup I2S_Standard + * @{ + */ + +#define I2S_Standard_Phillips ((uint16_t)0x0000) +#define I2S_Standard_MSB ((uint16_t)0x0010) +#define I2S_Standard_LSB ((uint16_t)0x0020) +#define I2S_Standard_PCMShort ((uint16_t)0x0030) +#define I2S_Standard_PCMLong ((uint16_t)0x00B0) +#define IS_I2S_STANDARD(STANDARD) (((STANDARD) == I2S_Standard_Phillips) || \ + ((STANDARD) == I2S_Standard_MSB) || \ + ((STANDARD) == I2S_Standard_LSB) || \ + ((STANDARD) == I2S_Standard_PCMShort) || \ + ((STANDARD) == I2S_Standard_PCMLong)) +/** + * @} + */ + +/** @defgroup I2S_Data_Format + * @{ + */ + +#define I2S_DataFormat_16b ((uint16_t)0x0000) +#define I2S_DataFormat_16bextended ((uint16_t)0x0001) +#define I2S_DataFormat_24b ((uint16_t)0x0003) +#define I2S_DataFormat_32b ((uint16_t)0x0005) +#define IS_I2S_DATA_FORMAT(FORMAT) (((FORMAT) == I2S_DataFormat_16b) || \ + ((FORMAT) == I2S_DataFormat_16bextended) || \ + ((FORMAT) == I2S_DataFormat_24b) || \ + ((FORMAT) == I2S_DataFormat_32b)) +/** + * @} + */ + +/** @defgroup I2S_MCLK_Output + * @{ + */ + +#define I2S_MCLKOutput_Enable ((uint16_t)0x0200) +#define I2S_MCLKOutput_Disable ((uint16_t)0x0000) +#define IS_I2S_MCLK_OUTPUT(OUTPUT) (((OUTPUT) == I2S_MCLKOutput_Enable) || \ + ((OUTPUT) == I2S_MCLKOutput_Disable)) +/** + * @} + */ + +/** @defgroup I2S_Audio_Frequency + * @{ + */ + +#define I2S_AudioFreq_192k ((uint32_t)192000) +#define I2S_AudioFreq_96k ((uint32_t)96000) +#define I2S_AudioFreq_48k ((uint32_t)48000) +#define I2S_AudioFreq_44k ((uint32_t)44100) +#define I2S_AudioFreq_32k ((uint32_t)32000) +#define I2S_AudioFreq_22k ((uint32_t)22050) +#define I2S_AudioFreq_16k ((uint32_t)16000) +#define I2S_AudioFreq_11k ((uint32_t)11025) +#define I2S_AudioFreq_8k ((uint32_t)8000) +#define I2S_AudioFreq_Default ((uint32_t)2) + +#define IS_I2S_AUDIO_FREQ(FREQ) ((((FREQ) >= I2S_AudioFreq_8k) && \ + ((FREQ) <= I2S_AudioFreq_192k)) || \ + ((FREQ) == I2S_AudioFreq_Default)) +/** + * @} + */ + +/** @defgroup I2S_Clock_Polarity + * @{ + */ + +#define I2S_CPOL_Low ((uint16_t)0x0000) +#define I2S_CPOL_High ((uint16_t)0x0008) +#define IS_I2S_CPOL(CPOL) (((CPOL) == I2S_CPOL_Low) || \ + ((CPOL) == I2S_CPOL_High)) +/** + * @} + */ + +/** @defgroup SPI_I2S_DMA_transfer_requests + * @{ + */ + +#define SPI_I2S_DMAReq_Tx ((uint16_t)0x0002) +#define SPI_I2S_DMAReq_Rx ((uint16_t)0x0001) +#define IS_SPI_I2S_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFFFC) == 0x00) && ((DMAREQ) != 0x00)) +/** + * @} + */ + +/** @defgroup SPI_NSS_internal_software_management + * @{ + */ + +#define SPI_NSSInternalSoft_Set ((uint16_t)0x0100) +#define SPI_NSSInternalSoft_Reset ((uint16_t)0xFEFF) +#define IS_SPI_NSS_INTERNAL(INTERNAL) (((INTERNAL) == SPI_NSSInternalSoft_Set) || \ + ((INTERNAL) == SPI_NSSInternalSoft_Reset)) +/** + * @} + */ + +/** @defgroup SPI_CRC_Transmit_Receive + * @{ + */ + +#define SPI_CRC_Tx ((uint8_t)0x00) +#define SPI_CRC_Rx ((uint8_t)0x01) +#define IS_SPI_CRC(CRC) (((CRC) == SPI_CRC_Tx) || ((CRC) == SPI_CRC_Rx)) +/** + * @} + */ + +/** @defgroup SPI_direction_transmit_receive + * @{ + */ + +#define SPI_Direction_Rx ((uint16_t)0xBFFF) +#define SPI_Direction_Tx ((uint16_t)0x4000) +#define IS_SPI_DIRECTION(DIRECTION) (((DIRECTION) == SPI_Direction_Rx) || \ + ((DIRECTION) == SPI_Direction_Tx)) +/** + * @} + */ + +/** @defgroup SPI_I2S_interrupts_definition + * @{ + */ + +#define SPI_I2S_IT_TXE ((uint8_t)0x71) +#define SPI_I2S_IT_RXNE ((uint8_t)0x60) +#define SPI_I2S_IT_ERR ((uint8_t)0x50) +#define IS_SPI_I2S_CONFIG_IT(IT) (((IT) == SPI_I2S_IT_TXE) || \ + ((IT) == SPI_I2S_IT_RXNE) || \ + ((IT) == SPI_I2S_IT_ERR)) +#define SPI_I2S_IT_OVR ((uint8_t)0x56) +#define SPI_IT_MODF ((uint8_t)0x55) +#define SPI_IT_CRCERR ((uint8_t)0x54) +#define I2S_IT_UDR ((uint8_t)0x53) +#define IS_SPI_I2S_CLEAR_IT(IT) (((IT) == SPI_IT_CRCERR)) +#define IS_SPI_I2S_GET_IT(IT) (((IT) == SPI_I2S_IT_RXNE) || ((IT) == SPI_I2S_IT_TXE) || \ + ((IT) == I2S_IT_UDR) || ((IT) == SPI_IT_CRCERR) || \ + ((IT) == SPI_IT_MODF) || ((IT) == SPI_I2S_IT_OVR)) +/** + * @} + */ + +/** @defgroup SPI_I2S_flags_definition + * @{ + */ + +#define SPI_I2S_FLAG_RXNE ((uint16_t)0x0001) +#define SPI_I2S_FLAG_TXE ((uint16_t)0x0002) +#define I2S_FLAG_CHSIDE ((uint16_t)0x0004) +#define I2S_FLAG_UDR ((uint16_t)0x0008) +#define SPI_FLAG_CRCERR ((uint16_t)0x0010) +#define SPI_FLAG_MODF ((uint16_t)0x0020) +#define SPI_I2S_FLAG_OVR ((uint16_t)0x0040) +#define SPI_I2S_FLAG_BSY ((uint16_t)0x0080) +#define IS_SPI_I2S_CLEAR_FLAG(FLAG) (((FLAG) == SPI_FLAG_CRCERR)) +#define IS_SPI_I2S_GET_FLAG(FLAG) (((FLAG) == SPI_I2S_FLAG_BSY) || ((FLAG) == SPI_I2S_FLAG_OVR) || \ + ((FLAG) == SPI_FLAG_MODF) || ((FLAG) == SPI_FLAG_CRCERR) || \ + ((FLAG) == I2S_FLAG_UDR) || ((FLAG) == I2S_FLAG_CHSIDE) || \ + ((FLAG) == SPI_I2S_FLAG_TXE) || ((FLAG) == SPI_I2S_FLAG_RXNE)) +/** + * @} + */ + +/** @defgroup SPI_CRC_polynomial + * @{ + */ + +#define IS_SPI_CRC_POLYNOMIAL(POLYNOMIAL) ((POLYNOMIAL) >= 0x1) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup SPI_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup SPI_Exported_Functions + * @{ + */ + +void SPI_I2S_DeInit(SPI_TypeDef* SPIx); +void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct); +void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct); +void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct); +void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct); +void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState); +void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState); +void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data); +uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx); +void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft); +void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize); +void SPI_TransmitCRC(SPI_TypeDef* SPIx); +void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState); +uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC); +uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx); +void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction); +FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); +void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); +ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT); +void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_SPI_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h new file mode 100644 index 0000000..65bf76a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h @@ -0,0 +1,1164 @@ +/** + ****************************************************************************** + * @file stm32f10x_tim.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the TIM firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_TIM_H +#define __STM32F10x_TIM_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup TIM + * @{ + */ + +/** @defgroup TIM_Exported_Types + * @{ + */ + +/** + * @brief TIM Time Base Init structure definition + * @note This structure is used with all TIMx except for TIM6 and TIM7. + */ + +typedef struct +{ + uint16_t TIM_Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock. + This parameter can be a number between 0x0000 and 0xFFFF */ + + uint16_t TIM_CounterMode; /*!< Specifies the counter mode. + This parameter can be a value of @ref TIM_Counter_Mode */ + + uint16_t TIM_Period; /*!< Specifies the period value to be loaded into the active + Auto-Reload Register at the next update event. + This parameter must be a number between 0x0000 and 0xFFFF. */ + + uint16_t TIM_ClockDivision; /*!< Specifies the clock division. + This parameter can be a value of @ref TIM_Clock_Division_CKD */ + + uint8_t TIM_RepetitionCounter; /*!< Specifies the repetition counter value. Each time the RCR downcounter + reaches zero, an update event is generated and counting restarts + from the RCR value (N). + This means in PWM mode that (N+1) corresponds to: + - the number of PWM periods in edge-aligned mode + - the number of half PWM period in center-aligned mode + This parameter must be a number between 0x00 and 0xFF. + @note This parameter is valid only for TIM1 and TIM8. */ +} TIM_TimeBaseInitTypeDef; + +/** + * @brief TIM Output Compare Init structure definition + */ + +typedef struct +{ + uint16_t TIM_OCMode; /*!< Specifies the TIM mode. + This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */ + + uint16_t TIM_OutputState; /*!< Specifies the TIM Output Compare state. + This parameter can be a value of @ref TIM_Output_Compare_state */ + + uint16_t TIM_OutputNState; /*!< Specifies the TIM complementary Output Compare state. + This parameter can be a value of @ref TIM_Output_Compare_N_state + @note This parameter is valid only for TIM1 and TIM8. */ + + uint16_t TIM_Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. + This parameter can be a number between 0x0000 and 0xFFFF */ + + uint16_t TIM_OCPolarity; /*!< Specifies the output polarity. + This parameter can be a value of @ref TIM_Output_Compare_Polarity */ + + uint16_t TIM_OCNPolarity; /*!< Specifies the complementary output polarity. + This parameter can be a value of @ref TIM_Output_Compare_N_Polarity + @note This parameter is valid only for TIM1 and TIM8. */ + + uint16_t TIM_OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_Output_Compare_Idle_State + @note This parameter is valid only for TIM1 and TIM8. */ + + uint16_t TIM_OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State + @note This parameter is valid only for TIM1 and TIM8. */ +} TIM_OCInitTypeDef; + +/** + * @brief TIM Input Capture Init structure definition + */ + +typedef struct +{ + + uint16_t TIM_Channel; /*!< Specifies the TIM channel. + This parameter can be a value of @ref TIM_Channel */ + + uint16_t TIM_ICPolarity; /*!< Specifies the active edge of the input signal. + This parameter can be a value of @ref TIM_Input_Capture_Polarity */ + + uint16_t TIM_ICSelection; /*!< Specifies the input. + This parameter can be a value of @ref TIM_Input_Capture_Selection */ + + uint16_t TIM_ICPrescaler; /*!< Specifies the Input Capture Prescaler. + This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ + + uint16_t TIM_ICFilter; /*!< Specifies the input capture filter. + This parameter can be a number between 0x0 and 0xF */ +} TIM_ICInitTypeDef; + +/** + * @brief BDTR structure definition + * @note This structure is used only with TIM1 and TIM8. + */ + +typedef struct +{ + + uint16_t TIM_OSSRState; /*!< Specifies the Off-State selection used in Run mode. + This parameter can be a value of @ref OSSR_Off_State_Selection_for_Run_mode_state */ + + uint16_t TIM_OSSIState; /*!< Specifies the Off-State used in Idle state. + This parameter can be a value of @ref OSSI_Off_State_Selection_for_Idle_mode_state */ + + uint16_t TIM_LOCKLevel; /*!< Specifies the LOCK level parameters. + This parameter can be a value of @ref Lock_level */ + + uint16_t TIM_DeadTime; /*!< Specifies the delay time between the switching-off and the + switching-on of the outputs. + This parameter can be a number between 0x00 and 0xFF */ + + uint16_t TIM_Break; /*!< Specifies whether the TIM Break input is enabled or not. + This parameter can be a value of @ref Break_Input_enable_disable */ + + uint16_t TIM_BreakPolarity; /*!< Specifies the TIM Break Input pin polarity. + This parameter can be a value of @ref Break_Polarity */ + + uint16_t TIM_AutomaticOutput; /*!< Specifies whether the TIM Automatic Output feature is enabled or not. + This parameter can be a value of @ref TIM_AOE_Bit_Set_Reset */ +} TIM_BDTRInitTypeDef; + +/** @defgroup TIM_Exported_constants + * @{ + */ + +#define IS_TIM_ALL_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM6) || \ + ((PERIPH) == TIM7) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM9) || \ + ((PERIPH) == TIM10)|| \ + ((PERIPH) == TIM11)|| \ + ((PERIPH) == TIM12)|| \ + ((PERIPH) == TIM13)|| \ + ((PERIPH) == TIM14)|| \ + ((PERIPH) == TIM15)|| \ + ((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM17)) + +/* LIST1: TIM 1 and 8 */ +#define IS_TIM_LIST1_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM8)) + +/* LIST2: TIM 1, 8, 15 16 and 17 */ +#define IS_TIM_LIST2_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15)|| \ + ((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM17)) + +/* LIST3: TIM 1, 2, 3, 4, 5 and 8 */ +#define IS_TIM_LIST3_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8)) + +/* LIST4: TIM 1, 2, 3, 4, 5, 8, 15, 16 and 17 */ +#define IS_TIM_LIST4_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15)|| \ + ((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM17)) + +/* LIST5: TIM 1, 2, 3, 4, 5, 8 and 15 */ +#define IS_TIM_LIST5_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15)) + +/* LIST6: TIM 1, 2, 3, 4, 5, 8, 9, 12 and 15 */ +#define IS_TIM_LIST6_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM9) || \ + ((PERIPH) == TIM12)|| \ + ((PERIPH) == TIM15)) + +/* LIST7: TIM 1, 2, 3, 4, 5, 6, 7, 8, 9, 12 and 15 */ +#define IS_TIM_LIST7_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM6) || \ + ((PERIPH) == TIM7) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM9) || \ + ((PERIPH) == TIM12)|| \ + ((PERIPH) == TIM15)) + +/* LIST8: TIM 1, 2, 3, 4, 5, 8, 9, 10, 11, 12, 13, 14, 15, 16 and 17 */ +#define IS_TIM_LIST8_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM9) || \ + ((PERIPH) == TIM10)|| \ + ((PERIPH) == TIM11)|| \ + ((PERIPH) == TIM12)|| \ + ((PERIPH) == TIM13)|| \ + ((PERIPH) == TIM14)|| \ + ((PERIPH) == TIM15)|| \ + ((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM17)) + +/* LIST9: TIM 1, 2, 3, 4, 5, 6, 7, 8, 15, 16, and 17 */ +#define IS_TIM_LIST9_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM6) || \ + ((PERIPH) == TIM7) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15)|| \ + ((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM17)) + +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_and_PWM_modes + * @{ + */ + +#define TIM_OCMode_Timing ((uint16_t)0x0000) +#define TIM_OCMode_Active ((uint16_t)0x0010) +#define TIM_OCMode_Inactive ((uint16_t)0x0020) +#define TIM_OCMode_Toggle ((uint16_t)0x0030) +#define TIM_OCMode_PWM1 ((uint16_t)0x0060) +#define TIM_OCMode_PWM2 ((uint16_t)0x0070) +#define IS_TIM_OC_MODE(MODE) (((MODE) == TIM_OCMode_Timing) || \ + ((MODE) == TIM_OCMode_Active) || \ + ((MODE) == TIM_OCMode_Inactive) || \ + ((MODE) == TIM_OCMode_Toggle)|| \ + ((MODE) == TIM_OCMode_PWM1) || \ + ((MODE) == TIM_OCMode_PWM2)) +#define IS_TIM_OCM(MODE) (((MODE) == TIM_OCMode_Timing) || \ + ((MODE) == TIM_OCMode_Active) || \ + ((MODE) == TIM_OCMode_Inactive) || \ + ((MODE) == TIM_OCMode_Toggle)|| \ + ((MODE) == TIM_OCMode_PWM1) || \ + ((MODE) == TIM_OCMode_PWM2) || \ + ((MODE) == TIM_ForcedAction_Active) || \ + ((MODE) == TIM_ForcedAction_InActive)) +/** + * @} + */ + +/** @defgroup TIM_One_Pulse_Mode + * @{ + */ + +#define TIM_OPMode_Single ((uint16_t)0x0008) +#define TIM_OPMode_Repetitive ((uint16_t)0x0000) +#define IS_TIM_OPM_MODE(MODE) (((MODE) == TIM_OPMode_Single) || \ + ((MODE) == TIM_OPMode_Repetitive)) +/** + * @} + */ + +/** @defgroup TIM_Channel + * @{ + */ + +#define TIM_Channel_1 ((uint16_t)0x0000) +#define TIM_Channel_2 ((uint16_t)0x0004) +#define TIM_Channel_3 ((uint16_t)0x0008) +#define TIM_Channel_4 ((uint16_t)0x000C) +#define IS_TIM_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ + ((CHANNEL) == TIM_Channel_2) || \ + ((CHANNEL) == TIM_Channel_3) || \ + ((CHANNEL) == TIM_Channel_4)) +#define IS_TIM_PWMI_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ + ((CHANNEL) == TIM_Channel_2)) +#define IS_TIM_COMPLEMENTARY_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ + ((CHANNEL) == TIM_Channel_2) || \ + ((CHANNEL) == TIM_Channel_3)) +/** + * @} + */ + +/** @defgroup TIM_Clock_Division_CKD + * @{ + */ + +#define TIM_CKD_DIV1 ((uint16_t)0x0000) +#define TIM_CKD_DIV2 ((uint16_t)0x0100) +#define TIM_CKD_DIV4 ((uint16_t)0x0200) +#define IS_TIM_CKD_DIV(DIV) (((DIV) == TIM_CKD_DIV1) || \ + ((DIV) == TIM_CKD_DIV2) || \ + ((DIV) == TIM_CKD_DIV4)) +/** + * @} + */ + +/** @defgroup TIM_Counter_Mode + * @{ + */ + +#define TIM_CounterMode_Up ((uint16_t)0x0000) +#define TIM_CounterMode_Down ((uint16_t)0x0010) +#define TIM_CounterMode_CenterAligned1 ((uint16_t)0x0020) +#define TIM_CounterMode_CenterAligned2 ((uint16_t)0x0040) +#define TIM_CounterMode_CenterAligned3 ((uint16_t)0x0060) +#define IS_TIM_COUNTER_MODE(MODE) (((MODE) == TIM_CounterMode_Up) || \ + ((MODE) == TIM_CounterMode_Down) || \ + ((MODE) == TIM_CounterMode_CenterAligned1) || \ + ((MODE) == TIM_CounterMode_CenterAligned2) || \ + ((MODE) == TIM_CounterMode_CenterAligned3)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Polarity + * @{ + */ + +#define TIM_OCPolarity_High ((uint16_t)0x0000) +#define TIM_OCPolarity_Low ((uint16_t)0x0002) +#define IS_TIM_OC_POLARITY(POLARITY) (((POLARITY) == TIM_OCPolarity_High) || \ + ((POLARITY) == TIM_OCPolarity_Low)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_Polarity + * @{ + */ + +#define TIM_OCNPolarity_High ((uint16_t)0x0000) +#define TIM_OCNPolarity_Low ((uint16_t)0x0008) +#define IS_TIM_OCN_POLARITY(POLARITY) (((POLARITY) == TIM_OCNPolarity_High) || \ + ((POLARITY) == TIM_OCNPolarity_Low)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_state + * @{ + */ + +#define TIM_OutputState_Disable ((uint16_t)0x0000) +#define TIM_OutputState_Enable ((uint16_t)0x0001) +#define IS_TIM_OUTPUT_STATE(STATE) (((STATE) == TIM_OutputState_Disable) || \ + ((STATE) == TIM_OutputState_Enable)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_state + * @{ + */ + +#define TIM_OutputNState_Disable ((uint16_t)0x0000) +#define TIM_OutputNState_Enable ((uint16_t)0x0004) +#define IS_TIM_OUTPUTN_STATE(STATE) (((STATE) == TIM_OutputNState_Disable) || \ + ((STATE) == TIM_OutputNState_Enable)) +/** + * @} + */ + +/** @defgroup TIM_Capture_Compare_state + * @{ + */ + +#define TIM_CCx_Enable ((uint16_t)0x0001) +#define TIM_CCx_Disable ((uint16_t)0x0000) +#define IS_TIM_CCX(CCX) (((CCX) == TIM_CCx_Enable) || \ + ((CCX) == TIM_CCx_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Capture_Compare_N_state + * @{ + */ + +#define TIM_CCxN_Enable ((uint16_t)0x0004) +#define TIM_CCxN_Disable ((uint16_t)0x0000) +#define IS_TIM_CCXN(CCXN) (((CCXN) == TIM_CCxN_Enable) || \ + ((CCXN) == TIM_CCxN_Disable)) +/** + * @} + */ + +/** @defgroup Break_Input_enable_disable + * @{ + */ + +#define TIM_Break_Enable ((uint16_t)0x1000) +#define TIM_Break_Disable ((uint16_t)0x0000) +#define IS_TIM_BREAK_STATE(STATE) (((STATE) == TIM_Break_Enable) || \ + ((STATE) == TIM_Break_Disable)) +/** + * @} + */ + +/** @defgroup Break_Polarity + * @{ + */ + +#define TIM_BreakPolarity_Low ((uint16_t)0x0000) +#define TIM_BreakPolarity_High ((uint16_t)0x2000) +#define IS_TIM_BREAK_POLARITY(POLARITY) (((POLARITY) == TIM_BreakPolarity_Low) || \ + ((POLARITY) == TIM_BreakPolarity_High)) +/** + * @} + */ + +/** @defgroup TIM_AOE_Bit_Set_Reset + * @{ + */ + +#define TIM_AutomaticOutput_Enable ((uint16_t)0x4000) +#define TIM_AutomaticOutput_Disable ((uint16_t)0x0000) +#define IS_TIM_AUTOMATIC_OUTPUT_STATE(STATE) (((STATE) == TIM_AutomaticOutput_Enable) || \ + ((STATE) == TIM_AutomaticOutput_Disable)) +/** + * @} + */ + +/** @defgroup Lock_level + * @{ + */ + +#define TIM_LOCKLevel_OFF ((uint16_t)0x0000) +#define TIM_LOCKLevel_1 ((uint16_t)0x0100) +#define TIM_LOCKLevel_2 ((uint16_t)0x0200) +#define TIM_LOCKLevel_3 ((uint16_t)0x0300) +#define IS_TIM_LOCK_LEVEL(LEVEL) (((LEVEL) == TIM_LOCKLevel_OFF) || \ + ((LEVEL) == TIM_LOCKLevel_1) || \ + ((LEVEL) == TIM_LOCKLevel_2) || \ + ((LEVEL) == TIM_LOCKLevel_3)) +/** + * @} + */ + +/** @defgroup OSSI_Off_State_Selection_for_Idle_mode_state + * @{ + */ + +#define TIM_OSSIState_Enable ((uint16_t)0x0400) +#define TIM_OSSIState_Disable ((uint16_t)0x0000) +#define IS_TIM_OSSI_STATE(STATE) (((STATE) == TIM_OSSIState_Enable) || \ + ((STATE) == TIM_OSSIState_Disable)) +/** + * @} + */ + +/** @defgroup OSSR_Off_State_Selection_for_Run_mode_state + * @{ + */ + +#define TIM_OSSRState_Enable ((uint16_t)0x0800) +#define TIM_OSSRState_Disable ((uint16_t)0x0000) +#define IS_TIM_OSSR_STATE(STATE) (((STATE) == TIM_OSSRState_Enable) || \ + ((STATE) == TIM_OSSRState_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Idle_State + * @{ + */ + +#define TIM_OCIdleState_Set ((uint16_t)0x0100) +#define TIM_OCIdleState_Reset ((uint16_t)0x0000) +#define IS_TIM_OCIDLE_STATE(STATE) (((STATE) == TIM_OCIdleState_Set) || \ + ((STATE) == TIM_OCIdleState_Reset)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_Idle_State + * @{ + */ + +#define TIM_OCNIdleState_Set ((uint16_t)0x0200) +#define TIM_OCNIdleState_Reset ((uint16_t)0x0000) +#define IS_TIM_OCNIDLE_STATE(STATE) (((STATE) == TIM_OCNIdleState_Set) || \ + ((STATE) == TIM_OCNIdleState_Reset)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Polarity + * @{ + */ + +#define TIM_ICPolarity_Rising ((uint16_t)0x0000) +#define TIM_ICPolarity_Falling ((uint16_t)0x0002) +#define TIM_ICPolarity_BothEdge ((uint16_t)0x000A) +#define IS_TIM_IC_POLARITY(POLARITY) (((POLARITY) == TIM_ICPolarity_Rising) || \ + ((POLARITY) == TIM_ICPolarity_Falling)) +#define IS_TIM_IC_POLARITY_LITE(POLARITY) (((POLARITY) == TIM_ICPolarity_Rising) || \ + ((POLARITY) == TIM_ICPolarity_Falling)|| \ + ((POLARITY) == TIM_ICPolarity_BothEdge)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Selection + * @{ + */ + +#define TIM_ICSelection_DirectTI ((uint16_t)0x0001) /*!< TIM Input 1, 2, 3 or 4 is selected to be + connected to IC1, IC2, IC3 or IC4, respectively */ +#define TIM_ICSelection_IndirectTI ((uint16_t)0x0002) /*!< TIM Input 1, 2, 3 or 4 is selected to be + connected to IC2, IC1, IC4 or IC3, respectively. */ +#define TIM_ICSelection_TRC ((uint16_t)0x0003) /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to TRC. */ +#define IS_TIM_IC_SELECTION(SELECTION) (((SELECTION) == TIM_ICSelection_DirectTI) || \ + ((SELECTION) == TIM_ICSelection_IndirectTI) || \ + ((SELECTION) == TIM_ICSelection_TRC)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Prescaler + * @{ + */ + +#define TIM_ICPSC_DIV1 ((uint16_t)0x0000) /*!< Capture performed each time an edge is detected on the capture input. */ +#define TIM_ICPSC_DIV2 ((uint16_t)0x0004) /*!< Capture performed once every 2 events. */ +#define TIM_ICPSC_DIV4 ((uint16_t)0x0008) /*!< Capture performed once every 4 events. */ +#define TIM_ICPSC_DIV8 ((uint16_t)0x000C) /*!< Capture performed once every 8 events. */ +#define IS_TIM_IC_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ICPSC_DIV1) || \ + ((PRESCALER) == TIM_ICPSC_DIV2) || \ + ((PRESCALER) == TIM_ICPSC_DIV4) || \ + ((PRESCALER) == TIM_ICPSC_DIV8)) +/** + * @} + */ + +/** @defgroup TIM_interrupt_sources + * @{ + */ + +#define TIM_IT_Update ((uint16_t)0x0001) +#define TIM_IT_CC1 ((uint16_t)0x0002) +#define TIM_IT_CC2 ((uint16_t)0x0004) +#define TIM_IT_CC3 ((uint16_t)0x0008) +#define TIM_IT_CC4 ((uint16_t)0x0010) +#define TIM_IT_COM ((uint16_t)0x0020) +#define TIM_IT_Trigger ((uint16_t)0x0040) +#define TIM_IT_Break ((uint16_t)0x0080) +#define IS_TIM_IT(IT) ((((IT) & (uint16_t)0xFF00) == 0x0000) && ((IT) != 0x0000)) + +#define IS_TIM_GET_IT(IT) (((IT) == TIM_IT_Update) || \ + ((IT) == TIM_IT_CC1) || \ + ((IT) == TIM_IT_CC2) || \ + ((IT) == TIM_IT_CC3) || \ + ((IT) == TIM_IT_CC4) || \ + ((IT) == TIM_IT_COM) || \ + ((IT) == TIM_IT_Trigger) || \ + ((IT) == TIM_IT_Break)) +/** + * @} + */ + +/** @defgroup TIM_DMA_Base_address + * @{ + */ + +#define TIM_DMABase_CR1 ((uint16_t)0x0000) +#define TIM_DMABase_CR2 ((uint16_t)0x0001) +#define TIM_DMABase_SMCR ((uint16_t)0x0002) +#define TIM_DMABase_DIER ((uint16_t)0x0003) +#define TIM_DMABase_SR ((uint16_t)0x0004) +#define TIM_DMABase_EGR ((uint16_t)0x0005) +#define TIM_DMABase_CCMR1 ((uint16_t)0x0006) +#define TIM_DMABase_CCMR2 ((uint16_t)0x0007) +#define TIM_DMABase_CCER ((uint16_t)0x0008) +#define TIM_DMABase_CNT ((uint16_t)0x0009) +#define TIM_DMABase_PSC ((uint16_t)0x000A) +#define TIM_DMABase_ARR ((uint16_t)0x000B) +#define TIM_DMABase_RCR ((uint16_t)0x000C) +#define TIM_DMABase_CCR1 ((uint16_t)0x000D) +#define TIM_DMABase_CCR2 ((uint16_t)0x000E) +#define TIM_DMABase_CCR3 ((uint16_t)0x000F) +#define TIM_DMABase_CCR4 ((uint16_t)0x0010) +#define TIM_DMABase_BDTR ((uint16_t)0x0011) +#define TIM_DMABase_DCR ((uint16_t)0x0012) +#define IS_TIM_DMA_BASE(BASE) (((BASE) == TIM_DMABase_CR1) || \ + ((BASE) == TIM_DMABase_CR2) || \ + ((BASE) == TIM_DMABase_SMCR) || \ + ((BASE) == TIM_DMABase_DIER) || \ + ((BASE) == TIM_DMABase_SR) || \ + ((BASE) == TIM_DMABase_EGR) || \ + ((BASE) == TIM_DMABase_CCMR1) || \ + ((BASE) == TIM_DMABase_CCMR2) || \ + ((BASE) == TIM_DMABase_CCER) || \ + ((BASE) == TIM_DMABase_CNT) || \ + ((BASE) == TIM_DMABase_PSC) || \ + ((BASE) == TIM_DMABase_ARR) || \ + ((BASE) == TIM_DMABase_RCR) || \ + ((BASE) == TIM_DMABase_CCR1) || \ + ((BASE) == TIM_DMABase_CCR2) || \ + ((BASE) == TIM_DMABase_CCR3) || \ + ((BASE) == TIM_DMABase_CCR4) || \ + ((BASE) == TIM_DMABase_BDTR) || \ + ((BASE) == TIM_DMABase_DCR)) +/** + * @} + */ + +/** @defgroup TIM_DMA_Burst_Length + * @{ + */ + +#define TIM_DMABurstLength_1Transfer ((uint16_t)0x0000) +#define TIM_DMABurstLength_2Transfers ((uint16_t)0x0100) +#define TIM_DMABurstLength_3Transfers ((uint16_t)0x0200) +#define TIM_DMABurstLength_4Transfers ((uint16_t)0x0300) +#define TIM_DMABurstLength_5Transfers ((uint16_t)0x0400) +#define TIM_DMABurstLength_6Transfers ((uint16_t)0x0500) +#define TIM_DMABurstLength_7Transfers ((uint16_t)0x0600) +#define TIM_DMABurstLength_8Transfers ((uint16_t)0x0700) +#define TIM_DMABurstLength_9Transfers ((uint16_t)0x0800) +#define TIM_DMABurstLength_10Transfers ((uint16_t)0x0900) +#define TIM_DMABurstLength_11Transfers ((uint16_t)0x0A00) +#define TIM_DMABurstLength_12Transfers ((uint16_t)0x0B00) +#define TIM_DMABurstLength_13Transfers ((uint16_t)0x0C00) +#define TIM_DMABurstLength_14Transfers ((uint16_t)0x0D00) +#define TIM_DMABurstLength_15Transfers ((uint16_t)0x0E00) +#define TIM_DMABurstLength_16Transfers ((uint16_t)0x0F00) +#define TIM_DMABurstLength_17Transfers ((uint16_t)0x1000) +#define TIM_DMABurstLength_18Transfers ((uint16_t)0x1100) +#define IS_TIM_DMA_LENGTH(LENGTH) (((LENGTH) == TIM_DMABurstLength_1Transfer) || \ + ((LENGTH) == TIM_DMABurstLength_2Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_3Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_4Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_5Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_6Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_7Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_8Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_9Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_10Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_11Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_12Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_13Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_14Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_15Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_16Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_17Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_18Transfers)) +/** + * @} + */ + +/** @defgroup TIM_DMA_sources + * @{ + */ + +#define TIM_DMA_Update ((uint16_t)0x0100) +#define TIM_DMA_CC1 ((uint16_t)0x0200) +#define TIM_DMA_CC2 ((uint16_t)0x0400) +#define TIM_DMA_CC3 ((uint16_t)0x0800) +#define TIM_DMA_CC4 ((uint16_t)0x1000) +#define TIM_DMA_COM ((uint16_t)0x2000) +#define TIM_DMA_Trigger ((uint16_t)0x4000) +#define IS_TIM_DMA_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0x80FF) == 0x0000) && ((SOURCE) != 0x0000)) + +/** + * @} + */ + +/** @defgroup TIM_External_Trigger_Prescaler + * @{ + */ + +#define TIM_ExtTRGPSC_OFF ((uint16_t)0x0000) +#define TIM_ExtTRGPSC_DIV2 ((uint16_t)0x1000) +#define TIM_ExtTRGPSC_DIV4 ((uint16_t)0x2000) +#define TIM_ExtTRGPSC_DIV8 ((uint16_t)0x3000) +#define IS_TIM_EXT_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ExtTRGPSC_OFF) || \ + ((PRESCALER) == TIM_ExtTRGPSC_DIV2) || \ + ((PRESCALER) == TIM_ExtTRGPSC_DIV4) || \ + ((PRESCALER) == TIM_ExtTRGPSC_DIV8)) +/** + * @} + */ + +/** @defgroup TIM_Internal_Trigger_Selection + * @{ + */ + +#define TIM_TS_ITR0 ((uint16_t)0x0000) +#define TIM_TS_ITR1 ((uint16_t)0x0010) +#define TIM_TS_ITR2 ((uint16_t)0x0020) +#define TIM_TS_ITR3 ((uint16_t)0x0030) +#define TIM_TS_TI1F_ED ((uint16_t)0x0040) +#define TIM_TS_TI1FP1 ((uint16_t)0x0050) +#define TIM_TS_TI2FP2 ((uint16_t)0x0060) +#define TIM_TS_ETRF ((uint16_t)0x0070) +#define IS_TIM_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \ + ((SELECTION) == TIM_TS_ITR1) || \ + ((SELECTION) == TIM_TS_ITR2) || \ + ((SELECTION) == TIM_TS_ITR3) || \ + ((SELECTION) == TIM_TS_TI1F_ED) || \ + ((SELECTION) == TIM_TS_TI1FP1) || \ + ((SELECTION) == TIM_TS_TI2FP2) || \ + ((SELECTION) == TIM_TS_ETRF)) +#define IS_TIM_INTERNAL_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \ + ((SELECTION) == TIM_TS_ITR1) || \ + ((SELECTION) == TIM_TS_ITR2) || \ + ((SELECTION) == TIM_TS_ITR3)) +/** + * @} + */ + +/** @defgroup TIM_TIx_External_Clock_Source + * @{ + */ + +#define TIM_TIxExternalCLK1Source_TI1 ((uint16_t)0x0050) +#define TIM_TIxExternalCLK1Source_TI2 ((uint16_t)0x0060) +#define TIM_TIxExternalCLK1Source_TI1ED ((uint16_t)0x0040) +#define IS_TIM_TIXCLK_SOURCE(SOURCE) (((SOURCE) == TIM_TIxExternalCLK1Source_TI1) || \ + ((SOURCE) == TIM_TIxExternalCLK1Source_TI2) || \ + ((SOURCE) == TIM_TIxExternalCLK1Source_TI1ED)) +/** + * @} + */ + +/** @defgroup TIM_External_Trigger_Polarity + * @{ + */ +#define TIM_ExtTRGPolarity_Inverted ((uint16_t)0x8000) +#define TIM_ExtTRGPolarity_NonInverted ((uint16_t)0x0000) +#define IS_TIM_EXT_POLARITY(POLARITY) (((POLARITY) == TIM_ExtTRGPolarity_Inverted) || \ + ((POLARITY) == TIM_ExtTRGPolarity_NonInverted)) +/** + * @} + */ + +/** @defgroup TIM_Prescaler_Reload_Mode + * @{ + */ + +#define TIM_PSCReloadMode_Update ((uint16_t)0x0000) +#define TIM_PSCReloadMode_Immediate ((uint16_t)0x0001) +#define IS_TIM_PRESCALER_RELOAD(RELOAD) (((RELOAD) == TIM_PSCReloadMode_Update) || \ + ((RELOAD) == TIM_PSCReloadMode_Immediate)) +/** + * @} + */ + +/** @defgroup TIM_Forced_Action + * @{ + */ + +#define TIM_ForcedAction_Active ((uint16_t)0x0050) +#define TIM_ForcedAction_InActive ((uint16_t)0x0040) +#define IS_TIM_FORCED_ACTION(ACTION) (((ACTION) == TIM_ForcedAction_Active) || \ + ((ACTION) == TIM_ForcedAction_InActive)) +/** + * @} + */ + +/** @defgroup TIM_Encoder_Mode + * @{ + */ + +#define TIM_EncoderMode_TI1 ((uint16_t)0x0001) +#define TIM_EncoderMode_TI2 ((uint16_t)0x0002) +#define TIM_EncoderMode_TI12 ((uint16_t)0x0003) +#define IS_TIM_ENCODER_MODE(MODE) (((MODE) == TIM_EncoderMode_TI1) || \ + ((MODE) == TIM_EncoderMode_TI2) || \ + ((MODE) == TIM_EncoderMode_TI12)) +/** + * @} + */ + + +/** @defgroup TIM_Event_Source + * @{ + */ + +#define TIM_EventSource_Update ((uint16_t)0x0001) +#define TIM_EventSource_CC1 ((uint16_t)0x0002) +#define TIM_EventSource_CC2 ((uint16_t)0x0004) +#define TIM_EventSource_CC3 ((uint16_t)0x0008) +#define TIM_EventSource_CC4 ((uint16_t)0x0010) +#define TIM_EventSource_COM ((uint16_t)0x0020) +#define TIM_EventSource_Trigger ((uint16_t)0x0040) +#define TIM_EventSource_Break ((uint16_t)0x0080) +#define IS_TIM_EVENT_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0xFF00) == 0x0000) && ((SOURCE) != 0x0000)) + +/** + * @} + */ + +/** @defgroup TIM_Update_Source + * @{ + */ + +#define TIM_UpdateSource_Global ((uint16_t)0x0000) /*!< Source of update is the counter overflow/underflow + or the setting of UG bit, or an update generation + through the slave mode controller. */ +#define TIM_UpdateSource_Regular ((uint16_t)0x0001) /*!< Source of update is counter overflow/underflow. */ +#define IS_TIM_UPDATE_SOURCE(SOURCE) (((SOURCE) == TIM_UpdateSource_Global) || \ + ((SOURCE) == TIM_UpdateSource_Regular)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Preload_State + * @{ + */ + +#define TIM_OCPreload_Enable ((uint16_t)0x0008) +#define TIM_OCPreload_Disable ((uint16_t)0x0000) +#define IS_TIM_OCPRELOAD_STATE(STATE) (((STATE) == TIM_OCPreload_Enable) || \ + ((STATE) == TIM_OCPreload_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Fast_State + * @{ + */ + +#define TIM_OCFast_Enable ((uint16_t)0x0004) +#define TIM_OCFast_Disable ((uint16_t)0x0000) +#define IS_TIM_OCFAST_STATE(STATE) (((STATE) == TIM_OCFast_Enable) || \ + ((STATE) == TIM_OCFast_Disable)) + +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Clear_State + * @{ + */ + +#define TIM_OCClear_Enable ((uint16_t)0x0080) +#define TIM_OCClear_Disable ((uint16_t)0x0000) +#define IS_TIM_OCCLEAR_STATE(STATE) (((STATE) == TIM_OCClear_Enable) || \ + ((STATE) == TIM_OCClear_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Trigger_Output_Source + * @{ + */ + +#define TIM_TRGOSource_Reset ((uint16_t)0x0000) +#define TIM_TRGOSource_Enable ((uint16_t)0x0010) +#define TIM_TRGOSource_Update ((uint16_t)0x0020) +#define TIM_TRGOSource_OC1 ((uint16_t)0x0030) +#define TIM_TRGOSource_OC1Ref ((uint16_t)0x0040) +#define TIM_TRGOSource_OC2Ref ((uint16_t)0x0050) +#define TIM_TRGOSource_OC3Ref ((uint16_t)0x0060) +#define TIM_TRGOSource_OC4Ref ((uint16_t)0x0070) +#define IS_TIM_TRGO_SOURCE(SOURCE) (((SOURCE) == TIM_TRGOSource_Reset) || \ + ((SOURCE) == TIM_TRGOSource_Enable) || \ + ((SOURCE) == TIM_TRGOSource_Update) || \ + ((SOURCE) == TIM_TRGOSource_OC1) || \ + ((SOURCE) == TIM_TRGOSource_OC1Ref) || \ + ((SOURCE) == TIM_TRGOSource_OC2Ref) || \ + ((SOURCE) == TIM_TRGOSource_OC3Ref) || \ + ((SOURCE) == TIM_TRGOSource_OC4Ref)) +/** + * @} + */ + +/** @defgroup TIM_Slave_Mode + * @{ + */ + +#define TIM_SlaveMode_Reset ((uint16_t)0x0004) +#define TIM_SlaveMode_Gated ((uint16_t)0x0005) +#define TIM_SlaveMode_Trigger ((uint16_t)0x0006) +#define TIM_SlaveMode_External1 ((uint16_t)0x0007) +#define IS_TIM_SLAVE_MODE(MODE) (((MODE) == TIM_SlaveMode_Reset) || \ + ((MODE) == TIM_SlaveMode_Gated) || \ + ((MODE) == TIM_SlaveMode_Trigger) || \ + ((MODE) == TIM_SlaveMode_External1)) +/** + * @} + */ + +/** @defgroup TIM_Master_Slave_Mode + * @{ + */ + +#define TIM_MasterSlaveMode_Enable ((uint16_t)0x0080) +#define TIM_MasterSlaveMode_Disable ((uint16_t)0x0000) +#define IS_TIM_MSM_STATE(STATE) (((STATE) == TIM_MasterSlaveMode_Enable) || \ + ((STATE) == TIM_MasterSlaveMode_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Flags + * @{ + */ + +#define TIM_FLAG_Update ((uint16_t)0x0001) +#define TIM_FLAG_CC1 ((uint16_t)0x0002) +#define TIM_FLAG_CC2 ((uint16_t)0x0004) +#define TIM_FLAG_CC3 ((uint16_t)0x0008) +#define TIM_FLAG_CC4 ((uint16_t)0x0010) +#define TIM_FLAG_COM ((uint16_t)0x0020) +#define TIM_FLAG_Trigger ((uint16_t)0x0040) +#define TIM_FLAG_Break ((uint16_t)0x0080) +#define TIM_FLAG_CC1OF ((uint16_t)0x0200) +#define TIM_FLAG_CC2OF ((uint16_t)0x0400) +#define TIM_FLAG_CC3OF ((uint16_t)0x0800) +#define TIM_FLAG_CC4OF ((uint16_t)0x1000) +#define IS_TIM_GET_FLAG(FLAG) (((FLAG) == TIM_FLAG_Update) || \ + ((FLAG) == TIM_FLAG_CC1) || \ + ((FLAG) == TIM_FLAG_CC2) || \ + ((FLAG) == TIM_FLAG_CC3) || \ + ((FLAG) == TIM_FLAG_CC4) || \ + ((FLAG) == TIM_FLAG_COM) || \ + ((FLAG) == TIM_FLAG_Trigger) || \ + ((FLAG) == TIM_FLAG_Break) || \ + ((FLAG) == TIM_FLAG_CC1OF) || \ + ((FLAG) == TIM_FLAG_CC2OF) || \ + ((FLAG) == TIM_FLAG_CC3OF) || \ + ((FLAG) == TIM_FLAG_CC4OF)) + + +#define IS_TIM_CLEAR_FLAG(TIM_FLAG) ((((TIM_FLAG) & (uint16_t)0xE100) == 0x0000) && ((TIM_FLAG) != 0x0000)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Filer_Value + * @{ + */ + +#define IS_TIM_IC_FILTER(ICFILTER) ((ICFILTER) <= 0xF) +/** + * @} + */ + +/** @defgroup TIM_External_Trigger_Filter + * @{ + */ + +#define IS_TIM_EXT_FILTER(EXTFILTER) ((EXTFILTER) <= 0xF) +/** + * @} + */ + +/** @defgroup TIM_Legacy + * @{ + */ + +#define TIM_DMABurstLength_1Byte TIM_DMABurstLength_1Transfer +#define TIM_DMABurstLength_2Bytes TIM_DMABurstLength_2Transfers +#define TIM_DMABurstLength_3Bytes TIM_DMABurstLength_3Transfers +#define TIM_DMABurstLength_4Bytes TIM_DMABurstLength_4Transfers +#define TIM_DMABurstLength_5Bytes TIM_DMABurstLength_5Transfers +#define TIM_DMABurstLength_6Bytes TIM_DMABurstLength_6Transfers +#define TIM_DMABurstLength_7Bytes TIM_DMABurstLength_7Transfers +#define TIM_DMABurstLength_8Bytes TIM_DMABurstLength_8Transfers +#define TIM_DMABurstLength_9Bytes TIM_DMABurstLength_9Transfers +#define TIM_DMABurstLength_10Bytes TIM_DMABurstLength_10Transfers +#define TIM_DMABurstLength_11Bytes TIM_DMABurstLength_11Transfers +#define TIM_DMABurstLength_12Bytes TIM_DMABurstLength_12Transfers +#define TIM_DMABurstLength_13Bytes TIM_DMABurstLength_13Transfers +#define TIM_DMABurstLength_14Bytes TIM_DMABurstLength_14Transfers +#define TIM_DMABurstLength_15Bytes TIM_DMABurstLength_15Transfers +#define TIM_DMABurstLength_16Bytes TIM_DMABurstLength_16Transfers +#define TIM_DMABurstLength_17Bytes TIM_DMABurstLength_17Transfers +#define TIM_DMABurstLength_18Bytes TIM_DMABurstLength_18Transfers +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup TIM_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions + * @{ + */ + +void TIM_DeInit(TIM_TypeDef* TIMx); +void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); +void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct); +void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct); +void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct); +void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); +void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct); +void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct); +void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState); +void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource); +void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength); +void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState); +void TIM_InternalClockConfig(TIM_TypeDef* TIMx); +void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); +void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource, + uint16_t TIM_ICPolarity, uint16_t ICFilter); +void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter); +void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, + uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter); +void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter); +void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode); +void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode); +void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); +void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode, + uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity); +void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); +void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); +void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); +void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx); +void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN); +void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode); +void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource); +void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode); +void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource); +void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode); +void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode); +void TIM_SetCounter(TIM_TypeDef* TIMx, uint16_t Counter); +void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint16_t Autoreload); +void TIM_SetCompare1(TIM_TypeDef* TIMx, uint16_t Compare1); +void TIM_SetCompare2(TIM_TypeDef* TIMx, uint16_t Compare2); +void TIM_SetCompare3(TIM_TypeDef* TIMx, uint16_t Compare3); +void TIM_SetCompare4(TIM_TypeDef* TIMx, uint16_t Compare4); +void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD); +uint16_t TIM_GetCapture1(TIM_TypeDef* TIMx); +uint16_t TIM_GetCapture2(TIM_TypeDef* TIMx); +uint16_t TIM_GetCapture3(TIM_TypeDef* TIMx); +uint16_t TIM_GetCapture4(TIM_TypeDef* TIMx); +uint16_t TIM_GetCounter(TIM_TypeDef* TIMx); +uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx); +FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint16_t TIM_FLAG); +void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG); +ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT); +void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_TIM_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h new file mode 100644 index 0000000..162fa87 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h @@ -0,0 +1,412 @@ +/** + ****************************************************************************** + * @file stm32f10x_usart.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the USART + * firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_USART_H +#define __STM32F10x_USART_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup USART + * @{ + */ + +/** @defgroup USART_Exported_Types + * @{ + */ + +/** + * @brief USART Init Structure definition + */ + +typedef struct +{ + uint32_t USART_BaudRate; /*!< This member configures the USART communication baud rate. + The baud rate is computed using the following formula: + - IntegerDivider = ((PCLKx) / (16 * (USART_InitStruct->USART_BaudRate))) + - FractionalDivider = ((IntegerDivider - ((u32) IntegerDivider)) * 16) + 0.5 */ + + uint16_t USART_WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. + This parameter can be a value of @ref USART_Word_Length */ + + uint16_t USART_StopBits; /*!< Specifies the number of stop bits transmitted. + This parameter can be a value of @ref USART_Stop_Bits */ + + uint16_t USART_Parity; /*!< Specifies the parity mode. + This parameter can be a value of @ref USART_Parity + @note When parity is enabled, the computed parity is inserted + at the MSB position of the transmitted data (9th bit when + the word length is set to 9 data bits; 8th bit when the + word length is set to 8 data bits). */ + + uint16_t USART_Mode; /*!< Specifies wether the Receive or Transmit mode is enabled or disabled. + This parameter can be a value of @ref USART_Mode */ + + uint16_t USART_HardwareFlowControl; /*!< Specifies wether the hardware flow control mode is enabled + or disabled. + This parameter can be a value of @ref USART_Hardware_Flow_Control */ +} USART_InitTypeDef; + +/** + * @brief USART Clock Init Structure definition + */ + +typedef struct +{ + + uint16_t USART_Clock; /*!< Specifies whether the USART clock is enabled or disabled. + This parameter can be a value of @ref USART_Clock */ + + uint16_t USART_CPOL; /*!< Specifies the steady state value of the serial clock. + This parameter can be a value of @ref USART_Clock_Polarity */ + + uint16_t USART_CPHA; /*!< Specifies the clock transition on which the bit capture is made. + This parameter can be a value of @ref USART_Clock_Phase */ + + uint16_t USART_LastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted + data bit (MSB) has to be output on the SCLK pin in synchronous mode. + This parameter can be a value of @ref USART_Last_Bit */ +} USART_ClockInitTypeDef; + +/** + * @} + */ + +/** @defgroup USART_Exported_Constants + * @{ + */ + +#define IS_USART_ALL_PERIPH(PERIPH) (((PERIPH) == USART1) || \ + ((PERIPH) == USART2) || \ + ((PERIPH) == USART3) || \ + ((PERIPH) == UART4) || \ + ((PERIPH) == UART5)) + +#define IS_USART_123_PERIPH(PERIPH) (((PERIPH) == USART1) || \ + ((PERIPH) == USART2) || \ + ((PERIPH) == USART3)) + +#define IS_USART_1234_PERIPH(PERIPH) (((PERIPH) == USART1) || \ + ((PERIPH) == USART2) || \ + ((PERIPH) == USART3) || \ + ((PERIPH) == UART4)) +/** @defgroup USART_Word_Length + * @{ + */ + +#define USART_WordLength_8b ((uint16_t)0x0000) +#define USART_WordLength_9b ((uint16_t)0x1000) + +#define IS_USART_WORD_LENGTH(LENGTH) (((LENGTH) == USART_WordLength_8b) || \ + ((LENGTH) == USART_WordLength_9b)) +/** + * @} + */ + +/** @defgroup USART_Stop_Bits + * @{ + */ + +#define USART_StopBits_1 ((uint16_t)0x0000) +#define USART_StopBits_0_5 ((uint16_t)0x1000) +#define USART_StopBits_2 ((uint16_t)0x2000) +#define USART_StopBits_1_5 ((uint16_t)0x3000) +#define IS_USART_STOPBITS(STOPBITS) (((STOPBITS) == USART_StopBits_1) || \ + ((STOPBITS) == USART_StopBits_0_5) || \ + ((STOPBITS) == USART_StopBits_2) || \ + ((STOPBITS) == USART_StopBits_1_5)) +/** + * @} + */ + +/** @defgroup USART_Parity + * @{ + */ + +#define USART_Parity_No ((uint16_t)0x0000) +#define USART_Parity_Even ((uint16_t)0x0400) +#define USART_Parity_Odd ((uint16_t)0x0600) +#define IS_USART_PARITY(PARITY) (((PARITY) == USART_Parity_No) || \ + ((PARITY) == USART_Parity_Even) || \ + ((PARITY) == USART_Parity_Odd)) +/** + * @} + */ + +/** @defgroup USART_Mode + * @{ + */ + +#define USART_Mode_Rx ((uint16_t)0x0004) +#define USART_Mode_Tx ((uint16_t)0x0008) +#define IS_USART_MODE(MODE) ((((MODE) & (uint16_t)0xFFF3) == 0x00) && ((MODE) != (uint16_t)0x00)) +/** + * @} + */ + +/** @defgroup USART_Hardware_Flow_Control + * @{ + */ +#define USART_HardwareFlowControl_None ((uint16_t)0x0000) +#define USART_HardwareFlowControl_RTS ((uint16_t)0x0100) +#define USART_HardwareFlowControl_CTS ((uint16_t)0x0200) +#define USART_HardwareFlowControl_RTS_CTS ((uint16_t)0x0300) +#define IS_USART_HARDWARE_FLOW_CONTROL(CONTROL)\ + (((CONTROL) == USART_HardwareFlowControl_None) || \ + ((CONTROL) == USART_HardwareFlowControl_RTS) || \ + ((CONTROL) == USART_HardwareFlowControl_CTS) || \ + ((CONTROL) == USART_HardwareFlowControl_RTS_CTS)) +/** + * @} + */ + +/** @defgroup USART_Clock + * @{ + */ +#define USART_Clock_Disable ((uint16_t)0x0000) +#define USART_Clock_Enable ((uint16_t)0x0800) +#define IS_USART_CLOCK(CLOCK) (((CLOCK) == USART_Clock_Disable) || \ + ((CLOCK) == USART_Clock_Enable)) +/** + * @} + */ + +/** @defgroup USART_Clock_Polarity + * @{ + */ + +#define USART_CPOL_Low ((uint16_t)0x0000) +#define USART_CPOL_High ((uint16_t)0x0400) +#define IS_USART_CPOL(CPOL) (((CPOL) == USART_CPOL_Low) || ((CPOL) == USART_CPOL_High)) + +/** + * @} + */ + +/** @defgroup USART_Clock_Phase + * @{ + */ + +#define USART_CPHA_1Edge ((uint16_t)0x0000) +#define USART_CPHA_2Edge ((uint16_t)0x0200) +#define IS_USART_CPHA(CPHA) (((CPHA) == USART_CPHA_1Edge) || ((CPHA) == USART_CPHA_2Edge)) + +/** + * @} + */ + +/** @defgroup USART_Last_Bit + * @{ + */ + +#define USART_LastBit_Disable ((uint16_t)0x0000) +#define USART_LastBit_Enable ((uint16_t)0x0100) +#define IS_USART_LASTBIT(LASTBIT) (((LASTBIT) == USART_LastBit_Disable) || \ + ((LASTBIT) == USART_LastBit_Enable)) +/** + * @} + */ + +/** @defgroup USART_Interrupt_definition + * @{ + */ + +#define USART_IT_PE ((uint16_t)0x0028) +#define USART_IT_TXE ((uint16_t)0x0727) +#define USART_IT_TC ((uint16_t)0x0626) +#define USART_IT_RXNE ((uint16_t)0x0525) +#define USART_IT_IDLE ((uint16_t)0x0424) +#define USART_IT_LBD ((uint16_t)0x0846) +#define USART_IT_CTS ((uint16_t)0x096A) +#define USART_IT_ERR ((uint16_t)0x0060) +#define USART_IT_ORE ((uint16_t)0x0360) +#define USART_IT_NE ((uint16_t)0x0260) +#define USART_IT_FE ((uint16_t)0x0160) +#define IS_USART_CONFIG_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \ + ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ + ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \ + ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ERR)) +#define IS_USART_GET_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \ + ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ + ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \ + ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ORE) || \ + ((IT) == USART_IT_NE) || ((IT) == USART_IT_FE)) +#define IS_USART_CLEAR_IT(IT) (((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ + ((IT) == USART_IT_LBD) || ((IT) == USART_IT_CTS)) +/** + * @} + */ + +/** @defgroup USART_DMA_Requests + * @{ + */ + +#define USART_DMAReq_Tx ((uint16_t)0x0080) +#define USART_DMAReq_Rx ((uint16_t)0x0040) +#define IS_USART_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFF3F) == 0x00) && ((DMAREQ) != (uint16_t)0x00)) + +/** + * @} + */ + +/** @defgroup USART_WakeUp_methods + * @{ + */ + +#define USART_WakeUp_IdleLine ((uint16_t)0x0000) +#define USART_WakeUp_AddressMark ((uint16_t)0x0800) +#define IS_USART_WAKEUP(WAKEUP) (((WAKEUP) == USART_WakeUp_IdleLine) || \ + ((WAKEUP) == USART_WakeUp_AddressMark)) +/** + * @} + */ + +/** @defgroup USART_LIN_Break_Detection_Length + * @{ + */ + +#define USART_LINBreakDetectLength_10b ((uint16_t)0x0000) +#define USART_LINBreakDetectLength_11b ((uint16_t)0x0020) +#define IS_USART_LIN_BREAK_DETECT_LENGTH(LENGTH) \ + (((LENGTH) == USART_LINBreakDetectLength_10b) || \ + ((LENGTH) == USART_LINBreakDetectLength_11b)) +/** + * @} + */ + +/** @defgroup USART_IrDA_Low_Power + * @{ + */ + +#define USART_IrDAMode_LowPower ((uint16_t)0x0004) +#define USART_IrDAMode_Normal ((uint16_t)0x0000) +#define IS_USART_IRDA_MODE(MODE) (((MODE) == USART_IrDAMode_LowPower) || \ + ((MODE) == USART_IrDAMode_Normal)) +/** + * @} + */ + +/** @defgroup USART_Flags + * @{ + */ + +#define USART_FLAG_CTS ((uint16_t)0x0200) +#define USART_FLAG_LBD ((uint16_t)0x0100) +#define USART_FLAG_TXE ((uint16_t)0x0080) +#define USART_FLAG_TC ((uint16_t)0x0040) +#define USART_FLAG_RXNE ((uint16_t)0x0020) +#define USART_FLAG_IDLE ((uint16_t)0x0010) +#define USART_FLAG_ORE ((uint16_t)0x0008) +#define USART_FLAG_NE ((uint16_t)0x0004) +#define USART_FLAG_FE ((uint16_t)0x0002) +#define USART_FLAG_PE ((uint16_t)0x0001) +#define IS_USART_FLAG(FLAG) (((FLAG) == USART_FLAG_PE) || ((FLAG) == USART_FLAG_TXE) || \ + ((FLAG) == USART_FLAG_TC) || ((FLAG) == USART_FLAG_RXNE) || \ + ((FLAG) == USART_FLAG_IDLE) || ((FLAG) == USART_FLAG_LBD) || \ + ((FLAG) == USART_FLAG_CTS) || ((FLAG) == USART_FLAG_ORE) || \ + ((FLAG) == USART_FLAG_NE) || ((FLAG) == USART_FLAG_FE)) + +#define IS_USART_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFC9F) == 0x00) && ((FLAG) != (uint16_t)0x00)) +#define IS_USART_PERIPH_FLAG(PERIPH, USART_FLAG) ((((*(uint32_t*)&(PERIPH)) != UART4_BASE) &&\ + ((*(uint32_t*)&(PERIPH)) != UART5_BASE)) \ + || ((USART_FLAG) != USART_FLAG_CTS)) +#define IS_USART_BAUDRATE(BAUDRATE) (((BAUDRATE) > 0) && ((BAUDRATE) < 0x0044AA21)) +#define IS_USART_ADDRESS(ADDRESS) ((ADDRESS) <= 0xF) +#define IS_USART_DATA(DATA) ((DATA) <= 0x1FF) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup USART_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup USART_Exported_Functions + * @{ + */ + +void USART_DeInit(USART_TypeDef* USARTx); +void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct); +void USART_StructInit(USART_InitTypeDef* USART_InitStruct); +void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct); +void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct); +void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState); +void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState); +void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address); +void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp); +void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength); +void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_SendData(USART_TypeDef* USARTx, uint16_t Data); +uint16_t USART_ReceiveData(USART_TypeDef* USARTx); +void USART_SendBreak(USART_TypeDef* USARTx); +void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime); +void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler); +void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode); +void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState); +FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG); +void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG); +ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT); +void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_USART_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h new file mode 100644 index 0000000..bdfa177 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h @@ -0,0 +1,115 @@ +/** + ****************************************************************************** + * @file stm32f10x_wwdg.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the WWDG firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_WWDG_H +#define __STM32F10x_WWDG_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup WWDG + * @{ + */ + +/** @defgroup WWDG_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup WWDG_Exported_Constants + * @{ + */ + +/** @defgroup WWDG_Prescaler + * @{ + */ + +#define WWDG_Prescaler_1 ((uint32_t)0x00000000) +#define WWDG_Prescaler_2 ((uint32_t)0x00000080) +#define WWDG_Prescaler_4 ((uint32_t)0x00000100) +#define WWDG_Prescaler_8 ((uint32_t)0x00000180) +#define IS_WWDG_PRESCALER(PRESCALER) (((PRESCALER) == WWDG_Prescaler_1) || \ + ((PRESCALER) == WWDG_Prescaler_2) || \ + ((PRESCALER) == WWDG_Prescaler_4) || \ + ((PRESCALER) == WWDG_Prescaler_8)) +#define IS_WWDG_WINDOW_VALUE(VALUE) ((VALUE) <= 0x7F) +#define IS_WWDG_COUNTER(COUNTER) (((COUNTER) >= 0x40) && ((COUNTER) <= 0x7F)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup WWDG_Exported_Macros + * @{ + */ +/** + * @} + */ + +/** @defgroup WWDG_Exported_Functions + * @{ + */ + +void WWDG_DeInit(void); +void WWDG_SetPrescaler(uint32_t WWDG_Prescaler); +void WWDG_SetWindowValue(uint8_t WindowValue); +void WWDG_EnableIT(void); +void WWDG_SetCounter(uint8_t Counter); +void WWDG_Enable(uint8_t Counter); +FlagStatus WWDG_GetFlagStatus(void); +void WWDG_ClearFlag(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_WWDG_H */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/misc.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/misc.c new file mode 100644 index 0000000..c0a5e11 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/misc.c @@ -0,0 +1,225 @@ +/** + ****************************************************************************** + * @file misc.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the miscellaneous firmware functions (add-on + * to CMSIS functions). + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "misc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup MISC + * @brief MISC driver modules + * @{ + */ + +/** @defgroup MISC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup MISC_Private_Defines + * @{ + */ + +#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) +/** + * @} + */ + +/** @defgroup MISC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup MISC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup MISC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup MISC_Private_Functions + * @{ + */ + +/** + * @brief Configures the priority grouping: pre-emption priority and subpriority. + * @param NVIC_PriorityGroup: specifies the priority grouping bits length. + * This parameter can be one of the following values: + * @arg NVIC_PriorityGroup_0: 0 bits for pre-emption priority + * 4 bits for subpriority + * @arg NVIC_PriorityGroup_1: 1 bits for pre-emption priority + * 3 bits for subpriority + * @arg NVIC_PriorityGroup_2: 2 bits for pre-emption priority + * 2 bits for subpriority + * @arg NVIC_PriorityGroup_3: 3 bits for pre-emption priority + * 1 bits for subpriority + * @arg NVIC_PriorityGroup_4: 4 bits for pre-emption priority + * 0 bits for subpriority + * @retval None + */ +void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup) +{ + /* Check the parameters */ + assert_param(IS_NVIC_PRIORITY_GROUP(NVIC_PriorityGroup)); + + /* Set the PRIGROUP[10:8] bits according to NVIC_PriorityGroup value */ + SCB->AIRCR = AIRCR_VECTKEY_MASK | NVIC_PriorityGroup; +} + +/** + * @brief Initializes the NVIC peripheral according to the specified + * parameters in the NVIC_InitStruct. + * @param NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure that contains + * the configuration information for the specified NVIC peripheral. + * @retval None + */ +void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct) +{ + uint32_t tmppriority = 0x00, tmppre = 0x00, tmpsub = 0x0F; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NVIC_InitStruct->NVIC_IRQChannelCmd)); + assert_param(IS_NVIC_PREEMPTION_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority)); + assert_param(IS_NVIC_SUB_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelSubPriority)); + + if (NVIC_InitStruct->NVIC_IRQChannelCmd != DISABLE) + { + /* Compute the Corresponding IRQ Priority --------------------------------*/ + tmppriority = (0x700 - ((SCB->AIRCR) & (uint32_t)0x700))>> 0x08; + tmppre = (0x4 - tmppriority); + tmpsub = tmpsub >> tmppriority; + + tmppriority = (uint32_t)NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority << tmppre; + tmppriority |= NVIC_InitStruct->NVIC_IRQChannelSubPriority & tmpsub; + tmppriority = tmppriority << 0x04; + + NVIC->IP[NVIC_InitStruct->NVIC_IRQChannel] = tmppriority; + + /* Enable the Selected IRQ Channels --------------------------------------*/ + NVIC->ISER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] = + (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F); + } + else + { + /* Disable the Selected IRQ Channels -------------------------------------*/ + NVIC->ICER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] = + (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F); + } +} + +/** + * @brief Sets the vector table location and Offset. + * @param NVIC_VectTab: specifies if the vector table is in RAM or FLASH memory. + * This parameter can be one of the following values: + * @arg NVIC_VectTab_RAM + * @arg NVIC_VectTab_FLASH + * @param Offset: Vector Table base offset field. This value must be a multiple + * of 0x200. + * @retval None + */ +void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset) +{ + /* Check the parameters */ + assert_param(IS_NVIC_VECTTAB(NVIC_VectTab)); + assert_param(IS_NVIC_OFFSET(Offset)); + + SCB->VTOR = NVIC_VectTab | (Offset & (uint32_t)0x1FFFFF80); +} + +/** + * @brief Selects the condition for the system to enter low power mode. + * @param LowPowerMode: Specifies the new mode for the system to enter low power mode. + * This parameter can be one of the following values: + * @arg NVIC_LP_SEVONPEND + * @arg NVIC_LP_SLEEPDEEP + * @arg NVIC_LP_SLEEPONEXIT + * @param NewState: new state of LP condition. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_NVIC_LP(LowPowerMode)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + SCB->SCR |= LowPowerMode; + } + else + { + SCB->SCR &= (uint32_t)(~(uint32_t)LowPowerMode); + } +} + +/** + * @brief Configures the SysTick clock source. + * @param SysTick_CLKSource: specifies the SysTick clock source. + * This parameter can be one of the following values: + * @arg SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8 selected as SysTick clock source. + * @arg SysTick_CLKSource_HCLK: AHB clock selected as SysTick clock source. + * @retval None + */ +void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource) +{ + /* Check the parameters */ + assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource)); + if (SysTick_CLKSource == SysTick_CLKSource_HCLK) + { + SysTick->CTRL |= SysTick_CLKSource_HCLK; + } + else + { + SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c new file mode 100644 index 0000000..8155dc9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c @@ -0,0 +1,1307 @@ +/** + ****************************************************************************** + * @file stm32f10x_adc.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the ADC firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_adc.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup ADC + * @brief ADC driver modules + * @{ + */ + +/** @defgroup ADC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup ADC_Private_Defines + * @{ + */ + +/* ADC DISCNUM mask */ +#define CR1_DISCNUM_Reset ((uint32_t)0xFFFF1FFF) + +/* ADC DISCEN mask */ +#define CR1_DISCEN_Set ((uint32_t)0x00000800) +#define CR1_DISCEN_Reset ((uint32_t)0xFFFFF7FF) + +/* ADC JAUTO mask */ +#define CR1_JAUTO_Set ((uint32_t)0x00000400) +#define CR1_JAUTO_Reset ((uint32_t)0xFFFFFBFF) + +/* ADC JDISCEN mask */ +#define CR1_JDISCEN_Set ((uint32_t)0x00001000) +#define CR1_JDISCEN_Reset ((uint32_t)0xFFFFEFFF) + +/* ADC AWDCH mask */ +#define CR1_AWDCH_Reset ((uint32_t)0xFFFFFFE0) + +/* ADC Analog watchdog enable mode mask */ +#define CR1_AWDMode_Reset ((uint32_t)0xFF3FFDFF) + +/* CR1 register Mask */ +#define CR1_CLEAR_Mask ((uint32_t)0xFFF0FEFF) + +/* ADC ADON mask */ +#define CR2_ADON_Set ((uint32_t)0x00000001) +#define CR2_ADON_Reset ((uint32_t)0xFFFFFFFE) + +/* ADC DMA mask */ +#define CR2_DMA_Set ((uint32_t)0x00000100) +#define CR2_DMA_Reset ((uint32_t)0xFFFFFEFF) + +/* ADC RSTCAL mask */ +#define CR2_RSTCAL_Set ((uint32_t)0x00000008) + +/* ADC CAL mask */ +#define CR2_CAL_Set ((uint32_t)0x00000004) + +/* ADC SWSTART mask */ +#define CR2_SWSTART_Set ((uint32_t)0x00400000) + +/* ADC EXTTRIG mask */ +#define CR2_EXTTRIG_Set ((uint32_t)0x00100000) +#define CR2_EXTTRIG_Reset ((uint32_t)0xFFEFFFFF) + +/* ADC Software start mask */ +#define CR2_EXTTRIG_SWSTART_Set ((uint32_t)0x00500000) +#define CR2_EXTTRIG_SWSTART_Reset ((uint32_t)0xFFAFFFFF) + +/* ADC JEXTSEL mask */ +#define CR2_JEXTSEL_Reset ((uint32_t)0xFFFF8FFF) + +/* ADC JEXTTRIG mask */ +#define CR2_JEXTTRIG_Set ((uint32_t)0x00008000) +#define CR2_JEXTTRIG_Reset ((uint32_t)0xFFFF7FFF) + +/* ADC JSWSTART mask */ +#define CR2_JSWSTART_Set ((uint32_t)0x00200000) + +/* ADC injected software start mask */ +#define CR2_JEXTTRIG_JSWSTART_Set ((uint32_t)0x00208000) +#define CR2_JEXTTRIG_JSWSTART_Reset ((uint32_t)0xFFDF7FFF) + +/* ADC TSPD mask */ +#define CR2_TSVREFE_Set ((uint32_t)0x00800000) +#define CR2_TSVREFE_Reset ((uint32_t)0xFF7FFFFF) + +/* CR2 register Mask */ +#define CR2_CLEAR_Mask ((uint32_t)0xFFF1F7FD) + +/* ADC SQx mask */ +#define SQR3_SQ_Set ((uint32_t)0x0000001F) +#define SQR2_SQ_Set ((uint32_t)0x0000001F) +#define SQR1_SQ_Set ((uint32_t)0x0000001F) + +/* SQR1 register Mask */ +#define SQR1_CLEAR_Mask ((uint32_t)0xFF0FFFFF) + +/* ADC JSQx mask */ +#define JSQR_JSQ_Set ((uint32_t)0x0000001F) + +/* ADC JL mask */ +#define JSQR_JL_Set ((uint32_t)0x00300000) +#define JSQR_JL_Reset ((uint32_t)0xFFCFFFFF) + +/* ADC SMPx mask */ +#define SMPR1_SMP_Set ((uint32_t)0x00000007) +#define SMPR2_SMP_Set ((uint32_t)0x00000007) + +/* ADC JDRx registers offset */ +#define JDR_Offset ((uint8_t)0x28) + +/* ADC1 DR register base address */ +#define DR_ADDRESS ((uint32_t)0x4001244C) + +/** + * @} + */ + +/** @defgroup ADC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup ADC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup ADC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup ADC_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the ADCx peripheral registers to their default reset values. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval None + */ +void ADC_DeInit(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + if (ADCx == ADC1) + { + /* Enable ADC1 reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, ENABLE); + /* Release ADC1 from reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, DISABLE); + } + else if (ADCx == ADC2) + { + /* Enable ADC2 reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, ENABLE); + /* Release ADC2 from reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, DISABLE); + } + else + { + if (ADCx == ADC3) + { + /* Enable ADC3 reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, ENABLE); + /* Release ADC3 from reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, DISABLE); + } + } +} + +/** + * @brief Initializes the ADCx peripheral according to the specified parameters + * in the ADC_InitStruct. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_InitStruct: pointer to an ADC_InitTypeDef structure that contains + * the configuration information for the specified ADC peripheral. + * @retval None + */ +void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct) +{ + uint32_t tmpreg1 = 0; + uint8_t tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_MODE(ADC_InitStruct->ADC_Mode)); + assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ScanConvMode)); + assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ContinuousConvMode)); + assert_param(IS_ADC_EXT_TRIG(ADC_InitStruct->ADC_ExternalTrigConv)); + assert_param(IS_ADC_DATA_ALIGN(ADC_InitStruct->ADC_DataAlign)); + assert_param(IS_ADC_REGULAR_LENGTH(ADC_InitStruct->ADC_NbrOfChannel)); + + /*---------------------------- ADCx CR1 Configuration -----------------*/ + /* Get the ADCx CR1 value */ + tmpreg1 = ADCx->CR1; + /* Clear DUALMOD and SCAN bits */ + tmpreg1 &= CR1_CLEAR_Mask; + /* Configure ADCx: Dual mode and scan conversion mode */ + /* Set DUALMOD bits according to ADC_Mode value */ + /* Set SCAN bit according to ADC_ScanConvMode value */ + tmpreg1 |= (uint32_t)(ADC_InitStruct->ADC_Mode | ((uint32_t)ADC_InitStruct->ADC_ScanConvMode << 8)); + /* Write to ADCx CR1 */ + ADCx->CR1 = tmpreg1; + + /*---------------------------- ADCx CR2 Configuration -----------------*/ + /* Get the ADCx CR2 value */ + tmpreg1 = ADCx->CR2; + /* Clear CONT, ALIGN and EXTSEL bits */ + tmpreg1 &= CR2_CLEAR_Mask; + /* Configure ADCx: external trigger event and continuous conversion mode */ + /* Set ALIGN bit according to ADC_DataAlign value */ + /* Set EXTSEL bits according to ADC_ExternalTrigConv value */ + /* Set CONT bit according to ADC_ContinuousConvMode value */ + tmpreg1 |= (uint32_t)(ADC_InitStruct->ADC_DataAlign | ADC_InitStruct->ADC_ExternalTrigConv | + ((uint32_t)ADC_InitStruct->ADC_ContinuousConvMode << 1)); + /* Write to ADCx CR2 */ + ADCx->CR2 = tmpreg1; + + /*---------------------------- ADCx SQR1 Configuration -----------------*/ + /* Get the ADCx SQR1 value */ + tmpreg1 = ADCx->SQR1; + /* Clear L bits */ + tmpreg1 &= SQR1_CLEAR_Mask; + /* Configure ADCx: regular channel sequence length */ + /* Set L bits according to ADC_NbrOfChannel value */ + tmpreg2 |= (uint8_t) (ADC_InitStruct->ADC_NbrOfChannel - (uint8_t)1); + tmpreg1 |= (uint32_t)tmpreg2 << 20; + /* Write to ADCx SQR1 */ + ADCx->SQR1 = tmpreg1; +} + +/** + * @brief Fills each ADC_InitStruct member with its default value. + * @param ADC_InitStruct : pointer to an ADC_InitTypeDef structure which will be initialized. + * @retval None + */ +void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct) +{ + /* Reset ADC init structure parameters values */ + /* Initialize the ADC_Mode member */ + ADC_InitStruct->ADC_Mode = ADC_Mode_Independent; + /* initialize the ADC_ScanConvMode member */ + ADC_InitStruct->ADC_ScanConvMode = DISABLE; + /* Initialize the ADC_ContinuousConvMode member */ + ADC_InitStruct->ADC_ContinuousConvMode = DISABLE; + /* Initialize the ADC_ExternalTrigConv member */ + ADC_InitStruct->ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1; + /* Initialize the ADC_DataAlign member */ + ADC_InitStruct->ADC_DataAlign = ADC_DataAlign_Right; + /* Initialize the ADC_NbrOfChannel member */ + ADC_InitStruct->ADC_NbrOfChannel = 1; +} + +/** + * @brief Enables or disables the specified ADC peripheral. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the ADCx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the ADON bit to wake up the ADC from power down mode */ + ADCx->CR2 |= CR2_ADON_Set; + } + else + { + /* Disable the selected ADC peripheral */ + ADCx->CR2 &= CR2_ADON_Reset; + } +} + +/** + * @brief Enables or disables the specified ADC DMA request. + * @param ADCx: where x can be 1 or 3 to select the ADC peripheral. + * Note: ADC2 hasn't a DMA capability. + * @param NewState: new state of the selected ADC DMA transfer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_DMA_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC DMA request */ + ADCx->CR2 |= CR2_DMA_Set; + } + else + { + /* Disable the selected ADC DMA request */ + ADCx->CR2 &= CR2_DMA_Reset; + } +} + +/** + * @brief Enables or disables the specified ADC interrupts. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_IT: specifies the ADC interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg ADC_IT_EOC: End of conversion interrupt mask + * @arg ADC_IT_AWD: Analog watchdog interrupt mask + * @arg ADC_IT_JEOC: End of injected conversion interrupt mask + * @param NewState: new state of the specified ADC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState) +{ + uint8_t itmask = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_ADC_IT(ADC_IT)); + /* Get the ADC IT index */ + itmask = (uint8_t)ADC_IT; + if (NewState != DISABLE) + { + /* Enable the selected ADC interrupts */ + ADCx->CR1 |= itmask; + } + else + { + /* Disable the selected ADC interrupts */ + ADCx->CR1 &= (~(uint32_t)itmask); + } +} + +/** + * @brief Resets the selected ADC calibration registers. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval None + */ +void ADC_ResetCalibration(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Resets the selected ADC calibration registers */ + ADCx->CR2 |= CR2_RSTCAL_Set; +} + +/** + * @brief Gets the selected ADC reset calibration registers status. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The new state of ADC reset calibration registers (SET or RESET). + */ +FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Check the status of RSTCAL bit */ + if ((ADCx->CR2 & CR2_RSTCAL_Set) != (uint32_t)RESET) + { + /* RSTCAL bit is set */ + bitstatus = SET; + } + else + { + /* RSTCAL bit is reset */ + bitstatus = RESET; + } + /* Return the RSTCAL bit status */ + return bitstatus; +} + +/** + * @brief Starts the selected ADC calibration process. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval None + */ +void ADC_StartCalibration(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Enable the selected ADC calibration process */ + ADCx->CR2 |= CR2_CAL_Set; +} + +/** + * @brief Gets the selected ADC calibration status. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The new state of ADC calibration (SET or RESET). + */ +FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Check the status of CAL bit */ + if ((ADCx->CR2 & CR2_CAL_Set) != (uint32_t)RESET) + { + /* CAL bit is set: calibration on going */ + bitstatus = SET; + } + else + { + /* CAL bit is reset: end of calibration */ + bitstatus = RESET; + } + /* Return the CAL bit status */ + return bitstatus; +} + +/** + * @brief Enables or disables the selected ADC software start conversion . + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC software start conversion. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC conversion on external event and start the selected + ADC conversion */ + ADCx->CR2 |= CR2_EXTTRIG_SWSTART_Set; + } + else + { + /* Disable the selected ADC conversion on external event and stop the selected + ADC conversion */ + ADCx->CR2 &= CR2_EXTTRIG_SWSTART_Reset; + } +} + +/** + * @brief Gets the selected ADC Software start conversion Status. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The new state of ADC software start conversion (SET or RESET). + */ +FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Check the status of SWSTART bit */ + if ((ADCx->CR2 & CR2_SWSTART_Set) != (uint32_t)RESET) + { + /* SWSTART bit is set */ + bitstatus = SET; + } + else + { + /* SWSTART bit is reset */ + bitstatus = RESET; + } + /* Return the SWSTART bit status */ + return bitstatus; +} + +/** + * @brief Configures the discontinuous mode for the selected ADC regular + * group channel. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param Number: specifies the discontinuous mode regular channel + * count value. This number must be between 1 and 8. + * @retval None + */ +void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number) +{ + uint32_t tmpreg1 = 0; + uint32_t tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_REGULAR_DISC_NUMBER(Number)); + /* Get the old register value */ + tmpreg1 = ADCx->CR1; + /* Clear the old discontinuous mode channel count */ + tmpreg1 &= CR1_DISCNUM_Reset; + /* Set the discontinuous mode channel count */ + tmpreg2 = Number - 1; + tmpreg1 |= tmpreg2 << 13; + /* Store the new register value */ + ADCx->CR1 = tmpreg1; +} + +/** + * @brief Enables or disables the discontinuous mode on regular group + * channel for the specified ADC + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC discontinuous mode + * on regular group channel. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC regular discontinuous mode */ + ADCx->CR1 |= CR1_DISCEN_Set; + } + else + { + /* Disable the selected ADC regular discontinuous mode */ + ADCx->CR1 &= CR1_DISCEN_Reset; + } +} + +/** + * @brief Configures for the selected ADC regular channel its corresponding + * rank in the sequencer and its sample time. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure. + * This parameter can be one of the following values: + * @arg ADC_Channel_0: ADC Channel0 selected + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @param Rank: The rank in the regular group sequencer. This parameter must be between 1 to 16. + * @param ADC_SampleTime: The sample time value to be set for the selected channel. + * This parameter can be one of the following values: + * @arg ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles + * @arg ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles + * @arg ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles + * @arg ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles + * @arg ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles + * @arg ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles + * @arg ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles + * @arg ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles + * @retval None + */ +void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime) +{ + uint32_t tmpreg1 = 0, tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + assert_param(IS_ADC_REGULAR_RANK(Rank)); + assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime)); + /* if ADC_Channel_10 ... ADC_Channel_17 is selected */ + if (ADC_Channel > ADC_Channel_9) + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR1; + /* Calculate the mask to clear */ + tmpreg2 = SMPR1_SMP_Set << (3 * (ADC_Channel - 10)); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * (ADC_Channel - 10)); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SMPR1 = tmpreg1; + } + else /* ADC_Channel include in ADC_Channel_[0..9] */ + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR2; + /* Calculate the mask to clear */ + tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SMPR2 = tmpreg1; + } + /* For Rank 1 to 6 */ + if (Rank < 7) + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR3; + /* Calculate the mask to clear */ + tmpreg2 = SQR3_SQ_Set << (5 * (Rank - 1)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 1)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SQR3 = tmpreg1; + } + /* For Rank 7 to 12 */ + else if (Rank < 13) + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR2; + /* Calculate the mask to clear */ + tmpreg2 = SQR2_SQ_Set << (5 * (Rank - 7)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 7)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SQR2 = tmpreg1; + } + /* For Rank 13 to 16 */ + else + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR1; + /* Calculate the mask to clear */ + tmpreg2 = SQR1_SQ_Set << (5 * (Rank - 13)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 13)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SQR1 = tmpreg1; + } +} + +/** + * @brief Enables or disables the ADCx conversion through external trigger. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC external trigger start of conversion. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC conversion on external event */ + ADCx->CR2 |= CR2_EXTTRIG_Set; + } + else + { + /* Disable the selected ADC conversion on external event */ + ADCx->CR2 &= CR2_EXTTRIG_Reset; + } +} + +/** + * @brief Returns the last ADCx conversion result data for regular channel. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The Data conversion value. + */ +uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Return the selected ADC conversion value */ + return (uint16_t) ADCx->DR; +} + +/** + * @brief Returns the last ADC1 and ADC2 conversion result data in dual mode. + * @retval The Data conversion value. + */ +uint32_t ADC_GetDualModeConversionValue(void) +{ + /* Return the dual mode conversion value */ + return (*(__IO uint32_t *) DR_ADDRESS); +} + +/** + * @brief Enables or disables the selected ADC automatic injected group + * conversion after regular one. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC auto injected conversion + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC automatic injected group conversion */ + ADCx->CR1 |= CR1_JAUTO_Set; + } + else + { + /* Disable the selected ADC automatic injected group conversion */ + ADCx->CR1 &= CR1_JAUTO_Reset; + } +} + +/** + * @brief Enables or disables the discontinuous mode for injected group + * channel for the specified ADC + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC discontinuous mode + * on injected group channel. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC injected discontinuous mode */ + ADCx->CR1 |= CR1_JDISCEN_Set; + } + else + { + /* Disable the selected ADC injected discontinuous mode */ + ADCx->CR1 &= CR1_JDISCEN_Reset; + } +} + +/** + * @brief Configures the ADCx external trigger for injected channels conversion. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_ExternalTrigInjecConv: specifies the ADC trigger to start injected conversion. + * This parameter can be one of the following values: + * @arg ADC_ExternalTrigInjecConv_T1_TRGO: Timer1 TRGO event selected (for ADC1, ADC2 and ADC3) + * @arg ADC_ExternalTrigInjecConv_T1_CC4: Timer1 capture compare4 selected (for ADC1, ADC2 and ADC3) + * @arg ADC_ExternalTrigInjecConv_T2_TRGO: Timer2 TRGO event selected (for ADC1 and ADC2) + * @arg ADC_ExternalTrigInjecConv_T2_CC1: Timer2 capture compare1 selected (for ADC1 and ADC2) + * @arg ADC_ExternalTrigInjecConv_T3_CC4: Timer3 capture compare4 selected (for ADC1 and ADC2) + * @arg ADC_ExternalTrigInjecConv_T4_TRGO: Timer4 TRGO event selected (for ADC1 and ADC2) + * @arg ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4: External interrupt line 15 or Timer8 + * capture compare4 event selected (for ADC1 and ADC2) + * @arg ADC_ExternalTrigInjecConv_T4_CC3: Timer4 capture compare3 selected (for ADC3 only) + * @arg ADC_ExternalTrigInjecConv_T8_CC2: Timer8 capture compare2 selected (for ADC3 only) + * @arg ADC_ExternalTrigInjecConv_T8_CC4: Timer8 capture compare4 selected (for ADC3 only) + * @arg ADC_ExternalTrigInjecConv_T5_TRGO: Timer5 TRGO event selected (for ADC3 only) + * @arg ADC_ExternalTrigInjecConv_T5_CC4: Timer5 capture compare4 selected (for ADC3 only) + * @arg ADC_ExternalTrigInjecConv_None: Injected conversion started by software and not + * by external trigger (for ADC1, ADC2 and ADC3) + * @retval None + */ +void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_EXT_INJEC_TRIG(ADC_ExternalTrigInjecConv)); + /* Get the old register value */ + tmpreg = ADCx->CR2; + /* Clear the old external event selection for injected group */ + tmpreg &= CR2_JEXTSEL_Reset; + /* Set the external event selection for injected group */ + tmpreg |= ADC_ExternalTrigInjecConv; + /* Store the new register value */ + ADCx->CR2 = tmpreg; +} + +/** + * @brief Enables or disables the ADCx injected channels conversion through + * external trigger + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC external trigger start of + * injected conversion. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC external event selection for injected group */ + ADCx->CR2 |= CR2_JEXTTRIG_Set; + } + else + { + /* Disable the selected ADC external event selection for injected group */ + ADCx->CR2 &= CR2_JEXTTRIG_Reset; + } +} + +/** + * @brief Enables or disables the selected ADC start of the injected + * channels conversion. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC software start injected conversion. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC conversion for injected group on external event and start the selected + ADC injected conversion */ + ADCx->CR2 |= CR2_JEXTTRIG_JSWSTART_Set; + } + else + { + /* Disable the selected ADC conversion on external event for injected group and stop the selected + ADC injected conversion */ + ADCx->CR2 &= CR2_JEXTTRIG_JSWSTART_Reset; + } +} + +/** + * @brief Gets the selected ADC Software start injected conversion Status. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The new state of ADC software start injected conversion (SET or RESET). + */ +FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Check the status of JSWSTART bit */ + if ((ADCx->CR2 & CR2_JSWSTART_Set) != (uint32_t)RESET) + { + /* JSWSTART bit is set */ + bitstatus = SET; + } + else + { + /* JSWSTART bit is reset */ + bitstatus = RESET; + } + /* Return the JSWSTART bit status */ + return bitstatus; +} + +/** + * @brief Configures for the selected ADC injected channel its corresponding + * rank in the sequencer and its sample time. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure. + * This parameter can be one of the following values: + * @arg ADC_Channel_0: ADC Channel0 selected + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @param Rank: The rank in the injected group sequencer. This parameter must be between 1 and 4. + * @param ADC_SampleTime: The sample time value to be set for the selected channel. + * This parameter can be one of the following values: + * @arg ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles + * @arg ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles + * @arg ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles + * @arg ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles + * @arg ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles + * @arg ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles + * @arg ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles + * @arg ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles + * @retval None + */ +void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime) +{ + uint32_t tmpreg1 = 0, tmpreg2 = 0, tmpreg3 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + assert_param(IS_ADC_INJECTED_RANK(Rank)); + assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime)); + /* if ADC_Channel_10 ... ADC_Channel_17 is selected */ + if (ADC_Channel > ADC_Channel_9) + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR1; + /* Calculate the mask to clear */ + tmpreg2 = SMPR1_SMP_Set << (3*(ADC_Channel - 10)); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3*(ADC_Channel - 10)); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SMPR1 = tmpreg1; + } + else /* ADC_Channel include in ADC_Channel_[0..9] */ + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR2; + /* Calculate the mask to clear */ + tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SMPR2 = tmpreg1; + } + /* Rank configuration */ + /* Get the old register value */ + tmpreg1 = ADCx->JSQR; + /* Get JL value: Number = JL+1 */ + tmpreg3 = (tmpreg1 & JSQR_JL_Set)>> 20; + /* Calculate the mask to clear: ((Rank-1)+(4-JL-1)) */ + tmpreg2 = JSQR_JSQ_Set << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1))); + /* Clear the old JSQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set: ((Rank-1)+(4-JL-1)) */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1))); + /* Set the JSQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->JSQR = tmpreg1; +} + +/** + * @brief Configures the sequencer length for injected channels + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param Length: The sequencer length. + * This parameter must be a number between 1 to 4. + * @retval None + */ +void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length) +{ + uint32_t tmpreg1 = 0; + uint32_t tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_INJECTED_LENGTH(Length)); + + /* Get the old register value */ + tmpreg1 = ADCx->JSQR; + /* Clear the old injected sequnence lenght JL bits */ + tmpreg1 &= JSQR_JL_Reset; + /* Set the injected sequnence lenght JL bits */ + tmpreg2 = Length - 1; + tmpreg1 |= tmpreg2 << 20; + /* Store the new register value */ + ADCx->JSQR = tmpreg1; +} + +/** + * @brief Set the injected channels conversion value offset + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_InjectedChannel: the ADC injected channel to set its offset. + * This parameter can be one of the following values: + * @arg ADC_InjectedChannel_1: Injected Channel1 selected + * @arg ADC_InjectedChannel_2: Injected Channel2 selected + * @arg ADC_InjectedChannel_3: Injected Channel3 selected + * @arg ADC_InjectedChannel_4: Injected Channel4 selected + * @param Offset: the offset value for the selected ADC injected channel + * This parameter must be a 12bit value. + * @retval None + */ +void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel)); + assert_param(IS_ADC_OFFSET(Offset)); + + tmp = (uint32_t)ADCx; + tmp += ADC_InjectedChannel; + + /* Set the selected injected channel data offset */ + *(__IO uint32_t *) tmp = (uint32_t)Offset; +} + +/** + * @brief Returns the ADC injected channel conversion result + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_InjectedChannel: the converted ADC injected channel. + * This parameter can be one of the following values: + * @arg ADC_InjectedChannel_1: Injected Channel1 selected + * @arg ADC_InjectedChannel_2: Injected Channel2 selected + * @arg ADC_InjectedChannel_3: Injected Channel3 selected + * @arg ADC_InjectedChannel_4: Injected Channel4 selected + * @retval The Data conversion value. + */ +uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel)); + + tmp = (uint32_t)ADCx; + tmp += ADC_InjectedChannel + JDR_Offset; + + /* Returns the selected injected channel conversion data value */ + return (uint16_t) (*(__IO uint32_t*) tmp); +} + +/** + * @brief Enables or disables the analog watchdog on single/all regular + * or injected channels + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_AnalogWatchdog: the ADC analog watchdog configuration. + * This parameter can be one of the following values: + * @arg ADC_AnalogWatchdog_SingleRegEnable: Analog watchdog on a single regular channel + * @arg ADC_AnalogWatchdog_SingleInjecEnable: Analog watchdog on a single injected channel + * @arg ADC_AnalogWatchdog_SingleRegOrInjecEnable: Analog watchdog on a single regular or injected channel + * @arg ADC_AnalogWatchdog_AllRegEnable: Analog watchdog on all regular channel + * @arg ADC_AnalogWatchdog_AllInjecEnable: Analog watchdog on all injected channel + * @arg ADC_AnalogWatchdog_AllRegAllInjecEnable: Analog watchdog on all regular and injected channels + * @arg ADC_AnalogWatchdog_None: No channel guarded by the analog watchdog + * @retval None + */ +void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_ANALOG_WATCHDOG(ADC_AnalogWatchdog)); + /* Get the old register value */ + tmpreg = ADCx->CR1; + /* Clear AWDEN, AWDENJ and AWDSGL bits */ + tmpreg &= CR1_AWDMode_Reset; + /* Set the analog watchdog enable mode */ + tmpreg |= ADC_AnalogWatchdog; + /* Store the new register value */ + ADCx->CR1 = tmpreg; +} + +/** + * @brief Configures the high and low thresholds of the analog watchdog. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param HighThreshold: the ADC analog watchdog High threshold value. + * This parameter must be a 12bit value. + * @param LowThreshold: the ADC analog watchdog Low threshold value. + * This parameter must be a 12bit value. + * @retval None + */ +void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold, + uint16_t LowThreshold) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_THRESHOLD(HighThreshold)); + assert_param(IS_ADC_THRESHOLD(LowThreshold)); + /* Set the ADCx high threshold */ + ADCx->HTR = HighThreshold; + /* Set the ADCx low threshold */ + ADCx->LTR = LowThreshold; +} + +/** + * @brief Configures the analog watchdog guarded single channel + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure for the analog watchdog. + * This parameter can be one of the following values: + * @arg ADC_Channel_0: ADC Channel0 selected + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @retval None + */ +void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + /* Get the old register value */ + tmpreg = ADCx->CR1; + /* Clear the Analog watchdog channel select bits */ + tmpreg &= CR1_AWDCH_Reset; + /* Set the Analog watchdog channel */ + tmpreg |= ADC_Channel; + /* Store the new register value */ + ADCx->CR1 = tmpreg; +} + +/** + * @brief Enables or disables the temperature sensor and Vrefint channel. + * @param NewState: new state of the temperature sensor. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_TempSensorVrefintCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the temperature sensor and Vrefint channel*/ + ADC1->CR2 |= CR2_TSVREFE_Set; + } + else + { + /* Disable the temperature sensor and Vrefint channel*/ + ADC1->CR2 &= CR2_TSVREFE_Reset; + } +} + +/** + * @brief Checks whether the specified ADC flag is set or not. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg ADC_FLAG_AWD: Analog watchdog flag + * @arg ADC_FLAG_EOC: End of conversion flag + * @arg ADC_FLAG_JEOC: End of injected group conversion flag + * @arg ADC_FLAG_JSTRT: Start of injected group conversion flag + * @arg ADC_FLAG_STRT: Start of regular group conversion flag + * @retval The new state of ADC_FLAG (SET or RESET). + */ +FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_GET_FLAG(ADC_FLAG)); + /* Check the status of the specified ADC flag */ + if ((ADCx->SR & ADC_FLAG) != (uint8_t)RESET) + { + /* ADC_FLAG is set */ + bitstatus = SET; + } + else + { + /* ADC_FLAG is reset */ + bitstatus = RESET; + } + /* Return the ADC_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the ADCx's pending flags. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg ADC_FLAG_AWD: Analog watchdog flag + * @arg ADC_FLAG_EOC: End of conversion flag + * @arg ADC_FLAG_JEOC: End of injected group conversion flag + * @arg ADC_FLAG_JSTRT: Start of injected group conversion flag + * @arg ADC_FLAG_STRT: Start of regular group conversion flag + * @retval None + */ +void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CLEAR_FLAG(ADC_FLAG)); + /* Clear the selected ADC flags */ + ADCx->SR = ~(uint32_t)ADC_FLAG; +} + +/** + * @brief Checks whether the specified ADC interrupt has occurred or not. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_IT: specifies the ADC interrupt source to check. + * This parameter can be one of the following values: + * @arg ADC_IT_EOC: End of conversion interrupt mask + * @arg ADC_IT_AWD: Analog watchdog interrupt mask + * @arg ADC_IT_JEOC: End of injected conversion interrupt mask + * @retval The new state of ADC_IT (SET or RESET). + */ +ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t itmask = 0, enablestatus = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_GET_IT(ADC_IT)); + /* Get the ADC IT index */ + itmask = ADC_IT >> 8; + /* Get the ADC_IT enable bit status */ + enablestatus = (ADCx->CR1 & (uint8_t)ADC_IT) ; + /* Check the status of the specified ADC interrupt */ + if (((ADCx->SR & itmask) != (uint32_t)RESET) && enablestatus) + { + /* ADC_IT is set */ + bitstatus = SET; + } + else + { + /* ADC_IT is reset */ + bitstatus = RESET; + } + /* Return the ADC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the ADCx's interrupt pending bits. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_IT: specifies the ADC interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg ADC_IT_EOC: End of conversion interrupt mask + * @arg ADC_IT_AWD: Analog watchdog interrupt mask + * @arg ADC_IT_JEOC: End of injected conversion interrupt mask + * @retval None + */ +void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT) +{ + uint8_t itmask = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_IT(ADC_IT)); + /* Get the ADC IT index */ + itmask = (uint8_t)(ADC_IT >> 8); + /* Clear the selected ADC interrupt pending bits */ + ADCx->SR = ~(uint32_t)itmask; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c new file mode 100644 index 0000000..997eecc --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c @@ -0,0 +1,308 @@ +/** + ****************************************************************************** + * @file stm32f10x_bkp.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the BKP firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_bkp.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup BKP + * @brief BKP driver modules + * @{ + */ + +/** @defgroup BKP_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Private_Defines + * @{ + */ + +/* ------------ BKP registers bit address in the alias region --------------- */ +#define BKP_OFFSET (BKP_BASE - PERIPH_BASE) + +/* --- CR Register ----*/ + +/* Alias word address of TPAL bit */ +#define CR_OFFSET (BKP_OFFSET + 0x30) +#define TPAL_BitNumber 0x01 +#define CR_TPAL_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPAL_BitNumber * 4)) + +/* Alias word address of TPE bit */ +#define TPE_BitNumber 0x00 +#define CR_TPE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPE_BitNumber * 4)) + +/* --- CSR Register ---*/ + +/* Alias word address of TPIE bit */ +#define CSR_OFFSET (BKP_OFFSET + 0x34) +#define TPIE_BitNumber 0x02 +#define CSR_TPIE_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TPIE_BitNumber * 4)) + +/* Alias word address of TIF bit */ +#define TIF_BitNumber 0x09 +#define CSR_TIF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TIF_BitNumber * 4)) + +/* Alias word address of TEF bit */ +#define TEF_BitNumber 0x08 +#define CSR_TEF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TEF_BitNumber * 4)) + +/* ---------------------- BKP registers bit mask ------------------------ */ + +/* RTCCR register bit mask */ +#define RTCCR_CAL_MASK ((uint16_t)0xFF80) +#define RTCCR_MASK ((uint16_t)0xFC7F) + +/** + * @} + */ + + +/** @defgroup BKP_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the BKP peripheral registers to their default reset values. + * @param None + * @retval None + */ +void BKP_DeInit(void) +{ + RCC_BackupResetCmd(ENABLE); + RCC_BackupResetCmd(DISABLE); +} + +/** + * @brief Configures the Tamper Pin active level. + * @param BKP_TamperPinLevel: specifies the Tamper Pin active level. + * This parameter can be one of the following values: + * @arg BKP_TamperPinLevel_High: Tamper pin active on high level + * @arg BKP_TamperPinLevel_Low: Tamper pin active on low level + * @retval None + */ +void BKP_TamperPinLevelConfig(uint16_t BKP_TamperPinLevel) +{ + /* Check the parameters */ + assert_param(IS_BKP_TAMPER_PIN_LEVEL(BKP_TamperPinLevel)); + *(__IO uint32_t *) CR_TPAL_BB = BKP_TamperPinLevel; +} + +/** + * @brief Enables or disables the Tamper Pin activation. + * @param NewState: new state of the Tamper Pin activation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void BKP_TamperPinCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_TPE_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the Tamper Pin Interrupt. + * @param NewState: new state of the Tamper Pin Interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void BKP_ITConfig(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CSR_TPIE_BB = (uint32_t)NewState; +} + +/** + * @brief Select the RTC output source to output on the Tamper pin. + * @param BKP_RTCOutputSource: specifies the RTC output source. + * This parameter can be one of the following values: + * @arg BKP_RTCOutputSource_None: no RTC output on the Tamper pin. + * @arg BKP_RTCOutputSource_CalibClock: output the RTC clock with frequency + * divided by 64 on the Tamper pin. + * @arg BKP_RTCOutputSource_Alarm: output the RTC Alarm pulse signal on + * the Tamper pin. + * @arg BKP_RTCOutputSource_Second: output the RTC Second pulse signal on + * the Tamper pin. + * @retval None + */ +void BKP_RTCOutputConfig(uint16_t BKP_RTCOutputSource) +{ + uint16_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_BKP_RTC_OUTPUT_SOURCE(BKP_RTCOutputSource)); + tmpreg = BKP->RTCCR; + /* Clear CCO, ASOE and ASOS bits */ + tmpreg &= RTCCR_MASK; + + /* Set CCO, ASOE and ASOS bits according to BKP_RTCOutputSource value */ + tmpreg |= BKP_RTCOutputSource; + /* Store the new value */ + BKP->RTCCR = tmpreg; +} + +/** + * @brief Sets RTC Clock Calibration value. + * @param CalibrationValue: specifies the RTC Clock Calibration value. + * This parameter must be a number between 0 and 0x7F. + * @retval None + */ +void BKP_SetRTCCalibrationValue(uint8_t CalibrationValue) +{ + uint16_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_BKP_CALIBRATION_VALUE(CalibrationValue)); + tmpreg = BKP->RTCCR; + /* Clear CAL[6:0] bits */ + tmpreg &= RTCCR_CAL_MASK; + /* Set CAL[6:0] bits according to CalibrationValue value */ + tmpreg |= CalibrationValue; + /* Store the new value */ + BKP->RTCCR = tmpreg; +} + +/** + * @brief Writes user data to the specified Data Backup Register. + * @param BKP_DR: specifies the Data Backup Register. + * This parameter can be BKP_DRx where x:[1, 42] + * @param Data: data to write + * @retval None + */ +void BKP_WriteBackupRegister(uint16_t BKP_DR, uint16_t Data) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_BKP_DR(BKP_DR)); + + tmp = (uint32_t)BKP_BASE; + tmp += BKP_DR; + + *(__IO uint32_t *) tmp = Data; +} + +/** + * @brief Reads data from the specified Data Backup Register. + * @param BKP_DR: specifies the Data Backup Register. + * This parameter can be BKP_DRx where x:[1, 42] + * @retval The content of the specified Data Backup Register + */ +uint16_t BKP_ReadBackupRegister(uint16_t BKP_DR) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_BKP_DR(BKP_DR)); + + tmp = (uint32_t)BKP_BASE; + tmp += BKP_DR; + + return (*(__IO uint16_t *) tmp); +} + +/** + * @brief Checks whether the Tamper Pin Event flag is set or not. + * @param None + * @retval The new state of the Tamper Pin Event flag (SET or RESET). + */ +FlagStatus BKP_GetFlagStatus(void) +{ + return (FlagStatus)(*(__IO uint32_t *) CSR_TEF_BB); +} + +/** + * @brief Clears Tamper Pin Event pending flag. + * @param None + * @retval None + */ +void BKP_ClearFlag(void) +{ + /* Set CTE bit to clear Tamper Pin Event flag */ + BKP->CSR |= BKP_CSR_CTE; +} + +/** + * @brief Checks whether the Tamper Pin Interrupt has occurred or not. + * @param None + * @retval The new state of the Tamper Pin Interrupt (SET or RESET). + */ +ITStatus BKP_GetITStatus(void) +{ + return (ITStatus)(*(__IO uint32_t *) CSR_TIF_BB); +} + +/** + * @brief Clears Tamper Pin Interrupt pending bit. + * @param None + * @retval None + */ +void BKP_ClearITPendingBit(void) +{ + /* Set CTI bit to clear Tamper Pin Interrupt pending bit */ + BKP->CSR |= BKP_CSR_CTI; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c new file mode 100644 index 0000000..ec8e049 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c @@ -0,0 +1,1415 @@ +/** + ****************************************************************************** + * @file stm32f10x_can.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the CAN firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_can.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup CAN + * @brief CAN driver modules + * @{ + */ + +/** @defgroup CAN_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup CAN_Private_Defines + * @{ + */ + +/* CAN Master Control Register bits */ + +#define MCR_DBF ((uint32_t)0x00010000) /* software master reset */ + +/* CAN Mailbox Transmit Request */ +#define TMIDxR_TXRQ ((uint32_t)0x00000001) /* Transmit mailbox request */ + +/* CAN Filter Master Register bits */ +#define FMR_FINIT ((uint32_t)0x00000001) /* Filter init mode */ + +/* Time out for INAK bit */ +#define INAK_TIMEOUT ((uint32_t)0x0000FFFF) +/* Time out for SLAK bit */ +#define SLAK_TIMEOUT ((uint32_t)0x0000FFFF) + + + +/* Flags in TSR register */ +#define CAN_FLAGS_TSR ((uint32_t)0x08000000) +/* Flags in RF1R register */ +#define CAN_FLAGS_RF1R ((uint32_t)0x04000000) +/* Flags in RF0R register */ +#define CAN_FLAGS_RF0R ((uint32_t)0x02000000) +/* Flags in MSR register */ +#define CAN_FLAGS_MSR ((uint32_t)0x01000000) +/* Flags in ESR register */ +#define CAN_FLAGS_ESR ((uint32_t)0x00F00000) + +/* Mailboxes definition */ +#define CAN_TXMAILBOX_0 ((uint8_t)0x00) +#define CAN_TXMAILBOX_1 ((uint8_t)0x01) +#define CAN_TXMAILBOX_2 ((uint8_t)0x02) + + + +#define CAN_MODE_MASK ((uint32_t) 0x00000003) +/** + * @} + */ + +/** @defgroup CAN_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup CAN_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup CAN_Private_FunctionPrototypes + * @{ + */ + +static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit); + +/** + * @} + */ + +/** @defgroup CAN_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the CAN peripheral registers to their default reset values. + * @param CANx: where x can be 1 or 2 to select the CAN peripheral. + * @retval None. + */ +void CAN_DeInit(CAN_TypeDef* CANx) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + if (CANx == CAN1) + { + /* Enable CAN1 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, ENABLE); + /* Release CAN1 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, DISABLE); + } + else + { + /* Enable CAN2 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN2, ENABLE); + /* Release CAN2 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN2, DISABLE); + } +} + +/** + * @brief Initializes the CAN peripheral according to the specified + * parameters in the CAN_InitStruct. + * @param CANx: where x can be 1 or 2 to to select the CAN + * peripheral. + * @param CAN_InitStruct: pointer to a CAN_InitTypeDef structure that + * contains the configuration information for the + * CAN peripheral. + * @retval Constant indicates initialization succeed which will be + * CAN_InitStatus_Failed or CAN_InitStatus_Success. + */ +uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct) +{ + uint8_t InitStatus = CAN_InitStatus_Failed; + uint32_t wait_ack = 0x00000000; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TTCM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_ABOM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_AWUM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_NART)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_RFLM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TXFP)); + assert_param(IS_CAN_MODE(CAN_InitStruct->CAN_Mode)); + assert_param(IS_CAN_SJW(CAN_InitStruct->CAN_SJW)); + assert_param(IS_CAN_BS1(CAN_InitStruct->CAN_BS1)); + assert_param(IS_CAN_BS2(CAN_InitStruct->CAN_BS2)); + assert_param(IS_CAN_PRESCALER(CAN_InitStruct->CAN_Prescaler)); + + /* Exit from sleep mode */ + CANx->MCR &= (~(uint32_t)CAN_MCR_SLEEP); + + /* Request initialisation */ + CANx->MCR |= CAN_MCR_INRQ ; + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) && (wait_ack != INAK_TIMEOUT)) + { + wait_ack++; + } + + /* Check acknowledge */ + if ((CANx->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) + { + InitStatus = CAN_InitStatus_Failed; + } + else + { + /* Set the time triggered communication mode */ + if (CAN_InitStruct->CAN_TTCM == ENABLE) + { + CANx->MCR |= CAN_MCR_TTCM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_TTCM; + } + + /* Set the automatic bus-off management */ + if (CAN_InitStruct->CAN_ABOM == ENABLE) + { + CANx->MCR |= CAN_MCR_ABOM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_ABOM; + } + + /* Set the automatic wake-up mode */ + if (CAN_InitStruct->CAN_AWUM == ENABLE) + { + CANx->MCR |= CAN_MCR_AWUM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_AWUM; + } + + /* Set the no automatic retransmission */ + if (CAN_InitStruct->CAN_NART == ENABLE) + { + CANx->MCR |= CAN_MCR_NART; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_NART; + } + + /* Set the receive FIFO locked mode */ + if (CAN_InitStruct->CAN_RFLM == ENABLE) + { + CANx->MCR |= CAN_MCR_RFLM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_RFLM; + } + + /* Set the transmit FIFO priority */ + if (CAN_InitStruct->CAN_TXFP == ENABLE) + { + CANx->MCR |= CAN_MCR_TXFP; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_TXFP; + } + + /* Set the bit timing register */ + CANx->BTR = (uint32_t)((uint32_t)CAN_InitStruct->CAN_Mode << 30) | \ + ((uint32_t)CAN_InitStruct->CAN_SJW << 24) | \ + ((uint32_t)CAN_InitStruct->CAN_BS1 << 16) | \ + ((uint32_t)CAN_InitStruct->CAN_BS2 << 20) | \ + ((uint32_t)CAN_InitStruct->CAN_Prescaler - 1); + + /* Request leave initialisation */ + CANx->MCR &= ~(uint32_t)CAN_MCR_INRQ; + + /* Wait the acknowledge */ + wait_ack = 0; + + while (((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) && (wait_ack != INAK_TIMEOUT)) + { + wait_ack++; + } + + /* ...and check acknowledged */ + if ((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) + { + InitStatus = CAN_InitStatus_Failed; + } + else + { + InitStatus = CAN_InitStatus_Success ; + } + } + + /* At this step, return the status of initialization */ + return InitStatus; +} + +/** + * @brief Initializes the CAN peripheral according to the specified + * parameters in the CAN_FilterInitStruct. + * @param CAN_FilterInitStruct: pointer to a CAN_FilterInitTypeDef + * structure that contains the configuration + * information. + * @retval None. + */ +void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct) +{ + uint32_t filter_number_bit_pos = 0; + /* Check the parameters */ + assert_param(IS_CAN_FILTER_NUMBER(CAN_FilterInitStruct->CAN_FilterNumber)); + assert_param(IS_CAN_FILTER_MODE(CAN_FilterInitStruct->CAN_FilterMode)); + assert_param(IS_CAN_FILTER_SCALE(CAN_FilterInitStruct->CAN_FilterScale)); + assert_param(IS_CAN_FILTER_FIFO(CAN_FilterInitStruct->CAN_FilterFIFOAssignment)); + assert_param(IS_FUNCTIONAL_STATE(CAN_FilterInitStruct->CAN_FilterActivation)); + + filter_number_bit_pos = ((uint32_t)1) << CAN_FilterInitStruct->CAN_FilterNumber; + + /* Initialisation mode for the filter */ + CAN1->FMR |= FMR_FINIT; + + /* Filter Deactivation */ + CAN1->FA1R &= ~(uint32_t)filter_number_bit_pos; + + /* Filter Scale */ + if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_16bit) + { + /* 16-bit scale for the filter */ + CAN1->FS1R &= ~(uint32_t)filter_number_bit_pos; + + /* First 16-bit identifier and First 16-bit mask */ + /* Or First 16-bit identifier and Second 16-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow); + + /* Second 16-bit identifier and Second 16-bit mask */ + /* Or Third 16-bit identifier and Fourth 16-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh); + } + + if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_32bit) + { + /* 32-bit scale for the filter */ + CAN1->FS1R |= filter_number_bit_pos; + /* 32-bit identifier or First 32-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow); + /* 32-bit mask or Second 32-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow); + } + + /* Filter Mode */ + if (CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdMask) + { + /*Id/Mask mode for the filter*/ + CAN1->FM1R &= ~(uint32_t)filter_number_bit_pos; + } + else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */ + { + /*Identifier list mode for the filter*/ + CAN1->FM1R |= (uint32_t)filter_number_bit_pos; + } + + /* Filter FIFO assignment */ + if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_Filter_FIFO0) + { + /* FIFO 0 assignation for the filter */ + CAN1->FFA1R &= ~(uint32_t)filter_number_bit_pos; + } + + if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_Filter_FIFO1) + { + /* FIFO 1 assignation for the filter */ + CAN1->FFA1R |= (uint32_t)filter_number_bit_pos; + } + + /* Filter activation */ + if (CAN_FilterInitStruct->CAN_FilterActivation == ENABLE) + { + CAN1->FA1R |= filter_number_bit_pos; + } + + /* Leave the initialisation mode for the filter */ + CAN1->FMR &= ~FMR_FINIT; +} + +/** + * @brief Fills each CAN_InitStruct member with its default value. + * @param CAN_InitStruct: pointer to a CAN_InitTypeDef structure which + * will be initialized. + * @retval None. + */ +void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct) +{ + /* Reset CAN init structure parameters values */ + + /* Initialize the time triggered communication mode */ + CAN_InitStruct->CAN_TTCM = DISABLE; + + /* Initialize the automatic bus-off management */ + CAN_InitStruct->CAN_ABOM = DISABLE; + + /* Initialize the automatic wake-up mode */ + CAN_InitStruct->CAN_AWUM = DISABLE; + + /* Initialize the no automatic retransmission */ + CAN_InitStruct->CAN_NART = DISABLE; + + /* Initialize the receive FIFO locked mode */ + CAN_InitStruct->CAN_RFLM = DISABLE; + + /* Initialize the transmit FIFO priority */ + CAN_InitStruct->CAN_TXFP = DISABLE; + + /* Initialize the CAN_Mode member */ + CAN_InitStruct->CAN_Mode = CAN_Mode_Normal; + + /* Initialize the CAN_SJW member */ + CAN_InitStruct->CAN_SJW = CAN_SJW_1tq; + + /* Initialize the CAN_BS1 member */ + CAN_InitStruct->CAN_BS1 = CAN_BS1_4tq; + + /* Initialize the CAN_BS2 member */ + CAN_InitStruct->CAN_BS2 = CAN_BS2_3tq; + + /* Initialize the CAN_Prescaler member */ + CAN_InitStruct->CAN_Prescaler = 1; +} + +/** + * @brief Select the start bank filter for slave CAN. + * @note This function applies only to STM32 Connectivity line devices. + * @param CAN_BankNumber: Select the start slave bank filter from 1..27. + * @retval None. + */ +void CAN_SlaveStartBank(uint8_t CAN_BankNumber) +{ + /* Check the parameters */ + assert_param(IS_CAN_BANKNUMBER(CAN_BankNumber)); + + /* Enter Initialisation mode for the filter */ + CAN1->FMR |= FMR_FINIT; + + /* Select the start slave bank */ + CAN1->FMR &= (uint32_t)0xFFFFC0F1 ; + CAN1->FMR |= (uint32_t)(CAN_BankNumber)<<8; + + /* Leave Initialisation mode for the filter */ + CAN1->FMR &= ~FMR_FINIT; +} + +/** + * @brief Enables or disables the DBG Freeze for CAN. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param NewState: new state of the CAN peripheral. This parameter can + * be: ENABLE or DISABLE. + * @retval None. + */ +void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable Debug Freeze */ + CANx->MCR |= MCR_DBF; + } + else + { + /* Disable Debug Freeze */ + CANx->MCR &= ~MCR_DBF; + } +} + + +/** + * @brief Enables or disabes the CAN Time TriggerOperation communication mode. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param NewState : Mode new state , can be one of @ref FunctionalState. + * @note when enabled, Time stamp (TIME[15:0]) value is sent in the last + * two data bytes of the 8-byte message: TIME[7:0] in data byte 6 + * and TIME[15:8] in data byte 7 + * @note DLC must be programmed as 8 in order Time Stamp (2 bytes) to be + * sent over the CAN bus. + * @retval None + */ +void CAN_TTComModeCmd(CAN_TypeDef* CANx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the TTCM mode */ + CANx->MCR |= CAN_MCR_TTCM; + + /* Set TGT bits */ + CANx->sTxMailBox[0].TDTR |= ((uint32_t)CAN_TDT0R_TGT); + CANx->sTxMailBox[1].TDTR |= ((uint32_t)CAN_TDT1R_TGT); + CANx->sTxMailBox[2].TDTR |= ((uint32_t)CAN_TDT2R_TGT); + } + else + { + /* Disable the TTCM mode */ + CANx->MCR &= (uint32_t)(~(uint32_t)CAN_MCR_TTCM); + + /* Reset TGT bits */ + CANx->sTxMailBox[0].TDTR &= ((uint32_t)~CAN_TDT0R_TGT); + CANx->sTxMailBox[1].TDTR &= ((uint32_t)~CAN_TDT1R_TGT); + CANx->sTxMailBox[2].TDTR &= ((uint32_t)~CAN_TDT2R_TGT); + } +} +/** + * @brief Initiates the transmission of a message. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param TxMessage: pointer to a structure which contains CAN Id, CAN + * DLC and CAN data. + * @retval The number of the mailbox that is used for transmission + * or CAN_TxStatus_NoMailBox if there is no empty mailbox. + */ +uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage) +{ + uint8_t transmit_mailbox = 0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_IDTYPE(TxMessage->IDE)); + assert_param(IS_CAN_RTR(TxMessage->RTR)); + assert_param(IS_CAN_DLC(TxMessage->DLC)); + + /* Select one empty transmit mailbox */ + if ((CANx->TSR&CAN_TSR_TME0) == CAN_TSR_TME0) + { + transmit_mailbox = 0; + } + else if ((CANx->TSR&CAN_TSR_TME1) == CAN_TSR_TME1) + { + transmit_mailbox = 1; + } + else if ((CANx->TSR&CAN_TSR_TME2) == CAN_TSR_TME2) + { + transmit_mailbox = 2; + } + else + { + transmit_mailbox = CAN_TxStatus_NoMailBox; + } + + if (transmit_mailbox != CAN_TxStatus_NoMailBox) + { + /* Set up the Id */ + CANx->sTxMailBox[transmit_mailbox].TIR &= TMIDxR_TXRQ; + if (TxMessage->IDE == CAN_Id_Standard) + { + assert_param(IS_CAN_STDID(TxMessage->StdId)); + CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->StdId << 21) | \ + TxMessage->RTR); + } + else + { + assert_param(IS_CAN_EXTID(TxMessage->ExtId)); + CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->ExtId << 3) | \ + TxMessage->IDE | \ + TxMessage->RTR); + } + + /* Set up the DLC */ + TxMessage->DLC &= (uint8_t)0x0000000F; + CANx->sTxMailBox[transmit_mailbox].TDTR &= (uint32_t)0xFFFFFFF0; + CANx->sTxMailBox[transmit_mailbox].TDTR |= TxMessage->DLC; + + /* Set up the data field */ + CANx->sTxMailBox[transmit_mailbox].TDLR = (((uint32_t)TxMessage->Data[3] << 24) | + ((uint32_t)TxMessage->Data[2] << 16) | + ((uint32_t)TxMessage->Data[1] << 8) | + ((uint32_t)TxMessage->Data[0])); + CANx->sTxMailBox[transmit_mailbox].TDHR = (((uint32_t)TxMessage->Data[7] << 24) | + ((uint32_t)TxMessage->Data[6] << 16) | + ((uint32_t)TxMessage->Data[5] << 8) | + ((uint32_t)TxMessage->Data[4])); + /* Request transmission */ + CANx->sTxMailBox[transmit_mailbox].TIR |= TMIDxR_TXRQ; + } + return transmit_mailbox; +} + +/** + * @brief Checks the transmission of a message. + * @param CANx: where x can be 1 or 2 to to select the + * CAN peripheral. + * @param TransmitMailbox: the number of the mailbox that is used for + * transmission. + * @retval CAN_TxStatus_Ok if the CAN driver transmits the message, CAN_TxStatus_Failed + * in an other case. + */ +uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox) +{ + uint32_t state = 0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_TRANSMITMAILBOX(TransmitMailbox)); + + switch (TransmitMailbox) + { + case (CAN_TXMAILBOX_0): + state = CANx->TSR & (CAN_TSR_RQCP0 | CAN_TSR_TXOK0 | CAN_TSR_TME0); + break; + case (CAN_TXMAILBOX_1): + state = CANx->TSR & (CAN_TSR_RQCP1 | CAN_TSR_TXOK1 | CAN_TSR_TME1); + break; + case (CAN_TXMAILBOX_2): + state = CANx->TSR & (CAN_TSR_RQCP2 | CAN_TSR_TXOK2 | CAN_TSR_TME2); + break; + default: + state = CAN_TxStatus_Failed; + break; + } + switch (state) + { + /* transmit pending */ + case (0x0): state = CAN_TxStatus_Pending; + break; + /* transmit failed */ + case (CAN_TSR_RQCP0 | CAN_TSR_TME0): state = CAN_TxStatus_Failed; + break; + case (CAN_TSR_RQCP1 | CAN_TSR_TME1): state = CAN_TxStatus_Failed; + break; + case (CAN_TSR_RQCP2 | CAN_TSR_TME2): state = CAN_TxStatus_Failed; + break; + /* transmit succeeded */ + case (CAN_TSR_RQCP0 | CAN_TSR_TXOK0 | CAN_TSR_TME0):state = CAN_TxStatus_Ok; + break; + case (CAN_TSR_RQCP1 | CAN_TSR_TXOK1 | CAN_TSR_TME1):state = CAN_TxStatus_Ok; + break; + case (CAN_TSR_RQCP2 | CAN_TSR_TXOK2 | CAN_TSR_TME2):state = CAN_TxStatus_Ok; + break; + default: state = CAN_TxStatus_Failed; + break; + } + return (uint8_t) state; +} + +/** + * @brief Cancels a transmit request. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param Mailbox: Mailbox number. + * @retval None. + */ +void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_TRANSMITMAILBOX(Mailbox)); + /* abort transmission */ + switch (Mailbox) + { + case (CAN_TXMAILBOX_0): CANx->TSR |= CAN_TSR_ABRQ0; + break; + case (CAN_TXMAILBOX_1): CANx->TSR |= CAN_TSR_ABRQ1; + break; + case (CAN_TXMAILBOX_2): CANx->TSR |= CAN_TSR_ABRQ2; + break; + default: + break; + } +} + + +/** + * @brief Receives a message. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. + * @param RxMessage: pointer to a structure receive message which contains + * CAN Id, CAN DLC, CAN datas and FMI number. + * @retval None. + */ +void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_FIFO(FIFONumber)); + /* Get the Id */ + RxMessage->IDE = (uint8_t)0x04 & CANx->sFIFOMailBox[FIFONumber].RIR; + if (RxMessage->IDE == CAN_Id_Standard) + { + RxMessage->StdId = (uint32_t)0x000007FF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 21); + } + else + { + RxMessage->ExtId = (uint32_t)0x1FFFFFFF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 3); + } + + RxMessage->RTR = (uint8_t)0x02 & CANx->sFIFOMailBox[FIFONumber].RIR; + /* Get the DLC */ + RxMessage->DLC = (uint8_t)0x0F & CANx->sFIFOMailBox[FIFONumber].RDTR; + /* Get the FMI */ + RxMessage->FMI = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDTR >> 8); + /* Get the data field */ + RxMessage->Data[0] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDLR; + RxMessage->Data[1] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 8); + RxMessage->Data[2] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 16); + RxMessage->Data[3] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 24); + RxMessage->Data[4] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDHR; + RxMessage->Data[5] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 8); + RxMessage->Data[6] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 16); + RxMessage->Data[7] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 24); + /* Release the FIFO */ + /* Release FIFO0 */ + if (FIFONumber == CAN_FIFO0) + { + CANx->RF0R |= CAN_RF0R_RFOM0; + } + /* Release FIFO1 */ + else /* FIFONumber == CAN_FIFO1 */ + { + CANx->RF1R |= CAN_RF1R_RFOM1; + } +} + +/** + * @brief Releases the specified FIFO. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param FIFONumber: FIFO to release, CAN_FIFO0 or CAN_FIFO1. + * @retval None. + */ +void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_FIFO(FIFONumber)); + /* Release FIFO0 */ + if (FIFONumber == CAN_FIFO0) + { + CANx->RF0R |= CAN_RF0R_RFOM0; + } + /* Release FIFO1 */ + else /* FIFONumber == CAN_FIFO1 */ + { + CANx->RF1R |= CAN_RF1R_RFOM1; + } +} + +/** + * @brief Returns the number of pending messages. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. + * @retval NbMessage : which is the number of pending message. + */ +uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber) +{ + uint8_t message_pending=0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_FIFO(FIFONumber)); + if (FIFONumber == CAN_FIFO0) + { + message_pending = (uint8_t)(CANx->RF0R&(uint32_t)0x03); + } + else if (FIFONumber == CAN_FIFO1) + { + message_pending = (uint8_t)(CANx->RF1R&(uint32_t)0x03); + } + else + { + message_pending = 0; + } + return message_pending; +} + + +/** + * @brief Select the CAN Operation mode. + * @param CAN_OperatingMode : CAN Operating Mode. This parameter can be one + * of @ref CAN_OperatingMode_TypeDef enumeration. + * @retval status of the requested mode which can be + * - CAN_ModeStatus_Failed CAN failed entering the specific mode + * - CAN_ModeStatus_Success CAN Succeed entering the specific mode + + */ +uint8_t CAN_OperatingModeRequest(CAN_TypeDef* CANx, uint8_t CAN_OperatingMode) +{ + uint8_t status = CAN_ModeStatus_Failed; + + /* Timeout for INAK or also for SLAK bits*/ + uint32_t timeout = INAK_TIMEOUT; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_OPERATING_MODE(CAN_OperatingMode)); + + if (CAN_OperatingMode == CAN_OperatingMode_Initialization) + { + /* Request initialisation */ + CANx->MCR = (uint32_t)((CANx->MCR & (uint32_t)(~(uint32_t)CAN_MCR_SLEEP)) | CAN_MCR_INRQ); + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_INAK) && (timeout != 0)) + { + timeout--; + } + if ((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_INAK) + { + status = CAN_ModeStatus_Failed; + } + else + { + status = CAN_ModeStatus_Success; + } + } + else if (CAN_OperatingMode == CAN_OperatingMode_Normal) + { + /* Request leave initialisation and sleep mode and enter Normal mode */ + CANx->MCR &= (uint32_t)(~(CAN_MCR_SLEEP|CAN_MCR_INRQ)); + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MODE_MASK) != 0) && (timeout!=0)) + { + timeout--; + } + if ((CANx->MSR & CAN_MODE_MASK) != 0) + { + status = CAN_ModeStatus_Failed; + } + else + { + status = CAN_ModeStatus_Success; + } + } + else if (CAN_OperatingMode == CAN_OperatingMode_Sleep) + { + /* Request Sleep mode */ + CANx->MCR = (uint32_t)((CANx->MCR & (uint32_t)(~(uint32_t)CAN_MCR_INRQ)) | CAN_MCR_SLEEP); + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_SLAK) && (timeout!=0)) + { + timeout--; + } + if ((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_SLAK) + { + status = CAN_ModeStatus_Failed; + } + else + { + status = CAN_ModeStatus_Success; + } + } + else + { + status = CAN_ModeStatus_Failed; + } + + return (uint8_t) status; +} + +/** + * @brief Enters the low power mode. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval status: CAN_Sleep_Ok if sleep entered, CAN_Sleep_Failed in an + * other case. + */ +uint8_t CAN_Sleep(CAN_TypeDef* CANx) +{ + uint8_t sleepstatus = CAN_Sleep_Failed; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Request Sleep mode */ + CANx->MCR = (((CANx->MCR) & (uint32_t)(~(uint32_t)CAN_MCR_INRQ)) | CAN_MCR_SLEEP); + + /* Sleep mode status */ + if ((CANx->MSR & (CAN_MSR_SLAK|CAN_MSR_INAK)) == CAN_MSR_SLAK) + { + /* Sleep mode not entered */ + sleepstatus = CAN_Sleep_Ok; + } + /* return sleep mode status */ + return (uint8_t)sleepstatus; +} + +/** + * @brief Wakes the CAN up. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval status: CAN_WakeUp_Ok if sleep mode left, CAN_WakeUp_Failed in an + * other case. + */ +uint8_t CAN_WakeUp(CAN_TypeDef* CANx) +{ + uint32_t wait_slak = SLAK_TIMEOUT; + uint8_t wakeupstatus = CAN_WakeUp_Failed; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Wake up request */ + CANx->MCR &= ~(uint32_t)CAN_MCR_SLEEP; + + /* Sleep mode status */ + while(((CANx->MSR & CAN_MSR_SLAK) == CAN_MSR_SLAK)&&(wait_slak!=0x00)) + { + wait_slak--; + } + if((CANx->MSR & CAN_MSR_SLAK) != CAN_MSR_SLAK) + { + /* wake up done : Sleep mode exited */ + wakeupstatus = CAN_WakeUp_Ok; + } + /* return wakeup status */ + return (uint8_t)wakeupstatus; +} + + +/** + * @brief Returns the CANx's last error code (LEC). + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval CAN_ErrorCode: specifies the Error code : + * - CAN_ERRORCODE_NoErr No Error + * - CAN_ERRORCODE_StuffErr Stuff Error + * - CAN_ERRORCODE_FormErr Form Error + * - CAN_ERRORCODE_ACKErr Acknowledgment Error + * - CAN_ERRORCODE_BitRecessiveErr Bit Recessive Error + * - CAN_ERRORCODE_BitDominantErr Bit Dominant Error + * - CAN_ERRORCODE_CRCErr CRC Error + * - CAN_ERRORCODE_SoftwareSetErr Software Set Error + */ + +uint8_t CAN_GetLastErrorCode(CAN_TypeDef* CANx) +{ + uint8_t errorcode=0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Get the error code*/ + errorcode = (((uint8_t)CANx->ESR) & (uint8_t)CAN_ESR_LEC); + + /* Return the error code*/ + return errorcode; +} +/** + * @brief Returns the CANx Receive Error Counter (REC). + * @note In case of an error during reception, this counter is incremented + * by 1 or by 8 depending on the error condition as defined by the CAN + * standard. After every successful reception, the counter is + * decremented by 1 or reset to 120 if its value was higher than 128. + * When the counter value exceeds 127, the CAN controller enters the + * error passive state. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval CAN Receive Error Counter. + */ +uint8_t CAN_GetReceiveErrorCounter(CAN_TypeDef* CANx) +{ + uint8_t counter=0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Get the Receive Error Counter*/ + counter = (uint8_t)((CANx->ESR & CAN_ESR_REC)>> 24); + + /* Return the Receive Error Counter*/ + return counter; +} + + +/** + * @brief Returns the LSB of the 9-bit CANx Transmit Error Counter(TEC). + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval LSB of the 9-bit CAN Transmit Error Counter. + */ +uint8_t CAN_GetLSBTransmitErrorCounter(CAN_TypeDef* CANx) +{ + uint8_t counter=0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Get the LSB of the 9-bit CANx Transmit Error Counter(TEC) */ + counter = (uint8_t)((CANx->ESR & CAN_ESR_TEC)>> 16); + + /* Return the LSB of the 9-bit CANx Transmit Error Counter(TEC) */ + return counter; +} + + +/** + * @brief Enables or disables the specified CANx interrupts. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_IT: specifies the CAN interrupt sources to be enabled or disabled. + * This parameter can be: + * - CAN_IT_TME, + * - CAN_IT_FMP0, + * - CAN_IT_FF0, + * - CAN_IT_FOV0, + * - CAN_IT_FMP1, + * - CAN_IT_FF1, + * - CAN_IT_FOV1, + * - CAN_IT_EWG, + * - CAN_IT_EPV, + * - CAN_IT_LEC, + * - CAN_IT_ERR, + * - CAN_IT_WKU or + * - CAN_IT_SLK. + * @param NewState: new state of the CAN interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_IT(CAN_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected CANx interrupt */ + CANx->IER |= CAN_IT; + } + else + { + /* Disable the selected CANx interrupt */ + CANx->IER &= ~CAN_IT; + } +} +/** + * @brief Checks whether the specified CAN flag is set or not. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_FLAG: specifies the flag to check. + * This parameter can be one of the following flags: + * - CAN_FLAG_EWG + * - CAN_FLAG_EPV + * - CAN_FLAG_BOF + * - CAN_FLAG_RQCP0 + * - CAN_FLAG_RQCP1 + * - CAN_FLAG_RQCP2 + * - CAN_FLAG_FMP1 + * - CAN_FLAG_FF1 + * - CAN_FLAG_FOV1 + * - CAN_FLAG_FMP0 + * - CAN_FLAG_FF0 + * - CAN_FLAG_FOV0 + * - CAN_FLAG_WKU + * - CAN_FLAG_SLAK + * - CAN_FLAG_LEC + * @retval The new state of CAN_FLAG (SET or RESET). + */ +FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_GET_FLAG(CAN_FLAG)); + + + if((CAN_FLAG & CAN_FLAGS_ESR) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->ESR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else if((CAN_FLAG & CAN_FLAGS_MSR) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->MSR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else if((CAN_FLAG & CAN_FLAGS_TSR) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->TSR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else if((CAN_FLAG & CAN_FLAGS_RF0R) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->RF0R & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else /* If(CAN_FLAG & CAN_FLAGS_RF1R != (uint32_t)RESET) */ + { + /* Check the status of the specified CAN flag */ + if ((uint32_t)(CANx->RF1R & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + /* Return the CAN_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the CAN's pending flags. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_FLAG: specifies the flag to clear. + * This parameter can be one of the following flags: + * - CAN_FLAG_RQCP0 + * - CAN_FLAG_RQCP1 + * - CAN_FLAG_RQCP2 + * - CAN_FLAG_FF1 + * - CAN_FLAG_FOV1 + * - CAN_FLAG_FF0 + * - CAN_FLAG_FOV0 + * - CAN_FLAG_WKU + * - CAN_FLAG_SLAK + * - CAN_FLAG_LEC + * @retval None. + */ +void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG) +{ + uint32_t flagtmp=0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_CLEAR_FLAG(CAN_FLAG)); + + if (CAN_FLAG == CAN_FLAG_LEC) /* ESR register */ + { + /* Clear the selected CAN flags */ + CANx->ESR = (uint32_t)RESET; + } + else /* MSR or TSR or RF0R or RF1R */ + { + flagtmp = CAN_FLAG & 0x000FFFFF; + + if ((CAN_FLAG & CAN_FLAGS_RF0R)!=(uint32_t)RESET) + { + /* Receive Flags */ + CANx->RF0R = (uint32_t)(flagtmp); + } + else if ((CAN_FLAG & CAN_FLAGS_RF1R)!=(uint32_t)RESET) + { + /* Receive Flags */ + CANx->RF1R = (uint32_t)(flagtmp); + } + else if ((CAN_FLAG & CAN_FLAGS_TSR)!=(uint32_t)RESET) + { + /* Transmit Flags */ + CANx->TSR = (uint32_t)(flagtmp); + } + else /* If((CAN_FLAG & CAN_FLAGS_MSR)!=(uint32_t)RESET) */ + { + /* Operating mode Flags */ + CANx->MSR = (uint32_t)(flagtmp); + } + } +} + +/** + * @brief Checks whether the specified CANx interrupt has occurred or not. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_IT: specifies the CAN interrupt source to check. + * This parameter can be one of the following flags: + * - CAN_IT_TME + * - CAN_IT_FMP0 + * - CAN_IT_FF0 + * - CAN_IT_FOV0 + * - CAN_IT_FMP1 + * - CAN_IT_FF1 + * - CAN_IT_FOV1 + * - CAN_IT_WKU + * - CAN_IT_SLK + * - CAN_IT_EWG + * - CAN_IT_EPV + * - CAN_IT_BOF + * - CAN_IT_LEC + * - CAN_IT_ERR + * @retval The current state of CAN_IT (SET or RESET). + */ +ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT) +{ + ITStatus itstatus = RESET; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_IT(CAN_IT)); + + /* check the enable interrupt bit */ + if((CANx->IER & CAN_IT) != RESET) + { + /* in case the Interrupt is enabled, .... */ + switch (CAN_IT) + { + case CAN_IT_TME: + /* Check CAN_TSR_RQCPx bits */ + itstatus = CheckITStatus(CANx->TSR, CAN_TSR_RQCP0|CAN_TSR_RQCP1|CAN_TSR_RQCP2); + break; + case CAN_IT_FMP0: + /* Check CAN_RF0R_FMP0 bit */ + itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FMP0); + break; + case CAN_IT_FF0: + /* Check CAN_RF0R_FULL0 bit */ + itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FULL0); + break; + case CAN_IT_FOV0: + /* Check CAN_RF0R_FOVR0 bit */ + itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FOVR0); + break; + case CAN_IT_FMP1: + /* Check CAN_RF1R_FMP1 bit */ + itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FMP1); + break; + case CAN_IT_FF1: + /* Check CAN_RF1R_FULL1 bit */ + itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FULL1); + break; + case CAN_IT_FOV1: + /* Check CAN_RF1R_FOVR1 bit */ + itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FOVR1); + break; + case CAN_IT_WKU: + /* Check CAN_MSR_WKUI bit */ + itstatus = CheckITStatus(CANx->MSR, CAN_MSR_WKUI); + break; + case CAN_IT_SLK: + /* Check CAN_MSR_SLAKI bit */ + itstatus = CheckITStatus(CANx->MSR, CAN_MSR_SLAKI); + break; + case CAN_IT_EWG: + /* Check CAN_ESR_EWGF bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EWGF); + break; + case CAN_IT_EPV: + /* Check CAN_ESR_EPVF bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EPVF); + break; + case CAN_IT_BOF: + /* Check CAN_ESR_BOFF bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_BOFF); + break; + case CAN_IT_LEC: + /* Check CAN_ESR_LEC bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_LEC); + break; + case CAN_IT_ERR: + /* Check CAN_MSR_ERRI bit */ + itstatus = CheckITStatus(CANx->MSR, CAN_MSR_ERRI); + break; + default : + /* in case of error, return RESET */ + itstatus = RESET; + break; + } + } + else + { + /* in case the Interrupt is not enabled, return RESET */ + itstatus = RESET; + } + + /* Return the CAN_IT status */ + return itstatus; +} + +/** + * @brief Clears the CANx's interrupt pending bits. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_IT: specifies the interrupt pending bit to clear. + * - CAN_IT_TME + * - CAN_IT_FF0 + * - CAN_IT_FOV0 + * - CAN_IT_FF1 + * - CAN_IT_FOV1 + * - CAN_IT_WKU + * - CAN_IT_SLK + * - CAN_IT_EWG + * - CAN_IT_EPV + * - CAN_IT_BOF + * - CAN_IT_LEC + * - CAN_IT_ERR + * @retval None. + */ +void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_CLEAR_IT(CAN_IT)); + + switch (CAN_IT) + { + case CAN_IT_TME: + /* Clear CAN_TSR_RQCPx (rc_w1)*/ + CANx->TSR = CAN_TSR_RQCP0|CAN_TSR_RQCP1|CAN_TSR_RQCP2; + break; + case CAN_IT_FF0: + /* Clear CAN_RF0R_FULL0 (rc_w1)*/ + CANx->RF0R = CAN_RF0R_FULL0; + break; + case CAN_IT_FOV0: + /* Clear CAN_RF0R_FOVR0 (rc_w1)*/ + CANx->RF0R = CAN_RF0R_FOVR0; + break; + case CAN_IT_FF1: + /* Clear CAN_RF1R_FULL1 (rc_w1)*/ + CANx->RF1R = CAN_RF1R_FULL1; + break; + case CAN_IT_FOV1: + /* Clear CAN_RF1R_FOVR1 (rc_w1)*/ + CANx->RF1R = CAN_RF1R_FOVR1; + break; + case CAN_IT_WKU: + /* Clear CAN_MSR_WKUI (rc_w1)*/ + CANx->MSR = CAN_MSR_WKUI; + break; + case CAN_IT_SLK: + /* Clear CAN_MSR_SLAKI (rc_w1)*/ + CANx->MSR = CAN_MSR_SLAKI; + break; + case CAN_IT_EWG: + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* Note : the corresponding Flag is cleared by hardware depending + of the CAN Bus status*/ + break; + case CAN_IT_EPV: + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* Note : the corresponding Flag is cleared by hardware depending + of the CAN Bus status*/ + break; + case CAN_IT_BOF: + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* Note : the corresponding Flag is cleared by hardware depending + of the CAN Bus status*/ + break; + case CAN_IT_LEC: + /* Clear LEC bits */ + CANx->ESR = RESET; + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + break; + case CAN_IT_ERR: + /*Clear LEC bits */ + CANx->ESR = RESET; + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* Note : BOFF, EPVF and EWGF Flags are cleared by hardware depending + of the CAN Bus status*/ + break; + default : + break; + } +} + +/** + * @brief Checks whether the CAN interrupt has occurred or not. + * @param CAN_Reg: specifies the CAN interrupt register to check. + * @param It_Bit: specifies the interrupt source bit to check. + * @retval The new state of the CAN Interrupt (SET or RESET). + */ +static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit) +{ + ITStatus pendingbitstatus = RESET; + + if ((CAN_Reg & It_Bit) != (uint32_t)RESET) + { + /* CAN_IT is set */ + pendingbitstatus = SET; + } + else + { + /* CAN_IT is reset */ + pendingbitstatus = RESET; + } + return pendingbitstatus; +} + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_cec.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_cec.c new file mode 100644 index 0000000..4dc615f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_cec.c @@ -0,0 +1,433 @@ +/** + ****************************************************************************** + * @file stm32f10x_cec.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the CEC firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_cec.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup CEC + * @brief CEC driver modules + * @{ + */ + +/** @defgroup CEC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + + +/** @defgroup CEC_Private_Defines + * @{ + */ + +/* ------------ CEC registers bit address in the alias region ----------- */ +#define CEC_OFFSET (CEC_BASE - PERIPH_BASE) + +/* --- CFGR Register ---*/ + +/* Alias word address of PE bit */ +#define CFGR_OFFSET (CEC_OFFSET + 0x00) +#define PE_BitNumber 0x00 +#define CFGR_PE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (PE_BitNumber * 4)) + +/* Alias word address of IE bit */ +#define IE_BitNumber 0x01 +#define CFGR_IE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (IE_BitNumber * 4)) + +/* --- CSR Register ---*/ + +/* Alias word address of TSOM bit */ +#define CSR_OFFSET (CEC_OFFSET + 0x10) +#define TSOM_BitNumber 0x00 +#define CSR_TSOM_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TSOM_BitNumber * 4)) + +/* Alias word address of TEOM bit */ +#define TEOM_BitNumber 0x01 +#define CSR_TEOM_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TEOM_BitNumber * 4)) + +#define CFGR_CLEAR_Mask (uint8_t)(0xF3) /* CFGR register Mask */ +#define FLAG_Mask ((uint32_t)0x00FFFFFF) /* CEC FLAG mask */ + +/** + * @} + */ + + +/** @defgroup CEC_Private_Macros + * @{ + */ + +/** + * @} + */ + + +/** @defgroup CEC_Private_Variables + * @{ + */ + +/** + * @} + */ + + +/** @defgroup CEC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + + +/** @defgroup CEC_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the CEC peripheral registers to their default reset + * values. + * @param None + * @retval None + */ +void CEC_DeInit(void) +{ + /* Enable CEC reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CEC, ENABLE); + /* Release CEC from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CEC, DISABLE); +} + + +/** + * @brief Initializes the CEC peripheral according to the specified + * parameters in the CEC_InitStruct. + * @param CEC_InitStruct: pointer to an CEC_InitTypeDef structure that + * contains the configuration information for the specified + * CEC peripheral. + * @retval None + */ +void CEC_Init(CEC_InitTypeDef* CEC_InitStruct) +{ + uint16_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_CEC_BIT_TIMING_ERROR_MODE(CEC_InitStruct->CEC_BitTimingMode)); + assert_param(IS_CEC_BIT_PERIOD_ERROR_MODE(CEC_InitStruct->CEC_BitPeriodMode)); + + /*---------------------------- CEC CFGR Configuration -----------------*/ + /* Get the CEC CFGR value */ + tmpreg = CEC->CFGR; + + /* Clear BTEM and BPEM bits */ + tmpreg &= CFGR_CLEAR_Mask; + + /* Configure CEC: Bit Timing Error and Bit Period Error */ + tmpreg |= (uint16_t)(CEC_InitStruct->CEC_BitTimingMode | CEC_InitStruct->CEC_BitPeriodMode); + + /* Write to CEC CFGR register*/ + CEC->CFGR = tmpreg; + +} + +/** + * @brief Enables or disables the specified CEC peripheral. + * @param NewState: new state of the CEC peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void CEC_Cmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CFGR_PE_BB = (uint32_t)NewState; + + if(NewState == DISABLE) + { + /* Wait until the PE bit is cleared by hardware (Idle Line detected) */ + while((CEC->CFGR & CEC_CFGR_PE) != (uint32_t)RESET) + { + } + } +} + +/** + * @brief Enables or disables the CEC interrupt. + * @param NewState: new state of the CEC interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void CEC_ITConfig(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CFGR_IE_BB = (uint32_t)NewState; +} + +/** + * @brief Defines the Own Address of the CEC device. + * @param CEC_OwnAddress: The CEC own address + * @retval None + */ +void CEC_OwnAddressConfig(uint8_t CEC_OwnAddress) +{ + /* Check the parameters */ + assert_param(IS_CEC_ADDRESS(CEC_OwnAddress)); + + /* Set the CEC own address */ + CEC->OAR = CEC_OwnAddress; +} + +/** + * @brief Sets the CEC prescaler value. + * @param CEC_Prescaler: CEC prescaler new value + * @retval None + */ +void CEC_SetPrescaler(uint16_t CEC_Prescaler) +{ + /* Check the parameters */ + assert_param(IS_CEC_PRESCALER(CEC_Prescaler)); + + /* Set the Prescaler value*/ + CEC->PRES = CEC_Prescaler; +} + +/** + * @brief Transmits single data through the CEC peripheral. + * @param Data: the data to transmit. + * @retval None + */ +void CEC_SendDataByte(uint8_t Data) +{ + /* Transmit Data */ + CEC->TXD = Data ; +} + + +/** + * @brief Returns the most recent received data by the CEC peripheral. + * @param None + * @retval The received data. + */ +uint8_t CEC_ReceiveDataByte(void) +{ + /* Receive Data */ + return (uint8_t)(CEC->RXD); +} + +/** + * @brief Starts a new message. + * @param None + * @retval None + */ +void CEC_StartOfMessage(void) +{ + /* Starts of new message */ + *(__IO uint32_t *) CSR_TSOM_BB = (uint32_t)0x1; +} + +/** + * @brief Transmits message with or without an EOM bit. + * @param NewState: new state of the CEC Tx End Of Message. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void CEC_EndOfMessageCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* The data byte will be transmitted with or without an EOM bit*/ + *(__IO uint32_t *) CSR_TEOM_BB = (uint32_t)NewState; +} + +/** + * @brief Gets the CEC flag status + * @param CEC_FLAG: specifies the CEC flag to check. + * This parameter can be one of the following values: + * @arg CEC_FLAG_BTE: Bit Timing Error + * @arg CEC_FLAG_BPE: Bit Period Error + * @arg CEC_FLAG_RBTFE: Rx Block Transfer Finished Error + * @arg CEC_FLAG_SBE: Start Bit Error + * @arg CEC_FLAG_ACKE: Block Acknowledge Error + * @arg CEC_FLAG_LINE: Line Error + * @arg CEC_FLAG_TBTFE: Tx Block Transfer Finished Error + * @arg CEC_FLAG_TEOM: Tx End Of Message + * @arg CEC_FLAG_TERR: Tx Error + * @arg CEC_FLAG_TBTRF: Tx Byte Transfer Request or Block Transfer Finished + * @arg CEC_FLAG_RSOM: Rx Start Of Message + * @arg CEC_FLAG_REOM: Rx End Of Message + * @arg CEC_FLAG_RERR: Rx Error + * @arg CEC_FLAG_RBTF: Rx Byte/Block Transfer Finished + * @retval The new state of CEC_FLAG (SET or RESET) + */ +FlagStatus CEC_GetFlagStatus(uint32_t CEC_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t cecreg = 0, cecbase = 0; + + /* Check the parameters */ + assert_param(IS_CEC_GET_FLAG(CEC_FLAG)); + + /* Get the CEC peripheral base address */ + cecbase = (uint32_t)(CEC_BASE); + + /* Read flag register index */ + cecreg = CEC_FLAG >> 28; + + /* Get bit[23:0] of the flag */ + CEC_FLAG &= FLAG_Mask; + + if(cecreg != 0) + { + /* Flag in CEC ESR Register */ + CEC_FLAG = (uint32_t)(CEC_FLAG >> 16); + + /* Get the CEC ESR register address */ + cecbase += 0xC; + } + else + { + /* Get the CEC CSR register address */ + cecbase += 0x10; + } + + if(((*(__IO uint32_t *)cecbase) & CEC_FLAG) != (uint32_t)RESET) + { + /* CEC_FLAG is set */ + bitstatus = SET; + } + else + { + /* CEC_FLAG is reset */ + bitstatus = RESET; + } + + /* Return the CEC_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the CEC's pending flags. + * @param CEC_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg CEC_FLAG_TERR: Tx Error + * @arg CEC_FLAG_TBTRF: Tx Byte Transfer Request or Block Transfer Finished + * @arg CEC_FLAG_RSOM: Rx Start Of Message + * @arg CEC_FLAG_REOM: Rx End Of Message + * @arg CEC_FLAG_RERR: Rx Error + * @arg CEC_FLAG_RBTF: Rx Byte/Block Transfer Finished + * @retval None + */ +void CEC_ClearFlag(uint32_t CEC_FLAG) +{ + uint32_t tmp = 0x0; + + /* Check the parameters */ + assert_param(IS_CEC_CLEAR_FLAG(CEC_FLAG)); + + tmp = CEC->CSR & 0x2; + + /* Clear the selected CEC flags */ + CEC->CSR &= (uint32_t)(((~(uint32_t)CEC_FLAG) & 0xFFFFFFFC) | tmp); +} + +/** + * @brief Checks whether the specified CEC interrupt has occurred or not. + * @param CEC_IT: specifies the CEC interrupt source to check. + * This parameter can be one of the following values: + * @arg CEC_IT_TERR: Tx Error + * @arg CEC_IT_TBTF: Tx Block Transfer Finished + * @arg CEC_IT_RERR: Rx Error + * @arg CEC_IT_RBTF: Rx Block Transfer Finished + * @retval The new state of CEC_IT (SET or RESET). + */ +ITStatus CEC_GetITStatus(uint8_t CEC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_CEC_GET_IT(CEC_IT)); + + /* Get the CEC IT enable bit status */ + enablestatus = (CEC->CFGR & (uint8_t)CEC_CFGR_IE) ; + + /* Check the status of the specified CEC interrupt */ + if (((CEC->CSR & CEC_IT) != (uint32_t)RESET) && enablestatus) + { + /* CEC_IT is set */ + bitstatus = SET; + } + else + { + /* CEC_IT is reset */ + bitstatus = RESET; + } + /* Return the CEC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the CEC's interrupt pending bits. + * @param CEC_IT: specifies the CEC interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg CEC_IT_TERR: Tx Error + * @arg CEC_IT_TBTF: Tx Block Transfer Finished + * @arg CEC_IT_RERR: Rx Error + * @arg CEC_IT_RBTF: Rx Block Transfer Finished + * @retval None + */ +void CEC_ClearITPendingBit(uint16_t CEC_IT) +{ + uint32_t tmp = 0x0; + + /* Check the parameters */ + assert_param(IS_CEC_GET_IT(CEC_IT)); + + tmp = CEC->CSR & 0x2; + + /* Clear the selected CEC interrupt pending bits */ + CEC->CSR &= (uint32_t)(((~(uint32_t)CEC_IT) & 0xFFFFFFFC) | tmp); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c new file mode 100644 index 0000000..6501728 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c @@ -0,0 +1,160 @@ +/** + ****************************************************************************** + * @file stm32f10x_crc.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the CRC firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_crc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup CRC + * @brief CRC driver modules + * @{ + */ + +/** @defgroup CRC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Private_Defines + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Private_Functions + * @{ + */ + +/** + * @brief Resets the CRC Data register (DR). + * @param None + * @retval None + */ +void CRC_ResetDR(void) +{ + /* Reset CRC generator */ + CRC->CR = CRC_CR_RESET; +} + +/** + * @brief Computes the 32-bit CRC of a given data word(32-bit). + * @param Data: data word(32-bit) to compute its CRC + * @retval 32-bit CRC + */ +uint32_t CRC_CalcCRC(uint32_t Data) +{ + CRC->DR = Data; + + return (CRC->DR); +} + +/** + * @brief Computes the 32-bit CRC of a given buffer of data word(32-bit). + * @param pBuffer: pointer to the buffer containing the data to be computed + * @param BufferLength: length of the buffer to be computed + * @retval 32-bit CRC + */ +uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength) +{ + uint32_t index = 0; + + for(index = 0; index < BufferLength; index++) + { + CRC->DR = pBuffer[index]; + } + return (CRC->DR); +} + +/** + * @brief Returns the current CRC value. + * @param None + * @retval 32-bit CRC + */ +uint32_t CRC_GetCRC(void) +{ + return (CRC->DR); +} + +/** + * @brief Stores a 8-bit data in the Independent Data(ID) register. + * @param IDValue: 8-bit value to be stored in the ID register + * @retval None + */ +void CRC_SetIDRegister(uint8_t IDValue) +{ + CRC->IDR = IDValue; +} + +/** + * @brief Returns the 8-bit data stored in the Independent Data(ID) register + * @param None + * @retval 8-bit value of the ID register + */ +uint8_t CRC_GetIDRegister(void) +{ + return (CRC->IDR); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c new file mode 100644 index 0000000..1cfc71d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c @@ -0,0 +1,571 @@ +/** + ****************************************************************************** + * @file stm32f10x_dac.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the DAC firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_dac.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup DAC + * @brief DAC driver modules + * @{ + */ + +/** @defgroup DAC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup DAC_Private_Defines + * @{ + */ + +/* CR register Mask */ +#define CR_CLEAR_MASK ((uint32_t)0x00000FFE) + +/* DAC Dual Channels SWTRIG masks */ +#define DUAL_SWTRIG_SET ((uint32_t)0x00000003) +#define DUAL_SWTRIG_RESET ((uint32_t)0xFFFFFFFC) + +/* DHR registers offsets */ +#define DHR12R1_OFFSET ((uint32_t)0x00000008) +#define DHR12R2_OFFSET ((uint32_t)0x00000014) +#define DHR12RD_OFFSET ((uint32_t)0x00000020) + +/* DOR register offset */ +#define DOR_OFFSET ((uint32_t)0x0000002C) +/** + * @} + */ + +/** @defgroup DAC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DAC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup DAC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup DAC_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the DAC peripheral registers to their default reset values. + * @param None + * @retval None + */ +void DAC_DeInit(void) +{ + /* Enable DAC reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, ENABLE); + /* Release DAC from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, DISABLE); +} + +/** + * @brief Initializes the DAC peripheral according to the specified + * parameters in the DAC_InitStruct. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_InitStruct: pointer to a DAC_InitTypeDef structure that + * contains the configuration information for the specified DAC channel. + * @retval None + */ +void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct) +{ + uint32_t tmpreg1 = 0, tmpreg2 = 0; + /* Check the DAC parameters */ + assert_param(IS_DAC_TRIGGER(DAC_InitStruct->DAC_Trigger)); + assert_param(IS_DAC_GENERATE_WAVE(DAC_InitStruct->DAC_WaveGeneration)); + assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude)); + assert_param(IS_DAC_OUTPUT_BUFFER_STATE(DAC_InitStruct->DAC_OutputBuffer)); +/*---------------------------- DAC CR Configuration --------------------------*/ + /* Get the DAC CR value */ + tmpreg1 = DAC->CR; + /* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */ + tmpreg1 &= ~(CR_CLEAR_MASK << DAC_Channel); + /* Configure for the selected DAC channel: buffer output, trigger, wave generation, + mask/amplitude for wave generation */ + /* Set TSELx and TENx bits according to DAC_Trigger value */ + /* Set WAVEx bits according to DAC_WaveGeneration value */ + /* Set MAMPx bits according to DAC_LFSRUnmask_TriangleAmplitude value */ + /* Set BOFFx bit according to DAC_OutputBuffer value */ + tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration | + DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | DAC_InitStruct->DAC_OutputBuffer); + /* Calculate CR register value depending on DAC_Channel */ + tmpreg1 |= tmpreg2 << DAC_Channel; + /* Write to DAC CR */ + DAC->CR = tmpreg1; +} + +/** + * @brief Fills each DAC_InitStruct member with its default value. + * @param DAC_InitStruct : pointer to a DAC_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct) +{ +/*--------------- Reset DAC init structure parameters values -----------------*/ + /* Initialize the DAC_Trigger member */ + DAC_InitStruct->DAC_Trigger = DAC_Trigger_None; + /* Initialize the DAC_WaveGeneration member */ + DAC_InitStruct->DAC_WaveGeneration = DAC_WaveGeneration_None; + /* Initialize the DAC_LFSRUnmask_TriangleAmplitude member */ + DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0; + /* Initialize the DAC_OutputBuffer member */ + DAC_InitStruct->DAC_OutputBuffer = DAC_OutputBuffer_Enable; +} + +/** + * @brief Enables or disables the specified DAC channel. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param NewState: new state of the DAC channel. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected DAC channel */ + DAC->CR |= (DAC_CR_EN1 << DAC_Channel); + } + else + { + /* Disable the selected DAC channel */ + DAC->CR &= ~(DAC_CR_EN1 << DAC_Channel); + } +} +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/** + * @brief Enables or disables the specified DAC interrupts. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_IT: specifies the DAC interrupt sources to be enabled or disabled. + * This parameter can be the following values: + * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask + * @param NewState: new state of the specified DAC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_ITConfig(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_DAC_IT(DAC_IT)); + + if (NewState != DISABLE) + { + /* Enable the selected DAC interrupts */ + DAC->CR |= (DAC_IT << DAC_Channel); + } + else + { + /* Disable the selected DAC interrupts */ + DAC->CR &= (~(uint32_t)(DAC_IT << DAC_Channel)); + } +} +#endif + +/** + * @brief Enables or disables the specified DAC channel DMA request. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param NewState: new state of the selected DAC channel DMA request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected DAC channel DMA request */ + DAC->CR |= (DAC_CR_DMAEN1 << DAC_Channel); + } + else + { + /* Disable the selected DAC channel DMA request */ + DAC->CR &= ~(DAC_CR_DMAEN1 << DAC_Channel); + } +} + +/** + * @brief Enables or disables the selected DAC channel software trigger. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param NewState: new state of the selected DAC channel software trigger. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable software trigger for the selected DAC channel */ + DAC->SWTRIGR |= (uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4); + } + else + { + /* Disable software trigger for the selected DAC channel */ + DAC->SWTRIGR &= ~((uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4)); + } +} + +/** + * @brief Enables or disables simultaneously the two DAC channels software + * triggers. + * @param NewState: new state of the DAC channels software triggers. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_DualSoftwareTriggerCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable software trigger for both DAC channels */ + DAC->SWTRIGR |= DUAL_SWTRIG_SET ; + } + else + { + /* Disable software trigger for both DAC channels */ + DAC->SWTRIGR &= DUAL_SWTRIG_RESET; + } +} + +/** + * @brief Enables or disables the selected DAC channel wave generation. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_Wave: Specifies the wave type to enable or disable. + * This parameter can be one of the following values: + * @arg DAC_Wave_Noise: noise wave generation + * @arg DAC_Wave_Triangle: triangle wave generation + * @param NewState: new state of the selected DAC channel wave generation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_WAVE(DAC_Wave)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected wave generation for the selected DAC channel */ + DAC->CR |= DAC_Wave << DAC_Channel; + } + else + { + /* Disable the selected wave generation for the selected DAC channel */ + DAC->CR &= ~(DAC_Wave << DAC_Channel); + } +} + +/** + * @brief Set the specified data holding register value for DAC channel1. + * @param DAC_Align: Specifies the data alignment for DAC channel1. + * This parameter can be one of the following values: + * @arg DAC_Align_8b_R: 8bit right data alignment selected + * @arg DAC_Align_12b_L: 12bit left data alignment selected + * @arg DAC_Align_12b_R: 12bit right data alignment selected + * @param Data : Data to be loaded in the selected data holding register. + * @retval None + */ +void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_ALIGN(DAC_Align)); + assert_param(IS_DAC_DATA(Data)); + + tmp = (uint32_t)DAC_BASE; + tmp += DHR12R1_OFFSET + DAC_Align; + + /* Set the DAC channel1 selected data holding register */ + *(__IO uint32_t *) tmp = Data; +} + +/** + * @brief Set the specified data holding register value for DAC channel2. + * @param DAC_Align: Specifies the data alignment for DAC channel2. + * This parameter can be one of the following values: + * @arg DAC_Align_8b_R: 8bit right data alignment selected + * @arg DAC_Align_12b_L: 12bit left data alignment selected + * @arg DAC_Align_12b_R: 12bit right data alignment selected + * @param Data : Data to be loaded in the selected data holding register. + * @retval None + */ +void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_ALIGN(DAC_Align)); + assert_param(IS_DAC_DATA(Data)); + + tmp = (uint32_t)DAC_BASE; + tmp += DHR12R2_OFFSET + DAC_Align; + + /* Set the DAC channel2 selected data holding register */ + *(__IO uint32_t *)tmp = Data; +} + +/** + * @brief Set the specified data holding register value for dual channel + * DAC. + * @param DAC_Align: Specifies the data alignment for dual channel DAC. + * This parameter can be one of the following values: + * @arg DAC_Align_8b_R: 8bit right data alignment selected + * @arg DAC_Align_12b_L: 12bit left data alignment selected + * @arg DAC_Align_12b_R: 12bit right data alignment selected + * @param Data2: Data for DAC Channel2 to be loaded in the selected data + * holding register. + * @param Data1: Data for DAC Channel1 to be loaded in the selected data + * holding register. + * @retval None + */ +void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1) +{ + uint32_t data = 0, tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_ALIGN(DAC_Align)); + assert_param(IS_DAC_DATA(Data1)); + assert_param(IS_DAC_DATA(Data2)); + + /* Calculate and set dual DAC data holding register value */ + if (DAC_Align == DAC_Align_8b_R) + { + data = ((uint32_t)Data2 << 8) | Data1; + } + else + { + data = ((uint32_t)Data2 << 16) | Data1; + } + + tmp = (uint32_t)DAC_BASE; + tmp += DHR12RD_OFFSET + DAC_Align; + + /* Set the dual DAC selected data holding register */ + *(__IO uint32_t *)tmp = data; +} + +/** + * @brief Returns the last data output value of the selected DAC channel. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @retval The selected DAC channel data output value. + */ +uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + + tmp = (uint32_t) DAC_BASE ; + tmp += DOR_OFFSET + ((uint32_t)DAC_Channel >> 2); + + /* Returns the DAC channel data output register value */ + return (uint16_t) (*(__IO uint32_t*) tmp); +} + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/** + * @brief Checks whether the specified DAC flag is set or not. + * @param DAC_Channel: thee selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_FLAG: specifies the flag to check. + * This parameter can be only of the following value: + * @arg DAC_FLAG_DMAUDR: DMA underrun flag + * @retval The new state of DAC_FLAG (SET or RESET). + */ +FlagStatus DAC_GetFlagStatus(uint32_t DAC_Channel, uint32_t DAC_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_FLAG(DAC_FLAG)); + + /* Check the status of the specified DAC flag */ + if ((DAC->SR & (DAC_FLAG << DAC_Channel)) != (uint8_t)RESET) + { + /* DAC_FLAG is set */ + bitstatus = SET; + } + else + { + /* DAC_FLAG is reset */ + bitstatus = RESET; + } + /* Return the DAC_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the DAC channelx's pending flags. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_FLAG: specifies the flag to clear. + * This parameter can be of the following value: + * @arg DAC_FLAG_DMAUDR: DMA underrun flag + * @retval None + */ +void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_FLAG(DAC_FLAG)); + + /* Clear the selected DAC flags */ + DAC->SR = (DAC_FLAG << DAC_Channel); +} + +/** + * @brief Checks whether the specified DAC interrupt has occurred or not. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_IT: specifies the DAC interrupt source to check. + * This parameter can be the following values: + * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask + * @retval The new state of DAC_IT (SET or RESET). + */ +ITStatus DAC_GetITStatus(uint32_t DAC_Channel, uint32_t DAC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_IT(DAC_IT)); + + /* Get the DAC_IT enable bit status */ + enablestatus = (DAC->CR & (DAC_IT << DAC_Channel)) ; + + /* Check the status of the specified DAC interrupt */ + if (((DAC->SR & (DAC_IT << DAC_Channel)) != (uint32_t)RESET) && enablestatus) + { + /* DAC_IT is set */ + bitstatus = SET; + } + else + { + /* DAC_IT is reset */ + bitstatus = RESET; + } + /* Return the DAC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the DAC channelx's interrupt pending bits. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_IT: specifies the DAC interrupt pending bit to clear. + * This parameter can be the following values: + * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask + * @retval None + */ +void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_IT(DAC_IT)); + + /* Clear the selected DAC interrupt pending bits */ + DAC->SR = (DAC_IT << DAC_Channel); +} +#endif + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c new file mode 100644 index 0000000..96a8fde --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c @@ -0,0 +1,162 @@ +/** + ****************************************************************************** + * @file stm32f10x_dbgmcu.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the DBGMCU firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_dbgmcu.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup DBGMCU + * @brief DBGMCU driver modules + * @{ + */ + +/** @defgroup DBGMCU_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Private_Defines + * @{ + */ + +#define IDCODE_DEVID_MASK ((uint32_t)0x00000FFF) +/** + * @} + */ + +/** @defgroup DBGMCU_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Private_Functions + * @{ + */ + +/** + * @brief Returns the device revision identifier. + * @param None + * @retval Device revision identifier + */ +uint32_t DBGMCU_GetREVID(void) +{ + return(DBGMCU->IDCODE >> 16); +} + +/** + * @brief Returns the device identifier. + * @param None + * @retval Device identifier + */ +uint32_t DBGMCU_GetDEVID(void) +{ + return(DBGMCU->IDCODE & IDCODE_DEVID_MASK); +} + +/** + * @brief Configures the specified peripheral and low power mode behavior + * when the MCU under Debug mode. + * @param DBGMCU_Periph: specifies the peripheral and low power mode. + * This parameter can be any combination of the following values: + * @arg DBGMCU_SLEEP: Keep debugger connection during SLEEP mode + * @arg DBGMCU_STOP: Keep debugger connection during STOP mode + * @arg DBGMCU_STANDBY: Keep debugger connection during STANDBY mode + * @arg DBGMCU_IWDG_STOP: Debug IWDG stopped when Core is halted + * @arg DBGMCU_WWDG_STOP: Debug WWDG stopped when Core is halted + * @arg DBGMCU_TIM1_STOP: TIM1 counter stopped when Core is halted + * @arg DBGMCU_TIM2_STOP: TIM2 counter stopped when Core is halted + * @arg DBGMCU_TIM3_STOP: TIM3 counter stopped when Core is halted + * @arg DBGMCU_TIM4_STOP: TIM4 counter stopped when Core is halted + * @arg DBGMCU_CAN1_STOP: Debug CAN2 stopped when Core is halted + * @arg DBGMCU_I2C1_SMBUS_TIMEOUT: I2C1 SMBUS timeout mode stopped when Core is halted + * @arg DBGMCU_I2C2_SMBUS_TIMEOUT: I2C2 SMBUS timeout mode stopped when Core is halted + * @arg DBGMCU_TIM5_STOP: TIM5 counter stopped when Core is halted + * @arg DBGMCU_TIM6_STOP: TIM6 counter stopped when Core is halted + * @arg DBGMCU_TIM7_STOP: TIM7 counter stopped when Core is halted + * @arg DBGMCU_TIM8_STOP: TIM8 counter stopped when Core is halted + * @arg DBGMCU_CAN2_STOP: Debug CAN2 stopped when Core is halted + * @arg DBGMCU_TIM15_STOP: TIM15 counter stopped when Core is halted + * @arg DBGMCU_TIM16_STOP: TIM16 counter stopped when Core is halted + * @arg DBGMCU_TIM17_STOP: TIM17 counter stopped when Core is halted + * @arg DBGMCU_TIM9_STOP: TIM9 counter stopped when Core is halted + * @arg DBGMCU_TIM10_STOP: TIM10 counter stopped when Core is halted + * @arg DBGMCU_TIM11_STOP: TIM11 counter stopped when Core is halted + * @arg DBGMCU_TIM12_STOP: TIM12 counter stopped when Core is halted + * @arg DBGMCU_TIM13_STOP: TIM13 counter stopped when Core is halted + * @arg DBGMCU_TIM14_STOP: TIM14 counter stopped when Core is halted + * @param NewState: new state of the specified peripheral in Debug mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DBGMCU_PERIPH(DBGMCU_Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + DBGMCU->CR |= DBGMCU_Periph; + } + else + { + DBGMCU->CR &= ~DBGMCU_Periph; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c new file mode 100644 index 0000000..bf072df --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c @@ -0,0 +1,714 @@ +/** + ****************************************************************************** + * @file stm32f10x_dma.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the DMA firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_dma.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup DMA + * @brief DMA driver modules + * @{ + */ + +/** @defgroup DMA_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + +/** @defgroup DMA_Private_Defines + * @{ + */ + + +/* DMA1 Channelx interrupt pending bit masks */ +#define DMA1_Channel1_IT_Mask ((uint32_t)(DMA_ISR_GIF1 | DMA_ISR_TCIF1 | DMA_ISR_HTIF1 | DMA_ISR_TEIF1)) +#define DMA1_Channel2_IT_Mask ((uint32_t)(DMA_ISR_GIF2 | DMA_ISR_TCIF2 | DMA_ISR_HTIF2 | DMA_ISR_TEIF2)) +#define DMA1_Channel3_IT_Mask ((uint32_t)(DMA_ISR_GIF3 | DMA_ISR_TCIF3 | DMA_ISR_HTIF3 | DMA_ISR_TEIF3)) +#define DMA1_Channel4_IT_Mask ((uint32_t)(DMA_ISR_GIF4 | DMA_ISR_TCIF4 | DMA_ISR_HTIF4 | DMA_ISR_TEIF4)) +#define DMA1_Channel5_IT_Mask ((uint32_t)(DMA_ISR_GIF5 | DMA_ISR_TCIF5 | DMA_ISR_HTIF5 | DMA_ISR_TEIF5)) +#define DMA1_Channel6_IT_Mask ((uint32_t)(DMA_ISR_GIF6 | DMA_ISR_TCIF6 | DMA_ISR_HTIF6 | DMA_ISR_TEIF6)) +#define DMA1_Channel7_IT_Mask ((uint32_t)(DMA_ISR_GIF7 | DMA_ISR_TCIF7 | DMA_ISR_HTIF7 | DMA_ISR_TEIF7)) + +/* DMA2 Channelx interrupt pending bit masks */ +#define DMA2_Channel1_IT_Mask ((uint32_t)(DMA_ISR_GIF1 | DMA_ISR_TCIF1 | DMA_ISR_HTIF1 | DMA_ISR_TEIF1)) +#define DMA2_Channel2_IT_Mask ((uint32_t)(DMA_ISR_GIF2 | DMA_ISR_TCIF2 | DMA_ISR_HTIF2 | DMA_ISR_TEIF2)) +#define DMA2_Channel3_IT_Mask ((uint32_t)(DMA_ISR_GIF3 | DMA_ISR_TCIF3 | DMA_ISR_HTIF3 | DMA_ISR_TEIF3)) +#define DMA2_Channel4_IT_Mask ((uint32_t)(DMA_ISR_GIF4 | DMA_ISR_TCIF4 | DMA_ISR_HTIF4 | DMA_ISR_TEIF4)) +#define DMA2_Channel5_IT_Mask ((uint32_t)(DMA_ISR_GIF5 | DMA_ISR_TCIF5 | DMA_ISR_HTIF5 | DMA_ISR_TEIF5)) + +/* DMA2 FLAG mask */ +#define FLAG_Mask ((uint32_t)0x10000000) + +/* DMA registers Masks */ +#define CCR_CLEAR_Mask ((uint32_t)0xFFFF800F) + +/** + * @} + */ + +/** @defgroup DMA_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DMA_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup DMA_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup DMA_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the DMAy Channelx registers to their default reset + * values. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @retval None + */ +void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + + /* Disable the selected DMAy Channelx */ + DMAy_Channelx->CCR &= (uint16_t)(~DMA_CCR1_EN); + + /* Reset DMAy Channelx control register */ + DMAy_Channelx->CCR = 0; + + /* Reset DMAy Channelx remaining bytes register */ + DMAy_Channelx->CNDTR = 0; + + /* Reset DMAy Channelx peripheral address register */ + DMAy_Channelx->CPAR = 0; + + /* Reset DMAy Channelx memory address register */ + DMAy_Channelx->CMAR = 0; + + if (DMAy_Channelx == DMA1_Channel1) + { + /* Reset interrupt pending bits for DMA1 Channel1 */ + DMA1->IFCR |= DMA1_Channel1_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel2) + { + /* Reset interrupt pending bits for DMA1 Channel2 */ + DMA1->IFCR |= DMA1_Channel2_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel3) + { + /* Reset interrupt pending bits for DMA1 Channel3 */ + DMA1->IFCR |= DMA1_Channel3_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel4) + { + /* Reset interrupt pending bits for DMA1 Channel4 */ + DMA1->IFCR |= DMA1_Channel4_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel5) + { + /* Reset interrupt pending bits for DMA1 Channel5 */ + DMA1->IFCR |= DMA1_Channel5_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel6) + { + /* Reset interrupt pending bits for DMA1 Channel6 */ + DMA1->IFCR |= DMA1_Channel6_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel7) + { + /* Reset interrupt pending bits for DMA1 Channel7 */ + DMA1->IFCR |= DMA1_Channel7_IT_Mask; + } + else if (DMAy_Channelx == DMA2_Channel1) + { + /* Reset interrupt pending bits for DMA2 Channel1 */ + DMA2->IFCR |= DMA2_Channel1_IT_Mask; + } + else if (DMAy_Channelx == DMA2_Channel2) + { + /* Reset interrupt pending bits for DMA2 Channel2 */ + DMA2->IFCR |= DMA2_Channel2_IT_Mask; + } + else if (DMAy_Channelx == DMA2_Channel3) + { + /* Reset interrupt pending bits for DMA2 Channel3 */ + DMA2->IFCR |= DMA2_Channel3_IT_Mask; + } + else if (DMAy_Channelx == DMA2_Channel4) + { + /* Reset interrupt pending bits for DMA2 Channel4 */ + DMA2->IFCR |= DMA2_Channel4_IT_Mask; + } + else + { + if (DMAy_Channelx == DMA2_Channel5) + { + /* Reset interrupt pending bits for DMA2 Channel5 */ + DMA2->IFCR |= DMA2_Channel5_IT_Mask; + } + } +} + +/** + * @brief Initializes the DMAy Channelx according to the specified + * parameters in the DMA_InitStruct. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param DMA_InitStruct: pointer to a DMA_InitTypeDef structure that + * contains the configuration information for the specified DMA Channel. + * @retval None + */ +void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + assert_param(IS_DMA_DIR(DMA_InitStruct->DMA_DIR)); + assert_param(IS_DMA_BUFFER_SIZE(DMA_InitStruct->DMA_BufferSize)); + assert_param(IS_DMA_PERIPHERAL_INC_STATE(DMA_InitStruct->DMA_PeripheralInc)); + assert_param(IS_DMA_MEMORY_INC_STATE(DMA_InitStruct->DMA_MemoryInc)); + assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(DMA_InitStruct->DMA_PeripheralDataSize)); + assert_param(IS_DMA_MEMORY_DATA_SIZE(DMA_InitStruct->DMA_MemoryDataSize)); + assert_param(IS_DMA_MODE(DMA_InitStruct->DMA_Mode)); + assert_param(IS_DMA_PRIORITY(DMA_InitStruct->DMA_Priority)); + assert_param(IS_DMA_M2M_STATE(DMA_InitStruct->DMA_M2M)); + +/*--------------------------- DMAy Channelx CCR Configuration -----------------*/ + /* Get the DMAy_Channelx CCR value */ + tmpreg = DMAy_Channelx->CCR; + /* Clear MEM2MEM, PL, MSIZE, PSIZE, MINC, PINC, CIRC and DIR bits */ + tmpreg &= CCR_CLEAR_Mask; + /* Configure DMAy Channelx: data transfer, data size, priority level and mode */ + /* Set DIR bit according to DMA_DIR value */ + /* Set CIRC bit according to DMA_Mode value */ + /* Set PINC bit according to DMA_PeripheralInc value */ + /* Set MINC bit according to DMA_MemoryInc value */ + /* Set PSIZE bits according to DMA_PeripheralDataSize value */ + /* Set MSIZE bits according to DMA_MemoryDataSize value */ + /* Set PL bits according to DMA_Priority value */ + /* Set the MEM2MEM bit according to DMA_M2M value */ + tmpreg |= DMA_InitStruct->DMA_DIR | DMA_InitStruct->DMA_Mode | + DMA_InitStruct->DMA_PeripheralInc | DMA_InitStruct->DMA_MemoryInc | + DMA_InitStruct->DMA_PeripheralDataSize | DMA_InitStruct->DMA_MemoryDataSize | + DMA_InitStruct->DMA_Priority | DMA_InitStruct->DMA_M2M; + + /* Write to DMAy Channelx CCR */ + DMAy_Channelx->CCR = tmpreg; + +/*--------------------------- DMAy Channelx CNDTR Configuration ---------------*/ + /* Write to DMAy Channelx CNDTR */ + DMAy_Channelx->CNDTR = DMA_InitStruct->DMA_BufferSize; + +/*--------------------------- DMAy Channelx CPAR Configuration ----------------*/ + /* Write to DMAy Channelx CPAR */ + DMAy_Channelx->CPAR = DMA_InitStruct->DMA_PeripheralBaseAddr; + +/*--------------------------- DMAy Channelx CMAR Configuration ----------------*/ + /* Write to DMAy Channelx CMAR */ + DMAy_Channelx->CMAR = DMA_InitStruct->DMA_MemoryBaseAddr; +} + +/** + * @brief Fills each DMA_InitStruct member with its default value. + * @param DMA_InitStruct : pointer to a DMA_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct) +{ +/*-------------- Reset DMA init structure parameters values ------------------*/ + /* Initialize the DMA_PeripheralBaseAddr member */ + DMA_InitStruct->DMA_PeripheralBaseAddr = 0; + /* Initialize the DMA_MemoryBaseAddr member */ + DMA_InitStruct->DMA_MemoryBaseAddr = 0; + /* Initialize the DMA_DIR member */ + DMA_InitStruct->DMA_DIR = DMA_DIR_PeripheralSRC; + /* Initialize the DMA_BufferSize member */ + DMA_InitStruct->DMA_BufferSize = 0; + /* Initialize the DMA_PeripheralInc member */ + DMA_InitStruct->DMA_PeripheralInc = DMA_PeripheralInc_Disable; + /* Initialize the DMA_MemoryInc member */ + DMA_InitStruct->DMA_MemoryInc = DMA_MemoryInc_Disable; + /* Initialize the DMA_PeripheralDataSize member */ + DMA_InitStruct->DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; + /* Initialize the DMA_MemoryDataSize member */ + DMA_InitStruct->DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; + /* Initialize the DMA_Mode member */ + DMA_InitStruct->DMA_Mode = DMA_Mode_Normal; + /* Initialize the DMA_Priority member */ + DMA_InitStruct->DMA_Priority = DMA_Priority_Low; + /* Initialize the DMA_M2M member */ + DMA_InitStruct->DMA_M2M = DMA_M2M_Disable; +} + +/** + * @brief Enables or disables the specified DMAy Channelx. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param NewState: new state of the DMAy Channelx. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected DMAy Channelx */ + DMAy_Channelx->CCR |= DMA_CCR1_EN; + } + else + { + /* Disable the selected DMAy Channelx */ + DMAy_Channelx->CCR &= (uint16_t)(~DMA_CCR1_EN); + } +} + +/** + * @brief Enables or disables the specified DMAy Channelx interrupts. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param DMA_IT: specifies the DMA interrupts sources to be enabled + * or disabled. + * This parameter can be any combination of the following values: + * @arg DMA_IT_TC: Transfer complete interrupt mask + * @arg DMA_IT_HT: Half transfer interrupt mask + * @arg DMA_IT_TE: Transfer error interrupt mask + * @param NewState: new state of the specified DMA interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + assert_param(IS_DMA_CONFIG_IT(DMA_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected DMA interrupts */ + DMAy_Channelx->CCR |= DMA_IT; + } + else + { + /* Disable the selected DMA interrupts */ + DMAy_Channelx->CCR &= ~DMA_IT; + } +} + +/** + * @brief Sets the number of data units in the current DMAy Channelx transfer. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param DataNumber: The number of data units in the current DMAy Channelx + * transfer. + * @note This function can only be used when the DMAy_Channelx is disabled. + * @retval None. + */ +void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + +/*--------------------------- DMAy Channelx CNDTR Configuration ---------------*/ + /* Write to DMAy Channelx CNDTR */ + DMAy_Channelx->CNDTR = DataNumber; +} + +/** + * @brief Returns the number of remaining data units in the current + * DMAy Channelx transfer. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @retval The number of remaining data units in the current DMAy Channelx + * transfer. + */ +uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + /* Return the number of remaining data units for DMAy Channelx */ + return ((uint16_t)(DMAy_Channelx->CNDTR)); +} + +/** + * @brief Checks whether the specified DMAy Channelx flag is set or not. + * @param DMAy_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag. + * @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag. + * @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag. + * @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag. + * @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag. + * @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag. + * @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag. + * @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag. + * @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag. + * @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag. + * @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag. + * @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag. + * @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag. + * @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag. + * @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag. + * @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag. + * @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag. + * @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag. + * @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag. + * @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag. + * @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag. + * @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag. + * @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag. + * @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag. + * @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag. + * @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag. + * @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag. + * @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag. + * @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag. + * @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag. + * @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag. + * @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag. + * @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag. + * @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag. + * @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag. + * @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag. + * @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag. + * @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag. + * @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag. + * @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag. + * @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag. + * @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag. + * @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag. + * @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag. + * @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag. + * @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag. + * @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag. + * @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag. + * @retval The new state of DMAy_FLAG (SET or RESET). + */ +FlagStatus DMA_GetFlagStatus(uint32_t DMAy_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_DMA_GET_FLAG(DMAy_FLAG)); + + /* Calculate the used DMAy */ + if ((DMAy_FLAG & FLAG_Mask) != (uint32_t)RESET) + { + /* Get DMA2 ISR register value */ + tmpreg = DMA2->ISR ; + } + else + { + /* Get DMA1 ISR register value */ + tmpreg = DMA1->ISR ; + } + + /* Check the status of the specified DMAy flag */ + if ((tmpreg & DMAy_FLAG) != (uint32_t)RESET) + { + /* DMAy_FLAG is set */ + bitstatus = SET; + } + else + { + /* DMAy_FLAG is reset */ + bitstatus = RESET; + } + + /* Return the DMAy_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the DMAy Channelx's pending flags. + * @param DMAy_FLAG: specifies the flag to clear. + * This parameter can be any combination (for the same DMA) of the following values: + * @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag. + * @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag. + * @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag. + * @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag. + * @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag. + * @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag. + * @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag. + * @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag. + * @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag. + * @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag. + * @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag. + * @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag. + * @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag. + * @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag. + * @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag. + * @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag. + * @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag. + * @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag. + * @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag. + * @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag. + * @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag. + * @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag. + * @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag. + * @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag. + * @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag. + * @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag. + * @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag. + * @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag. + * @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag. + * @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag. + * @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag. + * @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag. + * @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag. + * @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag. + * @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag. + * @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag. + * @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag. + * @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag. + * @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag. + * @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag. + * @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag. + * @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag. + * @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag. + * @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag. + * @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag. + * @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag. + * @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag. + * @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag. + * @retval None + */ +void DMA_ClearFlag(uint32_t DMAy_FLAG) +{ + /* Check the parameters */ + assert_param(IS_DMA_CLEAR_FLAG(DMAy_FLAG)); + + /* Calculate the used DMAy */ + if ((DMAy_FLAG & FLAG_Mask) != (uint32_t)RESET) + { + /* Clear the selected DMAy flags */ + DMA2->IFCR = DMAy_FLAG; + } + else + { + /* Clear the selected DMAy flags */ + DMA1->IFCR = DMAy_FLAG; + } +} + +/** + * @brief Checks whether the specified DMAy Channelx interrupt has occurred or not. + * @param DMAy_IT: specifies the DMAy interrupt source to check. + * This parameter can be one of the following values: + * @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt. + * @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt. + * @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt. + * @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt. + * @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt. + * @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt. + * @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt. + * @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt. + * @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt. + * @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt. + * @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt. + * @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt. + * @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt. + * @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt. + * @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt. + * @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt. + * @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt. + * @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt. + * @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt. + * @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt. + * @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt. + * @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt. + * @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt. + * @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt. + * @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt. + * @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt. + * @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt. + * @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt. + * @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt. + * @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt. + * @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt. + * @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt. + * @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt. + * @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt. + * @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt. + * @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt. + * @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt. + * @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt. + * @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt. + * @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt. + * @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt. + * @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt. + * @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt. + * @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt. + * @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt. + * @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt. + * @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt. + * @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt. + * @retval The new state of DMAy_IT (SET or RESET). + */ +ITStatus DMA_GetITStatus(uint32_t DMAy_IT) +{ + ITStatus bitstatus = RESET; + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_DMA_GET_IT(DMAy_IT)); + + /* Calculate the used DMA */ + if ((DMAy_IT & FLAG_Mask) != (uint32_t)RESET) + { + /* Get DMA2 ISR register value */ + tmpreg = DMA2->ISR; + } + else + { + /* Get DMA1 ISR register value */ + tmpreg = DMA1->ISR; + } + + /* Check the status of the specified DMAy interrupt */ + if ((tmpreg & DMAy_IT) != (uint32_t)RESET) + { + /* DMAy_IT is set */ + bitstatus = SET; + } + else + { + /* DMAy_IT is reset */ + bitstatus = RESET; + } + /* Return the DMA_IT status */ + return bitstatus; +} + +/** + * @brief Clears the DMAy Channelx's interrupt pending bits. + * @param DMAy_IT: specifies the DMAy interrupt pending bit to clear. + * This parameter can be any combination (for the same DMA) of the following values: + * @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt. + * @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt. + * @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt. + * @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt. + * @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt. + * @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt. + * @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt. + * @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt. + * @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt. + * @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt. + * @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt. + * @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt. + * @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt. + * @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt. + * @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt. + * @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt. + * @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt. + * @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt. + * @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt. + * @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt. + * @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt. + * @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt. + * @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt. + * @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt. + * @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt. + * @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt. + * @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt. + * @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt. + * @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt. + * @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt. + * @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt. + * @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt. + * @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt. + * @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt. + * @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt. + * @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt. + * @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt. + * @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt. + * @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt. + * @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt. + * @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt. + * @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt. + * @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt. + * @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt. + * @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt. + * @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt. + * @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt. + * @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt. + * @retval None + */ +void DMA_ClearITPendingBit(uint32_t DMAy_IT) +{ + /* Check the parameters */ + assert_param(IS_DMA_CLEAR_IT(DMAy_IT)); + + /* Calculate the used DMAy */ + if ((DMAy_IT & FLAG_Mask) != (uint32_t)RESET) + { + /* Clear the selected DMAy interrupt pending bits */ + DMA2->IFCR = DMAy_IT; + } + else + { + /* Clear the selected DMAy interrupt pending bits */ + DMA1->IFCR = DMAy_IT; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c new file mode 100644 index 0000000..b6290d5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c @@ -0,0 +1,269 @@ +/** + ****************************************************************************** + * @file stm32f10x_exti.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the EXTI firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_exti.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup EXTI + * @brief EXTI driver modules + * @{ + */ + +/** @defgroup EXTI_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup EXTI_Private_Defines + * @{ + */ + +#define EXTI_LINENONE ((uint32_t)0x00000) /* No interrupt selected */ + +/** + * @} + */ + +/** @defgroup EXTI_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup EXTI_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup EXTI_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup EXTI_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the EXTI peripheral registers to their default reset values. + * @param None + * @retval None + */ +void EXTI_DeInit(void) +{ + EXTI->IMR = 0x00000000; + EXTI->EMR = 0x00000000; + EXTI->RTSR = 0x00000000; + EXTI->FTSR = 0x00000000; + EXTI->PR = 0x000FFFFF; +} + +/** + * @brief Initializes the EXTI peripheral according to the specified + * parameters in the EXTI_InitStruct. + * @param EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure + * that contains the configuration information for the EXTI peripheral. + * @retval None + */ +void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct) +{ + uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_EXTI_MODE(EXTI_InitStruct->EXTI_Mode)); + assert_param(IS_EXTI_TRIGGER(EXTI_InitStruct->EXTI_Trigger)); + assert_param(IS_EXTI_LINE(EXTI_InitStruct->EXTI_Line)); + assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->EXTI_LineCmd)); + + tmp = (uint32_t)EXTI_BASE; + + if (EXTI_InitStruct->EXTI_LineCmd != DISABLE) + { + /* Clear EXTI line configuration */ + EXTI->IMR &= ~EXTI_InitStruct->EXTI_Line; + EXTI->EMR &= ~EXTI_InitStruct->EXTI_Line; + + tmp += EXTI_InitStruct->EXTI_Mode; + + *(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line; + + /* Clear Rising Falling edge configuration */ + EXTI->RTSR &= ~EXTI_InitStruct->EXTI_Line; + EXTI->FTSR &= ~EXTI_InitStruct->EXTI_Line; + + /* Select the trigger for the selected external interrupts */ + if (EXTI_InitStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling) + { + /* Rising Falling edge */ + EXTI->RTSR |= EXTI_InitStruct->EXTI_Line; + EXTI->FTSR |= EXTI_InitStruct->EXTI_Line; + } + else + { + tmp = (uint32_t)EXTI_BASE; + tmp += EXTI_InitStruct->EXTI_Trigger; + + *(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line; + } + } + else + { + tmp += EXTI_InitStruct->EXTI_Mode; + + /* Disable the selected external lines */ + *(__IO uint32_t *) tmp &= ~EXTI_InitStruct->EXTI_Line; + } +} + +/** + * @brief Fills each EXTI_InitStruct member with its reset value. + * @param EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct) +{ + EXTI_InitStruct->EXTI_Line = EXTI_LINENONE; + EXTI_InitStruct->EXTI_Mode = EXTI_Mode_Interrupt; + EXTI_InitStruct->EXTI_Trigger = EXTI_Trigger_Falling; + EXTI_InitStruct->EXTI_LineCmd = DISABLE; +} + +/** + * @brief Generates a Software interrupt. + * @param EXTI_Line: specifies the EXTI lines to be enabled or disabled. + * This parameter can be any combination of EXTI_Linex where x can be (0..19). + * @retval None + */ +void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE(EXTI_Line)); + + EXTI->SWIER |= EXTI_Line; +} + +/** + * @brief Checks whether the specified EXTI line flag is set or not. + * @param EXTI_Line: specifies the EXTI line flag to check. + * This parameter can be: + * @arg EXTI_Linex: External interrupt line x where x(0..19) + * @retval The new state of EXTI_Line (SET or RESET). + */ +FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_GET_EXTI_LINE(EXTI_Line)); + + if ((EXTI->PR & EXTI_Line) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the EXTI's line pending flags. + * @param EXTI_Line: specifies the EXTI lines flags to clear. + * This parameter can be any combination of EXTI_Linex where x can be (0..19). + * @retval None + */ +void EXTI_ClearFlag(uint32_t EXTI_Line) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE(EXTI_Line)); + + EXTI->PR = EXTI_Line; +} + +/** + * @brief Checks whether the specified EXTI line is asserted or not. + * @param EXTI_Line: specifies the EXTI line to check. + * This parameter can be: + * @arg EXTI_Linex: External interrupt line x where x(0..19) + * @retval The new state of EXTI_Line (SET or RESET). + */ +ITStatus EXTI_GetITStatus(uint32_t EXTI_Line) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + /* Check the parameters */ + assert_param(IS_GET_EXTI_LINE(EXTI_Line)); + + enablestatus = EXTI->IMR & EXTI_Line; + if (((EXTI->PR & EXTI_Line) != (uint32_t)RESET) && (enablestatus != (uint32_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the EXTI's line pending bits. + * @param EXTI_Line: specifies the EXTI lines to clear. + * This parameter can be any combination of EXTI_Linex where x can be (0..19). + * @retval None + */ +void EXTI_ClearITPendingBit(uint32_t EXTI_Line) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE(EXTI_Line)); + + EXTI->PR = EXTI_Line; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c new file mode 100644 index 0000000..cdff9e9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c @@ -0,0 +1,1684 @@ +/** + ****************************************************************************** + * @file stm32f10x_flash.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the FLASH firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_flash.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup FLASH + * @brief FLASH driver modules + * @{ + */ + +/** @defgroup FLASH_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup FLASH_Private_Defines + * @{ + */ + +/* Flash Access Control Register bits */ +#define ACR_LATENCY_Mask ((uint32_t)0x00000038) +#define ACR_HLFCYA_Mask ((uint32_t)0xFFFFFFF7) +#define ACR_PRFTBE_Mask ((uint32_t)0xFFFFFFEF) + +/* Flash Access Control Register bits */ +#define ACR_PRFTBS_Mask ((uint32_t)0x00000020) + +/* Flash Control Register bits */ +#define CR_PG_Set ((uint32_t)0x00000001) +#define CR_PG_Reset ((uint32_t)0x00001FFE) +#define CR_PER_Set ((uint32_t)0x00000002) +#define CR_PER_Reset ((uint32_t)0x00001FFD) +#define CR_MER_Set ((uint32_t)0x00000004) +#define CR_MER_Reset ((uint32_t)0x00001FFB) +#define CR_OPTPG_Set ((uint32_t)0x00000010) +#define CR_OPTPG_Reset ((uint32_t)0x00001FEF) +#define CR_OPTER_Set ((uint32_t)0x00000020) +#define CR_OPTER_Reset ((uint32_t)0x00001FDF) +#define CR_STRT_Set ((uint32_t)0x00000040) +#define CR_LOCK_Set ((uint32_t)0x00000080) + +/* FLASH Mask */ +#define RDPRT_Mask ((uint32_t)0x00000002) +#define WRP0_Mask ((uint32_t)0x000000FF) +#define WRP1_Mask ((uint32_t)0x0000FF00) +#define WRP2_Mask ((uint32_t)0x00FF0000) +#define WRP3_Mask ((uint32_t)0xFF000000) +#define OB_USER_BFB2 ((uint16_t)0x0008) + +/* FLASH Keys */ +#define RDP_Key ((uint16_t)0x00A5) +#define FLASH_KEY1 ((uint32_t)0x45670123) +#define FLASH_KEY2 ((uint32_t)0xCDEF89AB) + +/* FLASH BANK address */ +#define FLASH_BANK1_END_ADDRESS ((uint32_t)0x807FFFF) + +/* Delay definition */ +#define EraseTimeout ((uint32_t)0x000B0000) +#define ProgramTimeout ((uint32_t)0x00002000) +/** + * @} + */ + +/** @defgroup FLASH_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup FLASH_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup FLASH_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup FLASH_Private_Functions + * @{ + */ + +/** +@code + + This driver provides functions to configure and program the Flash memory of all STM32F10x devices, + including the latest STM32F10x_XL density devices. + + STM32F10x_XL devices feature up to 1 Mbyte with dual bank architecture for read-while-write (RWW) capability: + - bank1: fixed size of 512 Kbytes (256 pages of 2Kbytes each) + - bank2: up to 512 Kbytes (up to 256 pages of 2Kbytes each) + While other STM32F10x devices features only one bank with memory up to 512 Kbytes. + + In version V3.3.0, some functions were updated and new ones were added to support + STM32F10x_XL devices. Thus some functions manages all devices, while other are + dedicated for XL devices only. + + The table below presents the list of available functions depending on the used STM32F10x devices. + + *************************************************** + * Legacy functions used for all STM32F10x devices * + *************************************************** + +----------------------------------------------------------------------------------------------------------------------------------+ + | Functions prototypes |STM32F10x_XL|Other STM32F10x| Comments | + | | devices | devices | | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_SetLatency | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_HalfCycleAccessCmd | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_PrefetchBufferCmd | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_Unlock | Yes | Yes | - For STM32F10X_XL devices: unlock Bank1 and Bank2. | + | | | | - For other devices: unlock Bank1 and it is equivalent | + | | | | to FLASH_UnlockBank1 function. | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_Lock | Yes | Yes | - For STM32F10X_XL devices: lock Bank1 and Bank2. | + | | | | - For other devices: lock Bank1 and it is equivalent | + | | | | to FLASH_LockBank1 function. | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ErasePage | Yes | Yes | - For STM32F10x_XL devices: erase a page in Bank1 and Bank2 | + | | | | - For other devices: erase a page in Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_EraseAllPages | Yes | Yes | - For STM32F10x_XL devices: erase all pages in Bank1 and Bank2 | + | | | | - For other devices: erase all pages in Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_EraseOptionBytes | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ProgramWord | Yes | Yes | Updated to program up to 1MByte (depending on the used device) | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ProgramHalfWord | Yes | Yes | Updated to program up to 1MByte (depending on the used device) | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ProgramOptionByteData | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_EnableWriteProtection | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ReadOutProtection | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_UserOptionByteConfig | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetUserOptionByte | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetWriteProtectionOptionByte | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetReadOutProtectionStatus | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetPrefetchBufferStatus | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ITConfig | Yes | Yes | - For STM32F10x_XL devices: enable Bank1 and Bank2's interrupts| + | | | | - For other devices: enable Bank1's interrupts | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetFlagStatus | Yes | Yes | - For STM32F10x_XL devices: return Bank1 and Bank2's flag status| + | | | | - For other devices: return Bank1's flag status | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ClearFlag | Yes | Yes | - For STM32F10x_XL devices: clear Bank1 and Bank2's flag | + | | | | - For other devices: clear Bank1's flag | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetStatus | Yes | Yes | - Return the status of Bank1 (for all devices) | + | | | | equivalent to FLASH_GetBank1Status function | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_WaitForLastOperation | Yes | Yes | - Wait for Bank1 last operation (for all devices) | + | | | | equivalent to: FLASH_WaitForLastBank1Operation function | + +----------------------------------------------------------------------------------------------------------------------------------+ + + ************************************************************************************************************************ + * New functions used for all STM32F10x devices to manage Bank1: * + * - These functions are mainly useful for STM32F10x_XL density devices, to have separate control for Bank1 and bank2 * + * - For other devices, these functions are optional (covered by functions listed above) * + ************************************************************************************************************************ + +----------------------------------------------------------------------------------------------------------------------------------+ + | Functions prototypes |STM32F10x_XL|Other STM32F10x| Comments | + | | devices | devices | | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_UnlockBank1 | Yes | Yes | - Unlock Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_LockBank1 | Yes | Yes | - Lock Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_EraseAllBank1Pages | Yes | Yes | - Erase all pages in Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_GetBank1Status | Yes | Yes | - Return the status of Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_WaitForLastBank1Operation | Yes | Yes | - Wait for Bank1 last operation | + +----------------------------------------------------------------------------------------------------------------------------------+ + + ***************************************************************************** + * New Functions used only with STM32F10x_XL density devices to manage Bank2 * + ***************************************************************************** + +----------------------------------------------------------------------------------------------------------------------------------+ + | Functions prototypes |STM32F10x_XL|Other STM32F10x| Comments | + | | devices | devices | | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_UnlockBank2 | Yes | No | - Unlock Bank2 | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_LockBank2 | Yes | No | - Lock Bank2 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_EraseAllBank2Pages | Yes | No | - Erase all pages in Bank2 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_GetBank2Status | Yes | No | - Return the status of Bank2 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_WaitForLastBank2Operation | Yes | No | - Wait for Bank2 last operation | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_BootConfig | Yes | No | - Configure to boot from Bank1 or Bank2 | + +----------------------------------------------------------------------------------------------------------------------------------+ +@endcode +*/ + + +/** + * @brief Sets the code latency value. + * @note This function can be used for all STM32F10x devices. + * @param FLASH_Latency: specifies the FLASH Latency value. + * This parameter can be one of the following values: + * @arg FLASH_Latency_0: FLASH Zero Latency cycle + * @arg FLASH_Latency_1: FLASH One Latency cycle + * @arg FLASH_Latency_2: FLASH Two Latency cycles + * @retval None + */ +void FLASH_SetLatency(uint32_t FLASH_Latency) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_FLASH_LATENCY(FLASH_Latency)); + + /* Read the ACR register */ + tmpreg = FLASH->ACR; + + /* Sets the Latency value */ + tmpreg &= ACR_LATENCY_Mask; + tmpreg |= FLASH_Latency; + + /* Write the ACR register */ + FLASH->ACR = tmpreg; +} + +/** + * @brief Enables or disables the Half cycle flash access. + * @note This function can be used for all STM32F10x devices. + * @param FLASH_HalfCycleAccess: specifies the FLASH Half cycle Access mode. + * This parameter can be one of the following values: + * @arg FLASH_HalfCycleAccess_Enable: FLASH Half Cycle Enable + * @arg FLASH_HalfCycleAccess_Disable: FLASH Half Cycle Disable + * @retval None + */ +void FLASH_HalfCycleAccessCmd(uint32_t FLASH_HalfCycleAccess) +{ + /* Check the parameters */ + assert_param(IS_FLASH_HALFCYCLEACCESS_STATE(FLASH_HalfCycleAccess)); + + /* Enable or disable the Half cycle access */ + FLASH->ACR &= ACR_HLFCYA_Mask; + FLASH->ACR |= FLASH_HalfCycleAccess; +} + +/** + * @brief Enables or disables the Prefetch Buffer. + * @note This function can be used for all STM32F10x devices. + * @param FLASH_PrefetchBuffer: specifies the Prefetch buffer status. + * This parameter can be one of the following values: + * @arg FLASH_PrefetchBuffer_Enable: FLASH Prefetch Buffer Enable + * @arg FLASH_PrefetchBuffer_Disable: FLASH Prefetch Buffer Disable + * @retval None + */ +void FLASH_PrefetchBufferCmd(uint32_t FLASH_PrefetchBuffer) +{ + /* Check the parameters */ + assert_param(IS_FLASH_PREFETCHBUFFER_STATE(FLASH_PrefetchBuffer)); + + /* Enable or disable the Prefetch Buffer */ + FLASH->ACR &= ACR_PRFTBE_Mask; + FLASH->ACR |= FLASH_PrefetchBuffer; +} + +/** + * @brief Unlocks the FLASH Program Erase Controller. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices this function unlocks Bank1 and Bank2. + * - For all other devices it unlocks Bank1 and it is equivalent + * to FLASH_UnlockBank1 function.. + * @param None + * @retval None + */ +void FLASH_Unlock(void) +{ + /* Authorize the FPEC of Bank1 Access */ + FLASH->KEYR = FLASH_KEY1; + FLASH->KEYR = FLASH_KEY2; + +#ifdef STM32F10X_XL + /* Authorize the FPEC of Bank2 Access */ + FLASH->KEYR2 = FLASH_KEY1; + FLASH->KEYR2 = FLASH_KEY2; +#endif /* STM32F10X_XL */ +} +/** + * @brief Unlocks the FLASH Bank1 Program Erase Controller. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices this function unlocks Bank1. + * - For all other devices it unlocks Bank1 and it is + * equivalent to FLASH_Unlock function. + * @param None + * @retval None + */ +void FLASH_UnlockBank1(void) +{ + /* Authorize the FPEC of Bank1 Access */ + FLASH->KEYR = FLASH_KEY1; + FLASH->KEYR = FLASH_KEY2; +} + +#ifdef STM32F10X_XL +/** + * @brief Unlocks the FLASH Bank2 Program Erase Controller. + * @note This function can be used only for STM32F10X_XL density devices. + * @param None + * @retval None + */ +void FLASH_UnlockBank2(void) +{ + /* Authorize the FPEC of Bank2 Access */ + FLASH->KEYR2 = FLASH_KEY1; + FLASH->KEYR2 = FLASH_KEY2; + +} +#endif /* STM32F10X_XL */ + +/** + * @brief Locks the FLASH Program Erase Controller. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices this function Locks Bank1 and Bank2. + * - For all other devices it Locks Bank1 and it is equivalent + * to FLASH_LockBank1 function. + * @param None + * @retval None + */ +void FLASH_Lock(void) +{ + /* Set the Lock Bit to lock the FPEC and the CR of Bank1 */ + FLASH->CR |= CR_LOCK_Set; + +#ifdef STM32F10X_XL + /* Set the Lock Bit to lock the FPEC and the CR of Bank2 */ + FLASH->CR2 |= CR_LOCK_Set; +#endif /* STM32F10X_XL */ +} + +/** + * @brief Locks the FLASH Bank1 Program Erase Controller. + * @note this function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices this function Locks Bank1. + * - For all other devices it Locks Bank1 and it is equivalent + * to FLASH_Lock function. + * @param None + * @retval None + */ +void FLASH_LockBank1(void) +{ + /* Set the Lock Bit to lock the FPEC and the CR of Bank1 */ + FLASH->CR |= CR_LOCK_Set; +} + +#ifdef STM32F10X_XL +/** + * @brief Locks the FLASH Bank2 Program Erase Controller. + * @note This function can be used only for STM32F10X_XL density devices. + * @param None + * @retval None + */ +void FLASH_LockBank2(void) +{ + /* Set the Lock Bit to lock the FPEC and the CR of Bank2 */ + FLASH->CR2 |= CR_LOCK_Set; +} +#endif /* STM32F10X_XL */ + +/** + * @brief Erases a specified FLASH page. + * @note This function can be used for all STM32F10x devices. + * @param Page_Address: The page address to be erased. + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ErasePage(uint32_t Page_Address) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Page_Address)); + +#ifdef STM32F10X_XL + if(Page_Address < FLASH_BANK1_END_ADDRESS) + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase the page */ + FLASH->CR|= CR_PER_Set; + FLASH->AR = Page_Address; + FLASH->CR|= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + + /* Disable the PER Bit */ + FLASH->CR &= CR_PER_Reset; + } + } + else + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase the page */ + FLASH->CR2|= CR_PER_Set; + FLASH->AR2 = Page_Address; + FLASH->CR2|= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(EraseTimeout); + + /* Disable the PER Bit */ + FLASH->CR2 &= CR_PER_Reset; + } + } +#else + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase the page */ + FLASH->CR|= CR_PER_Set; + FLASH->AR = Page_Address; + FLASH->CR|= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + + /* Disable the PER Bit */ + FLASH->CR &= CR_PER_Reset; + } +#endif /* STM32F10X_XL */ + + /* Return the Erase Status */ + return status; +} + +/** + * @brief Erases all FLASH pages. + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EraseAllPages(void) +{ + FLASH_Status status = FLASH_COMPLETE; + +#ifdef STM32F10X_XL + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR |= CR_MER_Set; + FLASH->CR |= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + + /* Disable the MER Bit */ + FLASH->CR &= CR_MER_Reset; + } + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR2 |= CR_MER_Set; + FLASH->CR2 |= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(EraseTimeout); + + /* Disable the MER Bit */ + FLASH->CR2 &= CR_MER_Reset; + } +#else + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR |= CR_MER_Set; + FLASH->CR |= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + + /* Disable the MER Bit */ + FLASH->CR &= CR_MER_Reset; + } +#endif /* STM32F10X_XL */ + + /* Return the Erase Status */ + return status; +} + +/** + * @brief Erases all Bank1 FLASH pages. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices this function erases all Bank1 pages. + * - For all other devices it erases all Bank1 pages and it is equivalent + * to FLASH_EraseAllPages function. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EraseAllBank1Pages(void) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR |= CR_MER_Set; + FLASH->CR |= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + + /* Disable the MER Bit */ + FLASH->CR &= CR_MER_Reset; + } + /* Return the Erase Status */ + return status; +} + +#ifdef STM32F10X_XL +/** + * @brief Erases all Bank2 FLASH pages. + * @note This function can be used only for STM32F10x_XL density devices. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EraseAllBank2Pages(void) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(EraseTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR2 |= CR_MER_Set; + FLASH->CR2 |= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(EraseTimeout); + + /* Disable the MER Bit */ + FLASH->CR2 &= CR_MER_Reset; + } + /* Return the Erase Status */ + return status; +} +#endif /* STM32F10X_XL */ + +/** + * @brief Erases the FLASH option bytes. + * @note This functions erases all option bytes except the Read protection (RDP). + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EraseOptionBytes(void) +{ + uint16_t rdptmp = RDP_Key; + + FLASH_Status status = FLASH_COMPLETE; + + /* Get the actual read protection Option Byte value */ + if(FLASH_GetReadOutProtectionStatus() != RESET) + { + rdptmp = 0x00; + } + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + + /* if the previous operation is completed, proceed to erase the option bytes */ + FLASH->CR |= CR_OPTER_Set; + FLASH->CR |= CR_STRT_Set; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the erase operation is completed, disable the OPTER Bit */ + FLASH->CR &= CR_OPTER_Reset; + + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= CR_OPTPG_Set; + /* Restore the last read protection Option Byte value */ + OB->RDP = (uint16_t)rdptmp; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + else + { + if (status != FLASH_TIMEOUT) + { + /* Disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + } + /* Return the erase status */ + return status; +} + +/** + * @brief Programs a word at a specified address. + * @note This function can be used for all STM32F10x devices. + * @param Address: specifies the address to be programmed. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + +#ifdef STM32F10X_XL + if(Address < FLASH_BANK1_END_ADDRESS - 2) + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(ProgramTimeout); + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new first + half word */ + FLASH->CR |= CR_PG_Set; + + *(__IO uint16_t*)Address = (uint16_t)Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new second + half word */ + tmp = Address + 2; + + *(__IO uint16_t*) tmp = Data >> 16; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + else + { + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + } + } + else if(Address == (FLASH_BANK1_END_ADDRESS - 1)) + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new first + half word */ + FLASH->CR |= CR_PG_Set; + + *(__IO uint16_t*)Address = (uint16_t)Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + else + { + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new second + half word */ + FLASH->CR2 |= CR_PG_Set; + tmp = Address + 2; + + *(__IO uint16_t*) tmp = Data >> 16; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR2 &= CR_PG_Reset; + } + else + { + /* Disable the PG Bit */ + FLASH->CR2 &= CR_PG_Reset; + } + } + else + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new first + half word */ + FLASH->CR2 |= CR_PG_Set; + + *(__IO uint16_t*)Address = (uint16_t)Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new second + half word */ + tmp = Address + 2; + + *(__IO uint16_t*) tmp = Data >> 16; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR2 &= CR_PG_Reset; + } + else + { + /* Disable the PG Bit */ + FLASH->CR2 &= CR_PG_Reset; + } + } + } +#else + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new first + half word */ + FLASH->CR |= CR_PG_Set; + + *(__IO uint16_t*)Address = (uint16_t)Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new second + half word */ + tmp = Address + 2; + + *(__IO uint16_t*) tmp = Data >> 16; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + else + { + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + } +#endif /* STM32F10X_XL */ + + /* Return the Program Status */ + return status; +} + +/** + * @brief Programs a half word at a specified address. + * @note This function can be used for all STM32F10x devices. + * @param Address: specifies the address to be programmed. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + +#ifdef STM32F10X_XL + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(Address < FLASH_BANK1_END_ADDRESS) + { + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new data */ + FLASH->CR |= CR_PG_Set; + + *(__IO uint16_t*)Address = Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + } + else + { + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new data */ + FLASH->CR2 |= CR_PG_Set; + + *(__IO uint16_t*)Address = Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR2 &= CR_PG_Reset; + } + } +#else + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new data */ + FLASH->CR |= CR_PG_Set; + + *(__IO uint16_t*)Address = Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } +#endif /* STM32F10X_XL */ + + /* Return the Program Status */ + return status; +} + +/** + * @brief Programs a half word at a specified Option Byte Data address. + * @note This function can be used for all STM32F10x devices. + * @param Address: specifies the address to be programmed. + * This parameter can be 0x1FFFF804 or 0x1FFFF806. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ProgramOptionByteData(uint32_t Address, uint8_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Check the parameters */ + assert_param(IS_OB_DATA_ADDRESS(Address)); + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + /* Enables the Option Bytes Programming operation */ + FLASH->CR |= CR_OPTPG_Set; + *(__IO uint16_t*)Address = Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + /* Return the Option Byte Data Program Status */ + return status; +} + +/** + * @brief Write protects the desired pages + * @note This function can be used for all STM32F10x devices. + * @param FLASH_Pages: specifies the address of the pages to be write protected. + * This parameter can be: + * @arg For @b STM32_Low-density_devices: value between FLASH_WRProt_Pages0to3 and FLASH_WRProt_Pages28to31 + * @arg For @b STM32_Medium-density_devices: value between FLASH_WRProt_Pages0to3 + * and FLASH_WRProt_Pages124to127 + * @arg For @b STM32_High-density_devices: value between FLASH_WRProt_Pages0to1 and + * FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to255 + * @arg For @b STM32_Connectivity_line_devices: value between FLASH_WRProt_Pages0to1 and + * FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to127 + * @arg For @b STM32_XL-density_devices: value between FLASH_WRProt_Pages0to1 and + * FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to511 + * @arg FLASH_WRProt_AllPages + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EnableWriteProtection(uint32_t FLASH_Pages) +{ + uint16_t WRP0_Data = 0xFFFF, WRP1_Data = 0xFFFF, WRP2_Data = 0xFFFF, WRP3_Data = 0xFFFF; + + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_FLASH_WRPROT_PAGE(FLASH_Pages)); + + FLASH_Pages = (uint32_t)(~FLASH_Pages); + WRP0_Data = (uint16_t)(FLASH_Pages & WRP0_Mask); + WRP1_Data = (uint16_t)((FLASH_Pages & WRP1_Mask) >> 8); + WRP2_Data = (uint16_t)((FLASH_Pages & WRP2_Mask) >> 16); + WRP3_Data = (uint16_t)((FLASH_Pages & WRP3_Mask) >> 24); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* Authorizes the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + FLASH->CR |= CR_OPTPG_Set; + if(WRP0_Data != 0xFF) + { + OB->WRP0 = WRP0_Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + } + if((status == FLASH_COMPLETE) && (WRP1_Data != 0xFF)) + { + OB->WRP1 = WRP1_Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + } + if((status == FLASH_COMPLETE) && (WRP2_Data != 0xFF)) + { + OB->WRP2 = WRP2_Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + } + + if((status == FLASH_COMPLETE)&& (WRP3_Data != 0xFF)) + { + OB->WRP3 = WRP3_Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + } + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + /* Return the write protection operation Status */ + return status; +} + +/** + * @brief Enables or disables the read out protection. + * @note If the user has already programmed the other option bytes before calling + * this function, he must re-program them since this function erases all option bytes. + * @note This function can be used for all STM32F10x devices. + * @param Newstate: new state of the ReadOut Protection. + * This parameter can be: ENABLE or DISABLE. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + status = FLASH_WaitForLastOperation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* Authorizes the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + FLASH->CR |= CR_OPTER_Set; + FLASH->CR |= CR_STRT_Set; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* if the erase operation is completed, disable the OPTER Bit */ + FLASH->CR &= CR_OPTER_Reset; + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= CR_OPTPG_Set; + if(NewState != DISABLE) + { + OB->RDP = 0x00; + } + else + { + OB->RDP = RDP_Key; + } + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + else + { + if(status != FLASH_TIMEOUT) + { + /* Disable the OPTER Bit */ + FLASH->CR &= CR_OPTER_Reset; + } + } + } + /* Return the protection operation Status */ + return status; +} + +/** + * @brief Programs the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY. + * @note This function can be used for all STM32F10x devices. + * @param OB_IWDG: Selects the IWDG mode + * This parameter can be one of the following values: + * @arg OB_IWDG_SW: Software IWDG selected + * @arg OB_IWDG_HW: Hardware IWDG selected + * @param OB_STOP: Reset event when entering STOP mode. + * This parameter can be one of the following values: + * @arg OB_STOP_NoRST: No reset generated when entering in STOP + * @arg OB_STOP_RST: Reset generated when entering in STOP + * @param OB_STDBY: Reset event when entering Standby mode. + * This parameter can be one of the following values: + * @arg OB_STDBY_NoRST: No reset generated when entering in STANDBY + * @arg OB_STDBY_RST: Reset generated when entering in STANDBY + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_UserOptionByteConfig(uint16_t OB_IWDG, uint16_t OB_STOP, uint16_t OB_STDBY) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_OB_IWDG_SOURCE(OB_IWDG)); + assert_param(IS_OB_STOP_SOURCE(OB_STOP)); + assert_param(IS_OB_STDBY_SOURCE(OB_STDBY)); + + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= CR_OPTPG_Set; + + OB->USER = OB_IWDG | (uint16_t)(OB_STOP | (uint16_t)(OB_STDBY | ((uint16_t)0xF8))); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + /* Return the Option Byte program Status */ + return status; +} + +#ifdef STM32F10X_XL +/** + * @brief Configures to boot from Bank1 or Bank2. + * @note This function can be used only for STM32F10x_XL density devices. + * @param FLASH_BOOT: select the FLASH Bank to boot from. + * This parameter can be one of the following values: + * @arg FLASH_BOOT_Bank1: At startup, if boot pins are set in boot from user Flash + * position and this parameter is selected the device will boot from Bank1(Default). + * @arg FLASH_BOOT_Bank2: At startup, if boot pins are set in boot from user Flash + * position and this parameter is selected the device will boot from Bank2 or Bank1, + * depending on the activation of the bank. The active banks are checked in + * the following order: Bank2, followed by Bank1. + * The active bank is recognized by the value programmed at the base address + * of the respective bank (corresponding to the initial stack pointer value + * in the interrupt vector table). + * For more information, please refer to AN2606 from www.st.com. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_BootConfig(uint16_t FLASH_BOOT) +{ + FLASH_Status status = FLASH_COMPLETE; + assert_param(IS_FLASH_BOOT(FLASH_BOOT)); + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= CR_OPTPG_Set; + + if(FLASH_BOOT == FLASH_BOOT_Bank1) + { + OB->USER |= OB_USER_BFB2; + } + else + { + OB->USER &= (uint16_t)(~(uint16_t)(OB_USER_BFB2)); + } + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + /* Return the Option Byte program Status */ + return status; +} +#endif /* STM32F10X_XL */ + +/** + * @brief Returns the FLASH User Option Bytes values. + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval The FLASH User Option Bytes values:IWDG_SW(Bit0), RST_STOP(Bit1) + * and RST_STDBY(Bit2). + */ +uint32_t FLASH_GetUserOptionByte(void) +{ + /* Return the User Option Byte */ + return (uint32_t)(FLASH->OBR >> 2); +} + +/** + * @brief Returns the FLASH Write Protection Option Bytes Register value. + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval The FLASH Write Protection Option Bytes Register value + */ +uint32_t FLASH_GetWriteProtectionOptionByte(void) +{ + /* Return the Flash write protection Register value */ + return (uint32_t)(FLASH->WRPR); +} + +/** + * @brief Checks whether the FLASH Read Out Protection Status is set or not. + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval FLASH ReadOut Protection Status(SET or RESET) + */ +FlagStatus FLASH_GetReadOutProtectionStatus(void) +{ + FlagStatus readoutstatus = RESET; + if ((FLASH->OBR & RDPRT_Mask) != (uint32_t)RESET) + { + readoutstatus = SET; + } + else + { + readoutstatus = RESET; + } + return readoutstatus; +} + +/** + * @brief Checks whether the FLASH Prefetch Buffer status is set or not. + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval FLASH Prefetch Buffer Status (SET or RESET). + */ +FlagStatus FLASH_GetPrefetchBufferStatus(void) +{ + FlagStatus bitstatus = RESET; + + if ((FLASH->ACR & ACR_PRFTBS_Mask) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the new state of FLASH Prefetch Buffer Status (SET or RESET) */ + return bitstatus; +} + +/** + * @brief Enables or disables the specified FLASH interrupts. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices, enables or disables the specified FLASH interrupts + for Bank1 and Bank2. + * - For other devices it enables or disables the specified FLASH interrupts for Bank1. + * @param FLASH_IT: specifies the FLASH interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg FLASH_IT_ERROR: FLASH Error Interrupt + * @arg FLASH_IT_EOP: FLASH end of operation Interrupt + * @param NewState: new state of the specified Flash interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState) +{ +#ifdef STM32F10X_XL + /* Check the parameters */ + assert_param(IS_FLASH_IT(FLASH_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if((FLASH_IT & 0x80000000) != 0x0) + { + if(NewState != DISABLE) + { + /* Enable the interrupt sources */ + FLASH->CR2 |= (FLASH_IT & 0x7FFFFFFF); + } + else + { + /* Disable the interrupt sources */ + FLASH->CR2 &= ~(uint32_t)(FLASH_IT & 0x7FFFFFFF); + } + } + else + { + if(NewState != DISABLE) + { + /* Enable the interrupt sources */ + FLASH->CR |= FLASH_IT; + } + else + { + /* Disable the interrupt sources */ + FLASH->CR &= ~(uint32_t)FLASH_IT; + } + } +#else + /* Check the parameters */ + assert_param(IS_FLASH_IT(FLASH_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if(NewState != DISABLE) + { + /* Enable the interrupt sources */ + FLASH->CR |= FLASH_IT; + } + else + { + /* Disable the interrupt sources */ + FLASH->CR &= ~(uint32_t)FLASH_IT; + } +#endif /* STM32F10X_XL */ +} + +/** + * @brief Checks whether the specified FLASH flag is set or not. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices, this function checks whether the specified + * Bank1 or Bank2 flag is set or not. + * - For other devices, it checks whether the specified Bank1 flag is + * set or not. + * @param FLASH_FLAG: specifies the FLASH flag to check. + * This parameter can be one of the following values: + * @arg FLASH_FLAG_BSY: FLASH Busy flag + * @arg FLASH_FLAG_PGERR: FLASH Program error flag + * @arg FLASH_FLAG_WRPRTERR: FLASH Write protected error flag + * @arg FLASH_FLAG_EOP: FLASH End of Operation flag + * @arg FLASH_FLAG_OPTERR: FLASH Option Byte error flag + * @retval The new state of FLASH_FLAG (SET or RESET). + */ +FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG) +{ + FlagStatus bitstatus = RESET; + +#ifdef STM32F10X_XL + /* Check the parameters */ + assert_param(IS_FLASH_GET_FLAG(FLASH_FLAG)) ; + if(FLASH_FLAG == FLASH_FLAG_OPTERR) + { + if((FLASH->OBR & FLASH_FLAG_OPTERR) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + else + { + if((FLASH_FLAG & 0x80000000) != 0x0) + { + if((FLASH->SR2 & FLASH_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + else + { + if((FLASH->SR & FLASH_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + } +#else + /* Check the parameters */ + assert_param(IS_FLASH_GET_FLAG(FLASH_FLAG)) ; + if(FLASH_FLAG == FLASH_FLAG_OPTERR) + { + if((FLASH->OBR & FLASH_FLAG_OPTERR) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + else + { + if((FLASH->SR & FLASH_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } +#endif /* STM32F10X_XL */ + + /* Return the new state of FLASH_FLAG (SET or RESET) */ + return bitstatus; +} + +/** + * @brief Clears the FLASH's pending flags. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices, this function clears Bank1 or Bank2’s pending flags + * - For other devices, it clears Bank1’s pending flags. + * @param FLASH_FLAG: specifies the FLASH flags to clear. + * This parameter can be any combination of the following values: + * @arg FLASH_FLAG_PGERR: FLASH Program error flag + * @arg FLASH_FLAG_WRPRTERR: FLASH Write protected error flag + * @arg FLASH_FLAG_EOP: FLASH End of Operation flag + * @retval None + */ +void FLASH_ClearFlag(uint32_t FLASH_FLAG) +{ +#ifdef STM32F10X_XL + /* Check the parameters */ + assert_param(IS_FLASH_CLEAR_FLAG(FLASH_FLAG)) ; + + if((FLASH_FLAG & 0x80000000) != 0x0) + { + /* Clear the flags */ + FLASH->SR2 = FLASH_FLAG; + } + else + { + /* Clear the flags */ + FLASH->SR = FLASH_FLAG; + } + +#else + /* Check the parameters */ + assert_param(IS_FLASH_CLEAR_FLAG(FLASH_FLAG)) ; + + /* Clear the flags */ + FLASH->SR = FLASH_FLAG; +#endif /* STM32F10X_XL */ +} + +/** + * @brief Returns the FLASH Status. + * @note This function can be used for all STM32F10x devices, it is equivalent + * to FLASH_GetBank1Status function. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, + * FLASH_ERROR_WRP or FLASH_COMPLETE + */ +FLASH_Status FLASH_GetStatus(void) +{ + FLASH_Status flashstatus = FLASH_COMPLETE; + + if((FLASH->SR & FLASH_FLAG_BSY) == FLASH_FLAG_BSY) + { + flashstatus = FLASH_BUSY; + } + else + { + if((FLASH->SR & FLASH_FLAG_PGERR) != 0) + { + flashstatus = FLASH_ERROR_PG; + } + else + { + if((FLASH->SR & FLASH_FLAG_WRPRTERR) != 0 ) + { + flashstatus = FLASH_ERROR_WRP; + } + else + { + flashstatus = FLASH_COMPLETE; + } + } + } + /* Return the Flash Status */ + return flashstatus; +} + +/** + * @brief Returns the FLASH Bank1 Status. + * @note This function can be used for all STM32F10x devices, it is equivalent + * to FLASH_GetStatus function. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, + * FLASH_ERROR_WRP or FLASH_COMPLETE + */ +FLASH_Status FLASH_GetBank1Status(void) +{ + FLASH_Status flashstatus = FLASH_COMPLETE; + + if((FLASH->SR & FLASH_FLAG_BANK1_BSY) == FLASH_FLAG_BSY) + { + flashstatus = FLASH_BUSY; + } + else + { + if((FLASH->SR & FLASH_FLAG_BANK1_PGERR) != 0) + { + flashstatus = FLASH_ERROR_PG; + } + else + { + if((FLASH->SR & FLASH_FLAG_BANK1_WRPRTERR) != 0 ) + { + flashstatus = FLASH_ERROR_WRP; + } + else + { + flashstatus = FLASH_COMPLETE; + } + } + } + /* Return the Flash Status */ + return flashstatus; +} + +#ifdef STM32F10X_XL +/** + * @brief Returns the FLASH Bank2 Status. + * @note This function can be used for STM32F10x_XL density devices. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, + * FLASH_ERROR_WRP or FLASH_COMPLETE + */ +FLASH_Status FLASH_GetBank2Status(void) +{ + FLASH_Status flashstatus = FLASH_COMPLETE; + + if((FLASH->SR2 & (FLASH_FLAG_BANK2_BSY & 0x7FFFFFFF)) == (FLASH_FLAG_BANK2_BSY & 0x7FFFFFFF)) + { + flashstatus = FLASH_BUSY; + } + else + { + if((FLASH->SR2 & (FLASH_FLAG_BANK2_PGERR & 0x7FFFFFFF)) != 0) + { + flashstatus = FLASH_ERROR_PG; + } + else + { + if((FLASH->SR2 & (FLASH_FLAG_BANK2_WRPRTERR & 0x7FFFFFFF)) != 0 ) + { + flashstatus = FLASH_ERROR_WRP; + } + else + { + flashstatus = FLASH_COMPLETE; + } + } + } + /* Return the Flash Status */ + return flashstatus; +} +#endif /* STM32F10X_XL */ +/** + * @brief Waits for a Flash operation to complete or a TIMEOUT to occur. + * @note This function can be used for all STM32F10x devices, + * it is equivalent to FLASH_WaitForLastBank1Operation. + * - For STM32F10X_XL devices this function waits for a Bank1 Flash operation + * to complete or a TIMEOUT to occur. + * - For all other devices it waits for a Flash operation to complete + * or a TIMEOUT to occur. + * @param Timeout: FLASH programming Timeout + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_WaitForLastOperation(uint32_t Timeout) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check for the Flash Status */ + status = FLASH_GetBank1Status(); + /* Wait for a Flash operation to complete or a TIMEOUT to occur */ + while((status == FLASH_BUSY) && (Timeout != 0x00)) + { + status = FLASH_GetBank1Status(); + Timeout--; + } + if(Timeout == 0x00 ) + { + status = FLASH_TIMEOUT; + } + /* Return the operation status */ + return status; +} + +/** + * @brief Waits for a Flash operation on Bank1 to complete or a TIMEOUT to occur. + * @note This function can be used for all STM32F10x devices, + * it is equivalent to FLASH_WaitForLastOperation. + * @param Timeout: FLASH programming Timeout + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_WaitForLastBank1Operation(uint32_t Timeout) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check for the Flash Status */ + status = FLASH_GetBank1Status(); + /* Wait for a Flash operation to complete or a TIMEOUT to occur */ + while((status == FLASH_FLAG_BANK1_BSY) && (Timeout != 0x00)) + { + status = FLASH_GetBank1Status(); + Timeout--; + } + if(Timeout == 0x00 ) + { + status = FLASH_TIMEOUT; + } + /* Return the operation status */ + return status; +} + +#ifdef STM32F10X_XL +/** + * @brief Waits for a Flash operation on Bank2 to complete or a TIMEOUT to occur. + * @note This function can be used only for STM32F10x_XL density devices. + * @param Timeout: FLASH programming Timeout + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_WaitForLastBank2Operation(uint32_t Timeout) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check for the Flash Status */ + status = FLASH_GetBank2Status(); + /* Wait for a Flash operation to complete or a TIMEOUT to occur */ + while((status == (FLASH_FLAG_BANK2_BSY & 0x7FFFFFFF)) && (Timeout != 0x00)) + { + status = FLASH_GetBank2Status(); + Timeout--; + } + if(Timeout == 0x00 ) + { + status = FLASH_TIMEOUT; + } + /* Return the operation status */ + return status; +} +#endif /* STM32F10X_XL */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c new file mode 100644 index 0000000..51669ee --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c @@ -0,0 +1,866 @@ +/** + ****************************************************************************** + * @file stm32f10x_fsmc.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the FSMC firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_fsmc.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup FSMC + * @brief FSMC driver modules + * @{ + */ + +/** @defgroup FSMC_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + +/** @defgroup FSMC_Private_Defines + * @{ + */ + +/* --------------------- FSMC registers bit mask ---------------------------- */ + +/* FSMC BCRx Mask */ +#define BCR_MBKEN_Set ((uint32_t)0x00000001) +#define BCR_MBKEN_Reset ((uint32_t)0x000FFFFE) +#define BCR_FACCEN_Set ((uint32_t)0x00000040) + +/* FSMC PCRx Mask */ +#define PCR_PBKEN_Set ((uint32_t)0x00000004) +#define PCR_PBKEN_Reset ((uint32_t)0x000FFFFB) +#define PCR_ECCEN_Set ((uint32_t)0x00000040) +#define PCR_ECCEN_Reset ((uint32_t)0x000FFFBF) +#define PCR_MemoryType_NAND ((uint32_t)0x00000008) +/** + * @} + */ + +/** @defgroup FSMC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup FSMC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup FSMC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup FSMC_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the FSMC NOR/SRAM Banks registers to their default + * reset values. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1 + * @arg FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2 + * @arg FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3 + * @arg FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4 + * @retval None + */ +void FSMC_NORSRAMDeInit(uint32_t FSMC_Bank) +{ + /* Check the parameter */ + assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank)); + + /* FSMC_Bank1_NORSRAM1 */ + if(FSMC_Bank == FSMC_Bank1_NORSRAM1) + { + FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030DB; + } + /* FSMC_Bank1_NORSRAM2, FSMC_Bank1_NORSRAM3 or FSMC_Bank1_NORSRAM4 */ + else + { + FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030D2; + } + FSMC_Bank1->BTCR[FSMC_Bank + 1] = 0x0FFFFFFF; + FSMC_Bank1E->BWTR[FSMC_Bank] = 0x0FFFFFFF; +} + +/** + * @brief Deinitializes the FSMC NAND Banks registers to their default reset values. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @retval None + */ +void FSMC_NANDDeInit(uint32_t FSMC_Bank) +{ + /* Check the parameter */ + assert_param(IS_FSMC_NAND_BANK(FSMC_Bank)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + /* Set the FSMC_Bank2 registers to their reset values */ + FSMC_Bank2->PCR2 = 0x00000018; + FSMC_Bank2->SR2 = 0x00000040; + FSMC_Bank2->PMEM2 = 0xFCFCFCFC; + FSMC_Bank2->PATT2 = 0xFCFCFCFC; + } + /* FSMC_Bank3_NAND */ + else + { + /* Set the FSMC_Bank3 registers to their reset values */ + FSMC_Bank3->PCR3 = 0x00000018; + FSMC_Bank3->SR3 = 0x00000040; + FSMC_Bank3->PMEM3 = 0xFCFCFCFC; + FSMC_Bank3->PATT3 = 0xFCFCFCFC; + } +} + +/** + * @brief Deinitializes the FSMC PCCARD Bank registers to their default reset values. + * @param None + * @retval None + */ +void FSMC_PCCARDDeInit(void) +{ + /* Set the FSMC_Bank4 registers to their reset values */ + FSMC_Bank4->PCR4 = 0x00000018; + FSMC_Bank4->SR4 = 0x00000000; + FSMC_Bank4->PMEM4 = 0xFCFCFCFC; + FSMC_Bank4->PATT4 = 0xFCFCFCFC; + FSMC_Bank4->PIO4 = 0xFCFCFCFC; +} + +/** + * @brief Initializes the FSMC NOR/SRAM Banks according to the specified + * parameters in the FSMC_NORSRAMInitStruct. + * @param FSMC_NORSRAMInitStruct : pointer to a FSMC_NORSRAMInitTypeDef + * structure that contains the configuration information for + * the FSMC NOR/SRAM specified Banks. + * @retval None + */ +void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct) +{ + /* Check the parameters */ + assert_param(IS_FSMC_NORSRAM_BANK(FSMC_NORSRAMInitStruct->FSMC_Bank)); + assert_param(IS_FSMC_MUX(FSMC_NORSRAMInitStruct->FSMC_DataAddressMux)); + assert_param(IS_FSMC_MEMORY(FSMC_NORSRAMInitStruct->FSMC_MemoryType)); + assert_param(IS_FSMC_MEMORY_WIDTH(FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth)); + assert_param(IS_FSMC_BURSTMODE(FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode)); + assert_param(IS_FSMC_ASYNWAIT(FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait)); + assert_param(IS_FSMC_WAIT_POLARITY(FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity)); + assert_param(IS_FSMC_WRAP_MODE(FSMC_NORSRAMInitStruct->FSMC_WrapMode)); + assert_param(IS_FSMC_WAIT_SIGNAL_ACTIVE(FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive)); + assert_param(IS_FSMC_WRITE_OPERATION(FSMC_NORSRAMInitStruct->FSMC_WriteOperation)); + assert_param(IS_FSMC_WAITE_SIGNAL(FSMC_NORSRAMInitStruct->FSMC_WaitSignal)); + assert_param(IS_FSMC_EXTENDED_MODE(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode)); + assert_param(IS_FSMC_WRITE_BURST(FSMC_NORSRAMInitStruct->FSMC_WriteBurst)); + assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime)); + assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime)); + assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime)); + assert_param(IS_FSMC_TURNAROUND_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration)); + assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision)); + assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency)); + assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode)); + + /* Bank1 NOR/SRAM control register configuration */ + FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] = + (uint32_t)FSMC_NORSRAMInitStruct->FSMC_DataAddressMux | + FSMC_NORSRAMInitStruct->FSMC_MemoryType | + FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth | + FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode | + FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait | + FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity | + FSMC_NORSRAMInitStruct->FSMC_WrapMode | + FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive | + FSMC_NORSRAMInitStruct->FSMC_WriteOperation | + FSMC_NORSRAMInitStruct->FSMC_WaitSignal | + FSMC_NORSRAMInitStruct->FSMC_ExtendedMode | + FSMC_NORSRAMInitStruct->FSMC_WriteBurst; + + if(FSMC_NORSRAMInitStruct->FSMC_MemoryType == FSMC_MemoryType_NOR) + { + FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] |= (uint32_t)BCR_FACCEN_Set; + } + + /* Bank1 NOR/SRAM timing register configuration */ + FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank+1] = + (uint32_t)FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime << 4) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime << 8) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration << 16) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision << 20) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency << 24) | + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode; + + + /* Bank1 NOR/SRAM timing register for write configuration, if extended mode is used */ + if(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode == FSMC_ExtendedMode_Enable) + { + assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime)); + assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime)); + assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime)); + assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision)); + assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency)); + assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode)); + FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = + (uint32_t)FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime | + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime << 4 )| + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime << 8) | + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision << 20) | + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency << 24) | + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode; + } + else + { + FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = 0x0FFFFFFF; + } +} + +/** + * @brief Initializes the FSMC NAND Banks according to the specified + * parameters in the FSMC_NANDInitStruct. + * @param FSMC_NANDInitStruct : pointer to a FSMC_NANDInitTypeDef + * structure that contains the configuration information for the FSMC + * NAND specified Banks. + * @retval None + */ +void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct) +{ + uint32_t tmppcr = 0x00000000, tmppmem = 0x00000000, tmppatt = 0x00000000; + + /* Check the parameters */ + assert_param( IS_FSMC_NAND_BANK(FSMC_NANDInitStruct->FSMC_Bank)); + assert_param( IS_FSMC_WAIT_FEATURE(FSMC_NANDInitStruct->FSMC_Waitfeature)); + assert_param( IS_FSMC_MEMORY_WIDTH(FSMC_NANDInitStruct->FSMC_MemoryDataWidth)); + assert_param( IS_FSMC_ECC_STATE(FSMC_NANDInitStruct->FSMC_ECC)); + assert_param( IS_FSMC_ECCPAGE_SIZE(FSMC_NANDInitStruct->FSMC_ECCPageSize)); + assert_param( IS_FSMC_TCLR_TIME(FSMC_NANDInitStruct->FSMC_TCLRSetupTime)); + assert_param( IS_FSMC_TAR_TIME(FSMC_NANDInitStruct->FSMC_TARSetupTime)); + assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime)); + assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime)); + + /* Set the tmppcr value according to FSMC_NANDInitStruct parameters */ + tmppcr = (uint32_t)FSMC_NANDInitStruct->FSMC_Waitfeature | + PCR_MemoryType_NAND | + FSMC_NANDInitStruct->FSMC_MemoryDataWidth | + FSMC_NANDInitStruct->FSMC_ECC | + FSMC_NANDInitStruct->FSMC_ECCPageSize | + (FSMC_NANDInitStruct->FSMC_TCLRSetupTime << 9 )| + (FSMC_NANDInitStruct->FSMC_TARSetupTime << 13); + + /* Set tmppmem value according to FSMC_CommonSpaceTimingStructure parameters */ + tmppmem = (uint32_t)FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime | + (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + /* Set tmppatt value according to FSMC_AttributeSpaceTimingStructure parameters */ + tmppatt = (uint32_t)FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime | + (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + if(FSMC_NANDInitStruct->FSMC_Bank == FSMC_Bank2_NAND) + { + /* FSMC_Bank2_NAND registers configuration */ + FSMC_Bank2->PCR2 = tmppcr; + FSMC_Bank2->PMEM2 = tmppmem; + FSMC_Bank2->PATT2 = tmppatt; + } + else + { + /* FSMC_Bank3_NAND registers configuration */ + FSMC_Bank3->PCR3 = tmppcr; + FSMC_Bank3->PMEM3 = tmppmem; + FSMC_Bank3->PATT3 = tmppatt; + } +} + +/** + * @brief Initializes the FSMC PCCARD Bank according to the specified + * parameters in the FSMC_PCCARDInitStruct. + * @param FSMC_PCCARDInitStruct : pointer to a FSMC_PCCARDInitTypeDef + * structure that contains the configuration information for the FSMC + * PCCARD Bank. + * @retval None + */ +void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct) +{ + /* Check the parameters */ + assert_param(IS_FSMC_WAIT_FEATURE(FSMC_PCCARDInitStruct->FSMC_Waitfeature)); + assert_param(IS_FSMC_TCLR_TIME(FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime)); + assert_param(IS_FSMC_TAR_TIME(FSMC_PCCARDInitStruct->FSMC_TARSetupTime)); + + assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime)); + + assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime)); + assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime)); + + /* Set the PCR4 register value according to FSMC_PCCARDInitStruct parameters */ + FSMC_Bank4->PCR4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_Waitfeature | + FSMC_MemoryDataWidth_16b | + (FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime << 9) | + (FSMC_PCCARDInitStruct->FSMC_TARSetupTime << 13); + + /* Set PMEM4 register value according to FSMC_CommonSpaceTimingStructure parameters */ + FSMC_Bank4->PMEM4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime | + (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + /* Set PATT4 register value according to FSMC_AttributeSpaceTimingStructure parameters */ + FSMC_Bank4->PATT4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime | + (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + /* Set PIO4 register value according to FSMC_IOSpaceTimingStructure parameters */ + FSMC_Bank4->PIO4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime | + (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime << 24); +} + +/** + * @brief Fills each FSMC_NORSRAMInitStruct member with its default value. + * @param FSMC_NORSRAMInitStruct: pointer to a FSMC_NORSRAMInitTypeDef + * structure which will be initialized. + * @retval None + */ +void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct) +{ + /* Reset NOR/SRAM Init structure parameters values */ + FSMC_NORSRAMInitStruct->FSMC_Bank = FSMC_Bank1_NORSRAM1; + FSMC_NORSRAMInitStruct->FSMC_DataAddressMux = FSMC_DataAddressMux_Enable; + FSMC_NORSRAMInitStruct->FSMC_MemoryType = FSMC_MemoryType_SRAM; + FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b; + FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable; + FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable; + FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low; + FSMC_NORSRAMInitStruct->FSMC_WrapMode = FSMC_WrapMode_Disable; + FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState; + FSMC_NORSRAMInitStruct->FSMC_WriteOperation = FSMC_WriteOperation_Enable; + FSMC_NORSRAMInitStruct->FSMC_WaitSignal = FSMC_WaitSignal_Enable; + FSMC_NORSRAMInitStruct->FSMC_ExtendedMode = FSMC_ExtendedMode_Disable; + FSMC_NORSRAMInitStruct->FSMC_WriteBurst = FSMC_WriteBurst_Disable; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime = 0xFF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime = 0xFF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A; +} + +/** + * @brief Fills each FSMC_NANDInitStruct member with its default value. + * @param FSMC_NANDInitStruct: pointer to a FSMC_NANDInitTypeDef + * structure which will be initialized. + * @retval None + */ +void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct) +{ + /* Reset NAND Init structure parameters values */ + FSMC_NANDInitStruct->FSMC_Bank = FSMC_Bank2_NAND; + FSMC_NANDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable; + FSMC_NANDInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b; + FSMC_NANDInitStruct->FSMC_ECC = FSMC_ECC_Disable; + FSMC_NANDInitStruct->FSMC_ECCPageSize = FSMC_ECCPageSize_256Bytes; + FSMC_NANDInitStruct->FSMC_TCLRSetupTime = 0x0; + FSMC_NANDInitStruct->FSMC_TARSetupTime = 0x0; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; +} + +/** + * @brief Fills each FSMC_PCCARDInitStruct member with its default value. + * @param FSMC_PCCARDInitStruct: pointer to a FSMC_PCCARDInitTypeDef + * structure which will be initialized. + * @retval None + */ +void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct) +{ + /* Reset PCCARD Init structure parameters values */ + FSMC_PCCARDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable; + FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime = 0x0; + FSMC_PCCARDInitStruct->FSMC_TARSetupTime = 0x0; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; +} + +/** + * @brief Enables or disables the specified NOR/SRAM Memory Bank. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1 + * @arg FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2 + * @arg FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3 + * @arg FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4 + * @param NewState: new state of the FSMC_Bank. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_NORSRAMCmd(uint32_t FSMC_Bank, FunctionalState NewState) +{ + assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected NOR/SRAM Bank by setting the PBKEN bit in the BCRx register */ + FSMC_Bank1->BTCR[FSMC_Bank] |= BCR_MBKEN_Set; + } + else + { + /* Disable the selected NOR/SRAM Bank by clearing the PBKEN bit in the BCRx register */ + FSMC_Bank1->BTCR[FSMC_Bank] &= BCR_MBKEN_Reset; + } +} + +/** + * @brief Enables or disables the specified NAND Memory Bank. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @param NewState: new state of the FSMC_Bank. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_NANDCmd(uint32_t FSMC_Bank, FunctionalState NewState) +{ + assert_param(IS_FSMC_NAND_BANK(FSMC_Bank)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected NAND Bank by setting the PBKEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 |= PCR_PBKEN_Set; + } + else + { + FSMC_Bank3->PCR3 |= PCR_PBKEN_Set; + } + } + else + { + /* Disable the selected NAND Bank by clearing the PBKEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 &= PCR_PBKEN_Reset; + } + else + { + FSMC_Bank3->PCR3 &= PCR_PBKEN_Reset; + } + } +} + +/** + * @brief Enables or disables the PCCARD Memory Bank. + * @param NewState: new state of the PCCARD Memory Bank. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_PCCARDCmd(FunctionalState NewState) +{ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the PCCARD Bank by setting the PBKEN bit in the PCR4 register */ + FSMC_Bank4->PCR4 |= PCR_PBKEN_Set; + } + else + { + /* Disable the PCCARD Bank by clearing the PBKEN bit in the PCR4 register */ + FSMC_Bank4->PCR4 &= PCR_PBKEN_Reset; + } +} + +/** + * @brief Enables or disables the FSMC NAND ECC feature. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @param NewState: new state of the FSMC NAND ECC feature. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_NANDECCCmd(uint32_t FSMC_Bank, FunctionalState NewState) +{ + assert_param(IS_FSMC_NAND_BANK(FSMC_Bank)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected NAND Bank ECC function by setting the ECCEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 |= PCR_ECCEN_Set; + } + else + { + FSMC_Bank3->PCR3 |= PCR_ECCEN_Set; + } + } + else + { + /* Disable the selected NAND Bank ECC function by clearing the ECCEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 &= PCR_ECCEN_Reset; + } + else + { + FSMC_Bank3->PCR3 &= PCR_ECCEN_Reset; + } + } +} + +/** + * @brief Returns the error correction code register value. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @retval The Error Correction Code (ECC) value. + */ +uint32_t FSMC_GetECC(uint32_t FSMC_Bank) +{ + uint32_t eccval = 0x00000000; + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + /* Get the ECCR2 register value */ + eccval = FSMC_Bank2->ECCR2; + } + else + { + /* Get the ECCR3 register value */ + eccval = FSMC_Bank3->ECCR3; + } + /* Return the error correction code value */ + return(eccval); +} + +/** + * @brief Enables or disables the specified FSMC interrupts. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_IT: specifies the FSMC interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. + * @arg FSMC_IT_Level: Level edge detection interrupt. + * @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. + * @param NewState: new state of the specified FSMC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_ITConfig(uint32_t FSMC_Bank, uint32_t FSMC_IT, FunctionalState NewState) +{ + assert_param(IS_FSMC_IT_BANK(FSMC_Bank)); + assert_param(IS_FSMC_IT(FSMC_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected FSMC_Bank2 interrupts */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->SR2 |= FSMC_IT; + } + /* Enable the selected FSMC_Bank3 interrupts */ + else if (FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 |= FSMC_IT; + } + /* Enable the selected FSMC_Bank4 interrupts */ + else + { + FSMC_Bank4->SR4 |= FSMC_IT; + } + } + else + { + /* Disable the selected FSMC_Bank2 interrupts */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + + FSMC_Bank2->SR2 &= (uint32_t)~FSMC_IT; + } + /* Disable the selected FSMC_Bank3 interrupts */ + else if (FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 &= (uint32_t)~FSMC_IT; + } + /* Disable the selected FSMC_Bank4 interrupts */ + else + { + FSMC_Bank4->SR4 &= (uint32_t)~FSMC_IT; + } + } +} + +/** + * @brief Checks whether the specified FSMC flag is set or not. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg FSMC_FLAG_RisingEdge: Rising egde detection Flag. + * @arg FSMC_FLAG_Level: Level detection Flag. + * @arg FSMC_FLAG_FallingEdge: Falling egde detection Flag. + * @arg FSMC_FLAG_FEMPT: Fifo empty Flag. + * @retval The new state of FSMC_FLAG (SET or RESET). + */ +FlagStatus FSMC_GetFlagStatus(uint32_t FSMC_Bank, uint32_t FSMC_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t tmpsr = 0x00000000; + + /* Check the parameters */ + assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank)); + assert_param(IS_FSMC_GET_FLAG(FSMC_FLAG)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + tmpsr = FSMC_Bank2->SR2; + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + tmpsr = FSMC_Bank3->SR3; + } + /* FSMC_Bank4_PCCARD*/ + else + { + tmpsr = FSMC_Bank4->SR4; + } + + /* Get the flag status */ + if ((tmpsr & FSMC_FLAG) != (uint16_t)RESET ) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @brief Clears the FSMC's pending flags. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg FSMC_FLAG_RisingEdge: Rising egde detection Flag. + * @arg FSMC_FLAG_Level: Level detection Flag. + * @arg FSMC_FLAG_FallingEdge: Falling egde detection Flag. + * @retval None + */ +void FSMC_ClearFlag(uint32_t FSMC_Bank, uint32_t FSMC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank)); + assert_param(IS_FSMC_CLEAR_FLAG(FSMC_FLAG)) ; + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->SR2 &= ~FSMC_FLAG; + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 &= ~FSMC_FLAG; + } + /* FSMC_Bank4_PCCARD*/ + else + { + FSMC_Bank4->SR4 &= ~FSMC_FLAG; + } +} + +/** + * @brief Checks whether the specified FSMC interrupt has occurred or not. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_IT: specifies the FSMC interrupt source to check. + * This parameter can be one of the following values: + * @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. + * @arg FSMC_IT_Level: Level edge detection interrupt. + * @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. + * @retval The new state of FSMC_IT (SET or RESET). + */ +ITStatus FSMC_GetITStatus(uint32_t FSMC_Bank, uint32_t FSMC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t tmpsr = 0x0, itstatus = 0x0, itenable = 0x0; + + /* Check the parameters */ + assert_param(IS_FSMC_IT_BANK(FSMC_Bank)); + assert_param(IS_FSMC_GET_IT(FSMC_IT)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + tmpsr = FSMC_Bank2->SR2; + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + tmpsr = FSMC_Bank3->SR3; + } + /* FSMC_Bank4_PCCARD*/ + else + { + tmpsr = FSMC_Bank4->SR4; + } + + itstatus = tmpsr & FSMC_IT; + + itenable = tmpsr & (FSMC_IT >> 3); + if ((itstatus != (uint32_t)RESET) && (itenable != (uint32_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the FSMC's interrupt pending bits. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_IT: specifies the interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. + * @arg FSMC_IT_Level: Level edge detection interrupt. + * @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. + * @retval None + */ +void FSMC_ClearITPendingBit(uint32_t FSMC_Bank, uint32_t FSMC_IT) +{ + /* Check the parameters */ + assert_param(IS_FSMC_IT_BANK(FSMC_Bank)); + assert_param(IS_FSMC_IT(FSMC_IT)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->SR2 &= ~(FSMC_IT >> 3); + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 &= ~(FSMC_IT >> 3); + } + /* FSMC_Bank4_PCCARD*/ + else + { + FSMC_Bank4->SR4 &= ~(FSMC_IT >> 3); + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c new file mode 100644 index 0000000..457ff11 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c @@ -0,0 +1,650 @@ +/** + ****************************************************************************** + * @file stm32f10x_gpio.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the GPIO firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_gpio.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup GPIO + * @brief GPIO driver modules + * @{ + */ + +/** @defgroup GPIO_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup GPIO_Private_Defines + * @{ + */ + +/* ------------ RCC registers bit address in the alias region ----------------*/ +#define AFIO_OFFSET (AFIO_BASE - PERIPH_BASE) + +/* --- EVENTCR Register -----*/ + +/* Alias word address of EVOE bit */ +#define EVCR_OFFSET (AFIO_OFFSET + 0x00) +#define EVOE_BitNumber ((uint8_t)0x07) +#define EVCR_EVOE_BB (PERIPH_BB_BASE + (EVCR_OFFSET * 32) + (EVOE_BitNumber * 4)) + + +/* --- MAPR Register ---*/ +/* Alias word address of MII_RMII_SEL bit */ +#define MAPR_OFFSET (AFIO_OFFSET + 0x04) +#define MII_RMII_SEL_BitNumber ((u8)0x17) +#define MAPR_MII_RMII_SEL_BB (PERIPH_BB_BASE + (MAPR_OFFSET * 32) + (MII_RMII_SEL_BitNumber * 4)) + + +#define EVCR_PORTPINCONFIG_MASK ((uint16_t)0xFF80) +#define LSB_MASK ((uint16_t)0xFFFF) +#define DBGAFR_POSITION_MASK ((uint32_t)0x000F0000) +#define DBGAFR_SWJCFG_MASK ((uint32_t)0xF0FFFFFF) +#define DBGAFR_LOCATION_MASK ((uint32_t)0x00200000) +#define DBGAFR_NUMBITS_MASK ((uint32_t)0x00100000) +/** + * @} + */ + +/** @defgroup GPIO_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup GPIO_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup GPIO_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup GPIO_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the GPIOx peripheral registers to their default reset values. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @retval None + */ +void GPIO_DeInit(GPIO_TypeDef* GPIOx) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + if (GPIOx == GPIOA) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, DISABLE); + } + else if (GPIOx == GPIOB) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, DISABLE); + } + else if (GPIOx == GPIOC) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, DISABLE); + } + else if (GPIOx == GPIOD) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, DISABLE); + } + else if (GPIOx == GPIOE) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, DISABLE); + } + else if (GPIOx == GPIOF) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, DISABLE); + } + else + { + if (GPIOx == GPIOG) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, DISABLE); + } + } +} + +/** + * @brief Deinitializes the Alternate Functions (remap, event control + * and EXTI configuration) registers to their default reset values. + * @param None + * @retval None + */ +void GPIO_AFIODeInit(void) +{ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, DISABLE); +} + +/** + * @brief Initializes the GPIOx peripheral according to the specified + * parameters in the GPIO_InitStruct. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure that + * contains the configuration information for the specified GPIO peripheral. + * @retval None + */ +void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct) +{ + uint32_t currentmode = 0x00, currentpin = 0x00, pinpos = 0x00, pos = 0x00; + uint32_t tmpreg = 0x00, pinmask = 0x00; + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_MODE(GPIO_InitStruct->GPIO_Mode)); + assert_param(IS_GPIO_PIN(GPIO_InitStruct->GPIO_Pin)); + +/*---------------------------- GPIO Mode Configuration -----------------------*/ + currentmode = ((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x0F); + if ((((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x10)) != 0x00) + { + /* Check the parameters */ + assert_param(IS_GPIO_SPEED(GPIO_InitStruct->GPIO_Speed)); + /* Output mode */ + currentmode |= (uint32_t)GPIO_InitStruct->GPIO_Speed; + } +/*---------------------------- GPIO CRL Configuration ------------------------*/ + /* Configure the eight low port pins */ + if (((uint32_t)GPIO_InitStruct->GPIO_Pin & ((uint32_t)0x00FF)) != 0x00) + { + tmpreg = GPIOx->CRL; + for (pinpos = 0x00; pinpos < 0x08; pinpos++) + { + pos = ((uint32_t)0x01) << pinpos; + /* Get the port pins position */ + currentpin = (GPIO_InitStruct->GPIO_Pin) & pos; + if (currentpin == pos) + { + pos = pinpos << 2; + /* Clear the corresponding low control register bits */ + pinmask = ((uint32_t)0x0F) << pos; + tmpreg &= ~pinmask; + /* Write the mode configuration in the corresponding bits */ + tmpreg |= (currentmode << pos); + /* Reset the corresponding ODR bit */ + if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD) + { + GPIOx->BRR = (((uint32_t)0x01) << pinpos); + } + else + { + /* Set the corresponding ODR bit */ + if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU) + { + GPIOx->BSRR = (((uint32_t)0x01) << pinpos); + } + } + } + } + GPIOx->CRL = tmpreg; + } +/*---------------------------- GPIO CRH Configuration ------------------------*/ + /* Configure the eight high port pins */ + if (GPIO_InitStruct->GPIO_Pin > 0x00FF) + { + tmpreg = GPIOx->CRH; + for (pinpos = 0x00; pinpos < 0x08; pinpos++) + { + pos = (((uint32_t)0x01) << (pinpos + 0x08)); + /* Get the port pins position */ + currentpin = ((GPIO_InitStruct->GPIO_Pin) & pos); + if (currentpin == pos) + { + pos = pinpos << 2; + /* Clear the corresponding high control register bits */ + pinmask = ((uint32_t)0x0F) << pos; + tmpreg &= ~pinmask; + /* Write the mode configuration in the corresponding bits */ + tmpreg |= (currentmode << pos); + /* Reset the corresponding ODR bit */ + if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD) + { + GPIOx->BRR = (((uint32_t)0x01) << (pinpos + 0x08)); + } + /* Set the corresponding ODR bit */ + if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU) + { + GPIOx->BSRR = (((uint32_t)0x01) << (pinpos + 0x08)); + } + } + } + GPIOx->CRH = tmpreg; + } +} + +/** + * @brief Fills each GPIO_InitStruct member with its default value. + * @param GPIO_InitStruct : pointer to a GPIO_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct) +{ + /* Reset GPIO init structure parameters values */ + GPIO_InitStruct->GPIO_Pin = GPIO_Pin_All; + GPIO_InitStruct->GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStruct->GPIO_Mode = GPIO_Mode_IN_FLOATING; +} + +/** + * @brief Reads the specified input port pin. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to read. + * This parameter can be GPIO_Pin_x where x can be (0..15). + * @retval The input port pin value. + */ +uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint8_t bitstatus = 0x00; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + + if ((GPIOx->IDR & GPIO_Pin) != (uint32_t)Bit_RESET) + { + bitstatus = (uint8_t)Bit_SET; + } + else + { + bitstatus = (uint8_t)Bit_RESET; + } + return bitstatus; +} + +/** + * @brief Reads the specified GPIO input data port. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @retval GPIO input data port value. + */ +uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + return ((uint16_t)GPIOx->IDR); +} + +/** + * @brief Reads the specified output data port bit. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to read. + * This parameter can be GPIO_Pin_x where x can be (0..15). + * @retval The output port pin value. + */ +uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint8_t bitstatus = 0x00; + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + + if ((GPIOx->ODR & GPIO_Pin) != (uint32_t)Bit_RESET) + { + bitstatus = (uint8_t)Bit_SET; + } + else + { + bitstatus = (uint8_t)Bit_RESET; + } + return bitstatus; +} + +/** + * @brief Reads the specified GPIO output data port. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @retval GPIO output data port value. + */ +uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + return ((uint16_t)GPIOx->ODR); +} + +/** + * @brief Sets the selected data port bits. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bits to be written. + * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). + * @retval None + */ +void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + GPIOx->BSRR = GPIO_Pin; +} + +/** + * @brief Clears the selected data port bits. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bits to be written. + * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). + * @retval None + */ +void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + GPIOx->BRR = GPIO_Pin; +} + +/** + * @brief Sets or clears the selected data port bit. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to be written. + * This parameter can be one of GPIO_Pin_x where x can be (0..15). + * @param BitVal: specifies the value to be written to the selected bit. + * This parameter can be one of the BitAction enum values: + * @arg Bit_RESET: to clear the port pin + * @arg Bit_SET: to set the port pin + * @retval None + */ +void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + assert_param(IS_GPIO_BIT_ACTION(BitVal)); + + if (BitVal != Bit_RESET) + { + GPIOx->BSRR = GPIO_Pin; + } + else + { + GPIOx->BRR = GPIO_Pin; + } +} + +/** + * @brief Writes data to the specified GPIO data port. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param PortVal: specifies the value to be written to the port output data register. + * @retval None + */ +void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + GPIOx->ODR = PortVal; +} + +/** + * @brief Locks GPIO Pins configuration registers. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to be written. + * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). + * @retval None + */ +void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint32_t tmp = 0x00010000; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + tmp |= GPIO_Pin; + /* Set LCKK bit */ + GPIOx->LCKR = tmp; + /* Reset LCKK bit */ + GPIOx->LCKR = GPIO_Pin; + /* Set LCKK bit */ + GPIOx->LCKR = tmp; + /* Read LCKK bit*/ + tmp = GPIOx->LCKR; + /* Read LCKK bit*/ + tmp = GPIOx->LCKR; +} + +/** + * @brief Selects the GPIO pin used as Event output. + * @param GPIO_PortSource: selects the GPIO port to be used as source + * for Event output. + * This parameter can be GPIO_PortSourceGPIOx where x can be (A..E). + * @param GPIO_PinSource: specifies the pin for the Event output. + * This parameter can be GPIO_PinSourcex where x can be (0..15). + * @retval None + */ +void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource) +{ + uint32_t tmpreg = 0x00; + /* Check the parameters */ + assert_param(IS_GPIO_EVENTOUT_PORT_SOURCE(GPIO_PortSource)); + assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource)); + + tmpreg = AFIO->EVCR; + /* Clear the PORT[6:4] and PIN[3:0] bits */ + tmpreg &= EVCR_PORTPINCONFIG_MASK; + tmpreg |= (uint32_t)GPIO_PortSource << 0x04; + tmpreg |= GPIO_PinSource; + AFIO->EVCR = tmpreg; +} + +/** + * @brief Enables or disables the Event Output. + * @param NewState: new state of the Event output. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void GPIO_EventOutputCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) EVCR_EVOE_BB = (uint32_t)NewState; +} + +/** + * @brief Changes the mapping of the specified pin. + * @param GPIO_Remap: selects the pin to remap. + * This parameter can be one of the following values: + * @arg GPIO_Remap_SPI1 : SPI1 Alternate Function mapping + * @arg GPIO_Remap_I2C1 : I2C1 Alternate Function mapping + * @arg GPIO_Remap_USART1 : USART1 Alternate Function mapping + * @arg GPIO_Remap_USART2 : USART2 Alternate Function mapping + * @arg GPIO_PartialRemap_USART3 : USART3 Partial Alternate Function mapping + * @arg GPIO_FullRemap_USART3 : USART3 Full Alternate Function mapping + * @arg GPIO_PartialRemap_TIM1 : TIM1 Partial Alternate Function mapping + * @arg GPIO_FullRemap_TIM1 : TIM1 Full Alternate Function mapping + * @arg GPIO_PartialRemap1_TIM2 : TIM2 Partial1 Alternate Function mapping + * @arg GPIO_PartialRemap2_TIM2 : TIM2 Partial2 Alternate Function mapping + * @arg GPIO_FullRemap_TIM2 : TIM2 Full Alternate Function mapping + * @arg GPIO_PartialRemap_TIM3 : TIM3 Partial Alternate Function mapping + * @arg GPIO_FullRemap_TIM3 : TIM3 Full Alternate Function mapping + * @arg GPIO_Remap_TIM4 : TIM4 Alternate Function mapping + * @arg GPIO_Remap1_CAN1 : CAN1 Alternate Function mapping + * @arg GPIO_Remap2_CAN1 : CAN1 Alternate Function mapping + * @arg GPIO_Remap_PD01 : PD01 Alternate Function mapping + * @arg GPIO_Remap_TIM5CH4_LSI : LSI connected to TIM5 Channel4 input capture for calibration + * @arg GPIO_Remap_ADC1_ETRGINJ : ADC1 External Trigger Injected Conversion remapping + * @arg GPIO_Remap_ADC1_ETRGREG : ADC1 External Trigger Regular Conversion remapping + * @arg GPIO_Remap_ADC2_ETRGINJ : ADC2 External Trigger Injected Conversion remapping + * @arg GPIO_Remap_ADC2_ETRGREG : ADC2 External Trigger Regular Conversion remapping + * @arg GPIO_Remap_ETH : Ethernet remapping (only for Connectivity line devices) + * @arg GPIO_Remap_CAN2 : CAN2 remapping (only for Connectivity line devices) + * @arg GPIO_Remap_SWJ_NoJTRST : Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST + * @arg GPIO_Remap_SWJ_JTAGDisable : JTAG-DP Disabled and SW-DP Enabled + * @arg GPIO_Remap_SWJ_Disable : Full SWJ Disabled (JTAG-DP + SW-DP) + * @arg GPIO_Remap_SPI3 : SPI3/I2S3 Alternate Function mapping (only for Connectivity line devices) + * When the SPI3/I2S3 is remapped using this function, the SWJ is configured + * to Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST. + * @arg GPIO_Remap_TIM2ITR1_PTP_SOF : Ethernet PTP output or USB OTG SOF (Start of Frame) connected + * to TIM2 Internal Trigger 1 for calibration (only for Connectivity line devices) + * If the GPIO_Remap_TIM2ITR1_PTP_SOF is enabled the TIM2 ITR1 is connected to + * Ethernet PTP output. When Reset TIM2 ITR1 is connected to USB OTG SOF output. + * @arg GPIO_Remap_PTP_PPS : Ethernet MAC PPS_PTS output on PB05 (only for Connectivity line devices) + * @arg GPIO_Remap_TIM15 : TIM15 Alternate Function mapping (only for Value line devices) + * @arg GPIO_Remap_TIM16 : TIM16 Alternate Function mapping (only for Value line devices) + * @arg GPIO_Remap_TIM17 : TIM17 Alternate Function mapping (only for Value line devices) + * @arg GPIO_Remap_CEC : CEC Alternate Function mapping (only for Value line devices) + * @arg GPIO_Remap_TIM1_DMA : TIM1 DMA requests mapping (only for Value line devices) + * @arg GPIO_Remap_TIM9 : TIM9 Alternate Function mapping (only for XL-density devices) + * @arg GPIO_Remap_TIM10 : TIM10 Alternate Function mapping (only for XL-density devices) + * @arg GPIO_Remap_TIM11 : TIM11 Alternate Function mapping (only for XL-density devices) + * @arg GPIO_Remap_TIM13 : TIM13 Alternate Function mapping (only for High density Value line and XL-density devices) + * @arg GPIO_Remap_TIM14 : TIM14 Alternate Function mapping (only for High density Value line and XL-density devices) + * @arg GPIO_Remap_FSMC_NADV : FSMC_NADV Alternate Function mapping (only for High density Value line and XL-density devices) + * @arg GPIO_Remap_TIM67_DAC_DMA : TIM6/TIM7 and DAC DMA requests remapping (only for High density Value line devices) + * @arg GPIO_Remap_TIM12 : TIM12 Alternate Function mapping (only for High density Value line devices) + * @arg GPIO_Remap_MISC : Miscellaneous Remap (DMA2 Channel5 Position and DAC Trigger remapping, + * only for High density Value line devices) + * @param NewState: new state of the port pin remapping. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void GPIO_PinRemapConfig(uint32_t GPIO_Remap, FunctionalState NewState) +{ + uint32_t tmp = 0x00, tmp1 = 0x00, tmpreg = 0x00, tmpmask = 0x00; + + /* Check the parameters */ + assert_param(IS_GPIO_REMAP(GPIO_Remap)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if((GPIO_Remap & 0x80000000) == 0x80000000) + { + tmpreg = AFIO->MAPR2; + } + else + { + tmpreg = AFIO->MAPR; + } + + tmpmask = (GPIO_Remap & DBGAFR_POSITION_MASK) >> 0x10; + tmp = GPIO_Remap & LSB_MASK; + + if ((GPIO_Remap & (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) == (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) + { + tmpreg &= DBGAFR_SWJCFG_MASK; + AFIO->MAPR &= DBGAFR_SWJCFG_MASK; + } + else if ((GPIO_Remap & DBGAFR_NUMBITS_MASK) == DBGAFR_NUMBITS_MASK) + { + tmp1 = ((uint32_t)0x03) << tmpmask; + tmpreg &= ~tmp1; + tmpreg |= ~DBGAFR_SWJCFG_MASK; + } + else + { + tmpreg &= ~(tmp << ((GPIO_Remap >> 0x15)*0x10)); + tmpreg |= ~DBGAFR_SWJCFG_MASK; + } + + if (NewState != DISABLE) + { + tmpreg |= (tmp << ((GPIO_Remap >> 0x15)*0x10)); + } + + if((GPIO_Remap & 0x80000000) == 0x80000000) + { + AFIO->MAPR2 = tmpreg; + } + else + { + AFIO->MAPR = tmpreg; + } +} + +/** + * @brief Selects the GPIO pin used as EXTI Line. + * @param GPIO_PortSource: selects the GPIO port to be used as source for EXTI lines. + * This parameter can be GPIO_PortSourceGPIOx where x can be (A..G). + * @param GPIO_PinSource: specifies the EXTI line to be configured. + * This parameter can be GPIO_PinSourcex where x can be (0..15). + * @retval None + */ +void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource) +{ + uint32_t tmp = 0x00; + /* Check the parameters */ + assert_param(IS_GPIO_EXTI_PORT_SOURCE(GPIO_PortSource)); + assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource)); + + tmp = ((uint32_t)0x0F) << (0x04 * (GPIO_PinSource & (uint8_t)0x03)); + AFIO->EXTICR[GPIO_PinSource >> 0x02] &= ~tmp; + AFIO->EXTICR[GPIO_PinSource >> 0x02] |= (((uint32_t)GPIO_PortSource) << (0x04 * (GPIO_PinSource & (uint8_t)0x03))); +} + +/** + * @brief Selects the Ethernet media interface. + * @note This function applies only to STM32 Connectivity line devices. + * @param GPIO_ETH_MediaInterface: specifies the Media Interface mode. + * This parameter can be one of the following values: + * @arg GPIO_ETH_MediaInterface_MII: MII mode + * @arg GPIO_ETH_MediaInterface_RMII: RMII mode + * @retval None + */ +void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface) +{ + assert_param(IS_GPIO_ETH_MEDIA_INTERFACE(GPIO_ETH_MediaInterface)); + + /* Configure MII_RMII selection bit */ + *(__IO uint32_t *) MAPR_MII_RMII_SEL_BB = GPIO_ETH_MediaInterface; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c new file mode 100644 index 0000000..4ea321c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c @@ -0,0 +1,1331 @@ +/** + ****************************************************************************** + * @file stm32f10x_i2c.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the I2C firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_i2c.h" +#include "stm32f10x_rcc.h" + + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup I2C + * @brief I2C driver modules + * @{ + */ + +/** @defgroup I2C_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup I2C_Private_Defines + * @{ + */ + +/* I2C SPE mask */ +#define CR1_PE_Set ((uint16_t)0x0001) +#define CR1_PE_Reset ((uint16_t)0xFFFE) + +/* I2C START mask */ +#define CR1_START_Set ((uint16_t)0x0100) +#define CR1_START_Reset ((uint16_t)0xFEFF) + +/* I2C STOP mask */ +#define CR1_STOP_Set ((uint16_t)0x0200) +#define CR1_STOP_Reset ((uint16_t)0xFDFF) + +/* I2C ACK mask */ +#define CR1_ACK_Set ((uint16_t)0x0400) +#define CR1_ACK_Reset ((uint16_t)0xFBFF) + +/* I2C ENGC mask */ +#define CR1_ENGC_Set ((uint16_t)0x0040) +#define CR1_ENGC_Reset ((uint16_t)0xFFBF) + +/* I2C SWRST mask */ +#define CR1_SWRST_Set ((uint16_t)0x8000) +#define CR1_SWRST_Reset ((uint16_t)0x7FFF) + +/* I2C PEC mask */ +#define CR1_PEC_Set ((uint16_t)0x1000) +#define CR1_PEC_Reset ((uint16_t)0xEFFF) + +/* I2C ENPEC mask */ +#define CR1_ENPEC_Set ((uint16_t)0x0020) +#define CR1_ENPEC_Reset ((uint16_t)0xFFDF) + +/* I2C ENARP mask */ +#define CR1_ENARP_Set ((uint16_t)0x0010) +#define CR1_ENARP_Reset ((uint16_t)0xFFEF) + +/* I2C NOSTRETCH mask */ +#define CR1_NOSTRETCH_Set ((uint16_t)0x0080) +#define CR1_NOSTRETCH_Reset ((uint16_t)0xFF7F) + +/* I2C registers Masks */ +#define CR1_CLEAR_Mask ((uint16_t)0xFBF5) + +/* I2C DMAEN mask */ +#define CR2_DMAEN_Set ((uint16_t)0x0800) +#define CR2_DMAEN_Reset ((uint16_t)0xF7FF) + +/* I2C LAST mask */ +#define CR2_LAST_Set ((uint16_t)0x1000) +#define CR2_LAST_Reset ((uint16_t)0xEFFF) + +/* I2C FREQ mask */ +#define CR2_FREQ_Reset ((uint16_t)0xFFC0) + +/* I2C ADD0 mask */ +#define OAR1_ADD0_Set ((uint16_t)0x0001) +#define OAR1_ADD0_Reset ((uint16_t)0xFFFE) + +/* I2C ENDUAL mask */ +#define OAR2_ENDUAL_Set ((uint16_t)0x0001) +#define OAR2_ENDUAL_Reset ((uint16_t)0xFFFE) + +/* I2C ADD2 mask */ +#define OAR2_ADD2_Reset ((uint16_t)0xFF01) + +/* I2C F/S mask */ +#define CCR_FS_Set ((uint16_t)0x8000) + +/* I2C CCR mask */ +#define CCR_CCR_Set ((uint16_t)0x0FFF) + +/* I2C FLAG mask */ +#define FLAG_Mask ((uint32_t)0x00FFFFFF) + +/* I2C Interrupt Enable mask */ +#define ITEN_Mask ((uint32_t)0x07000000) + +/** + * @} + */ + +/** @defgroup I2C_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup I2C_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup I2C_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup I2C_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the I2Cx peripheral registers to their default reset values. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @retval None + */ +void I2C_DeInit(I2C_TypeDef* I2Cx) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + if (I2Cx == I2C1) + { + /* Enable I2C1 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, ENABLE); + /* Release I2C1 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, DISABLE); + } + else + { + /* Enable I2C2 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, ENABLE); + /* Release I2C2 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, DISABLE); + } +} + +/** + * @brief Initializes the I2Cx peripheral according to the specified + * parameters in the I2C_InitStruct. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_InitStruct: pointer to a I2C_InitTypeDef structure that + * contains the configuration information for the specified I2C peripheral. + * @retval None + */ +void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct) +{ + uint16_t tmpreg = 0, freqrange = 0; + uint16_t result = 0x04; + uint32_t pclk1 = 8000000; + RCC_ClocksTypeDef rcc_clocks; + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_CLOCK_SPEED(I2C_InitStruct->I2C_ClockSpeed)); + assert_param(IS_I2C_MODE(I2C_InitStruct->I2C_Mode)); + assert_param(IS_I2C_DUTY_CYCLE(I2C_InitStruct->I2C_DutyCycle)); + assert_param(IS_I2C_OWN_ADDRESS1(I2C_InitStruct->I2C_OwnAddress1)); + assert_param(IS_I2C_ACK_STATE(I2C_InitStruct->I2C_Ack)); + assert_param(IS_I2C_ACKNOWLEDGE_ADDRESS(I2C_InitStruct->I2C_AcknowledgedAddress)); + +/*---------------------------- I2Cx CR2 Configuration ------------------------*/ + /* Get the I2Cx CR2 value */ + tmpreg = I2Cx->CR2; + /* Clear frequency FREQ[5:0] bits */ + tmpreg &= CR2_FREQ_Reset; + /* Get pclk1 frequency value */ + RCC_GetClocksFreq(&rcc_clocks); + pclk1 = rcc_clocks.PCLK1_Frequency; + /* Set frequency bits depending on pclk1 value */ + freqrange = (uint16_t)(pclk1 / 1000000); + tmpreg |= freqrange; + /* Write to I2Cx CR2 */ + I2Cx->CR2 = tmpreg; + +/*---------------------------- I2Cx CCR Configuration ------------------------*/ + /* Disable the selected I2C peripheral to configure TRISE */ + I2Cx->CR1 &= CR1_PE_Reset; + /* Reset tmpreg value */ + /* Clear F/S, DUTY and CCR[11:0] bits */ + tmpreg = 0; + + /* Configure speed in standard mode */ + if (I2C_InitStruct->I2C_ClockSpeed <= 100000) + { + /* Standard mode speed calculate */ + result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed << 1)); + /* Test if CCR value is under 0x4*/ + if (result < 0x04) + { + /* Set minimum allowed value */ + result = 0x04; + } + /* Set speed value for standard mode */ + tmpreg |= result; + /* Set Maximum Rise Time for standard mode */ + I2Cx->TRISE = freqrange + 1; + } + /* Configure speed in fast mode */ + else /*(I2C_InitStruct->I2C_ClockSpeed <= 400000)*/ + { + if (I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_2) + { + /* Fast mode speed calculate: Tlow/Thigh = 2 */ + result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 3)); + } + else /*I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_16_9*/ + { + /* Fast mode speed calculate: Tlow/Thigh = 16/9 */ + result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 25)); + /* Set DUTY bit */ + result |= I2C_DutyCycle_16_9; + } + + /* Test if CCR value is under 0x1*/ + if ((result & CCR_CCR_Set) == 0) + { + /* Set minimum allowed value */ + result |= (uint16_t)0x0001; + } + /* Set speed value and set F/S bit for fast mode */ + tmpreg |= (uint16_t)(result | CCR_FS_Set); + /* Set Maximum Rise Time for fast mode */ + I2Cx->TRISE = (uint16_t)(((freqrange * (uint16_t)300) / (uint16_t)1000) + (uint16_t)1); + } + + /* Write to I2Cx CCR */ + I2Cx->CCR = tmpreg; + /* Enable the selected I2C peripheral */ + I2Cx->CR1 |= CR1_PE_Set; + +/*---------------------------- I2Cx CR1 Configuration ------------------------*/ + /* Get the I2Cx CR1 value */ + tmpreg = I2Cx->CR1; + /* Clear ACK, SMBTYPE and SMBUS bits */ + tmpreg &= CR1_CLEAR_Mask; + /* Configure I2Cx: mode and acknowledgement */ + /* Set SMBTYPE and SMBUS bits according to I2C_Mode value */ + /* Set ACK bit according to I2C_Ack value */ + tmpreg |= (uint16_t)((uint32_t)I2C_InitStruct->I2C_Mode | I2C_InitStruct->I2C_Ack); + /* Write to I2Cx CR1 */ + I2Cx->CR1 = tmpreg; + +/*---------------------------- I2Cx OAR1 Configuration -----------------------*/ + /* Set I2Cx Own Address1 and acknowledged address */ + I2Cx->OAR1 = (I2C_InitStruct->I2C_AcknowledgedAddress | I2C_InitStruct->I2C_OwnAddress1); +} + +/** + * @brief Fills each I2C_InitStruct member with its default value. + * @param I2C_InitStruct: pointer to an I2C_InitTypeDef structure which will be initialized. + * @retval None + */ +void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct) +{ +/*---------------- Reset I2C init structure parameters values ----------------*/ + /* initialize the I2C_ClockSpeed member */ + I2C_InitStruct->I2C_ClockSpeed = 5000; + /* Initialize the I2C_Mode member */ + I2C_InitStruct->I2C_Mode = I2C_Mode_I2C; + /* Initialize the I2C_DutyCycle member */ + I2C_InitStruct->I2C_DutyCycle = I2C_DutyCycle_2; + /* Initialize the I2C_OwnAddress1 member */ + I2C_InitStruct->I2C_OwnAddress1 = 0; + /* Initialize the I2C_Ack member */ + I2C_InitStruct->I2C_Ack = I2C_Ack_Disable; + /* Initialize the I2C_AcknowledgedAddress member */ + I2C_InitStruct->I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; +} + +/** + * @brief Enables or disables the specified I2C peripheral. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C peripheral */ + I2Cx->CR1 |= CR1_PE_Set; + } + else + { + /* Disable the selected I2C peripheral */ + I2Cx->CR1 &= CR1_PE_Reset; + } +} + +/** + * @brief Enables or disables the specified I2C DMA requests. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C DMA transfer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C DMA requests */ + I2Cx->CR2 |= CR2_DMAEN_Set; + } + else + { + /* Disable the selected I2C DMA requests */ + I2Cx->CR2 &= CR2_DMAEN_Reset; + } +} + +/** + * @brief Specifies if the next DMA transfer will be the last one. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C DMA last transfer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Next DMA transfer is the last transfer */ + I2Cx->CR2 |= CR2_LAST_Set; + } + else + { + /* Next DMA transfer is not the last transfer */ + I2Cx->CR2 &= CR2_LAST_Reset; + } +} + +/** + * @brief Generates I2Cx communication START condition. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C START condition generation. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Generate a START condition */ + I2Cx->CR1 |= CR1_START_Set; + } + else + { + /* Disable the START condition generation */ + I2Cx->CR1 &= CR1_START_Reset; + } +} + +/** + * @brief Generates I2Cx communication STOP condition. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C STOP condition generation. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Generate a STOP condition */ + I2Cx->CR1 |= CR1_STOP_Set; + } + else + { + /* Disable the STOP condition generation */ + I2Cx->CR1 &= CR1_STOP_Reset; + } +} + +/** + * @brief Enables or disables the specified I2C acknowledge feature. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C Acknowledgement. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the acknowledgement */ + I2Cx->CR1 |= CR1_ACK_Set; + } + else + { + /* Disable the acknowledgement */ + I2Cx->CR1 &= CR1_ACK_Reset; + } +} + +/** + * @brief Configures the specified I2C own address2. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Address: specifies the 7bit I2C own address2. + * @retval None. + */ +void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address) +{ + uint16_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + /* Get the old register value */ + tmpreg = I2Cx->OAR2; + + /* Reset I2Cx Own address2 bit [7:1] */ + tmpreg &= OAR2_ADD2_Reset; + + /* Set I2Cx Own address2 */ + tmpreg |= (uint16_t)((uint16_t)Address & (uint16_t)0x00FE); + + /* Store the new register value */ + I2Cx->OAR2 = tmpreg; +} + +/** + * @brief Enables or disables the specified I2C dual addressing mode. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C dual addressing mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable dual addressing mode */ + I2Cx->OAR2 |= OAR2_ENDUAL_Set; + } + else + { + /* Disable dual addressing mode */ + I2Cx->OAR2 &= OAR2_ENDUAL_Reset; + } +} + +/** + * @brief Enables or disables the specified I2C general call feature. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C General call. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable generall call */ + I2Cx->CR1 |= CR1_ENGC_Set; + } + else + { + /* Disable generall call */ + I2Cx->CR1 &= CR1_ENGC_Reset; + } +} + +/** + * @brief Enables or disables the specified I2C interrupts. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_IT: specifies the I2C interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg I2C_IT_BUF: Buffer interrupt mask + * @arg I2C_IT_EVT: Event interrupt mask + * @arg I2C_IT_ERR: Error interrupt mask + * @param NewState: new state of the specified I2C interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_I2C_CONFIG_IT(I2C_IT)); + + if (NewState != DISABLE) + { + /* Enable the selected I2C interrupts */ + I2Cx->CR2 |= I2C_IT; + } + else + { + /* Disable the selected I2C interrupts */ + I2Cx->CR2 &= (uint16_t)~I2C_IT; + } +} + +/** + * @brief Sends a data byte through the I2Cx peripheral. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Data: Byte to be transmitted.. + * @retval None + */ +void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + /* Write in the DR register the data to be sent */ + I2Cx->DR = Data; +} + +/** + * @brief Returns the most recent received data by the I2Cx peripheral. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @retval The value of the received data. + */ +uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + /* Return the data in the DR register */ + return (uint8_t)I2Cx->DR; +} + +/** + * @brief Transmits the address byte to select the slave device. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Address: specifies the slave address which will be transmitted + * @param I2C_Direction: specifies whether the I2C device will be a + * Transmitter or a Receiver. This parameter can be one of the following values + * @arg I2C_Direction_Transmitter: Transmitter mode + * @arg I2C_Direction_Receiver: Receiver mode + * @retval None. + */ +void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_DIRECTION(I2C_Direction)); + /* Test on the direction to set/reset the read/write bit */ + if (I2C_Direction != I2C_Direction_Transmitter) + { + /* Set the address bit0 for read */ + Address |= OAR1_ADD0_Set; + } + else + { + /* Reset the address bit0 for write */ + Address &= OAR1_ADD0_Reset; + } + /* Send the address */ + I2Cx->DR = Address; +} + +/** + * @brief Reads the specified I2C register and returns its value. + * @param I2C_Register: specifies the register to read. + * This parameter can be one of the following values: + * @arg I2C_Register_CR1: CR1 register. + * @arg I2C_Register_CR2: CR2 register. + * @arg I2C_Register_OAR1: OAR1 register. + * @arg I2C_Register_OAR2: OAR2 register. + * @arg I2C_Register_DR: DR register. + * @arg I2C_Register_SR1: SR1 register. + * @arg I2C_Register_SR2: SR2 register. + * @arg I2C_Register_CCR: CCR register. + * @arg I2C_Register_TRISE: TRISE register. + * @retval The value of the read register. + */ +uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_REGISTER(I2C_Register)); + + tmp = (uint32_t) I2Cx; + tmp += I2C_Register; + + /* Return the selected register value */ + return (*(__IO uint16_t *) tmp); +} + +/** + * @brief Enables or disables the specified I2C software reset. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C software reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Peripheral under reset */ + I2Cx->CR1 |= CR1_SWRST_Set; + } + else + { + /* Peripheral not under reset */ + I2Cx->CR1 &= CR1_SWRST_Reset; + } +} + +/** + * @brief Selects the specified I2C NACK position in master receiver mode. + * This function is useful in I2C Master Receiver mode when the number + * of data to be received is equal to 2. In this case, this function + * should be called (with parameter I2C_NACKPosition_Next) before data + * reception starts,as described in the 2-byte reception procedure + * recommended in Reference Manual in Section: Master receiver. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_NACKPosition: specifies the NACK position. + * This parameter can be one of the following values: + * @arg I2C_NACKPosition_Next: indicates that the next byte will be the last + * received byte. + * @arg I2C_NACKPosition_Current: indicates that current byte is the last + * received byte. + * + * @note This function configures the same bit (POS) as I2C_PECPositionConfig() + * but is intended to be used in I2C mode while I2C_PECPositionConfig() + * is intended to used in SMBUS mode. + * + * @retval None + */ +void I2C_NACKPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_NACKPosition) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_NACK_POSITION(I2C_NACKPosition)); + + /* Check the input parameter */ + if (I2C_NACKPosition == I2C_NACKPosition_Next) + { + /* Next byte in shift register is the last received byte */ + I2Cx->CR1 |= I2C_NACKPosition_Next; + } + else + { + /* Current byte in shift register is the last received byte */ + I2Cx->CR1 &= I2C_NACKPosition_Current; + } +} + +/** + * @brief Drives the SMBusAlert pin high or low for the specified I2C. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_SMBusAlert: specifies SMBAlert pin level. + * This parameter can be one of the following values: + * @arg I2C_SMBusAlert_Low: SMBAlert pin driven low + * @arg I2C_SMBusAlert_High: SMBAlert pin driven high + * @retval None + */ +void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_SMBUS_ALERT(I2C_SMBusAlert)); + if (I2C_SMBusAlert == I2C_SMBusAlert_Low) + { + /* Drive the SMBusAlert pin Low */ + I2Cx->CR1 |= I2C_SMBusAlert_Low; + } + else + { + /* Drive the SMBusAlert pin High */ + I2Cx->CR1 &= I2C_SMBusAlert_High; + } +} + +/** + * @brief Enables or disables the specified I2C PEC transfer. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C PEC transmission. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C PEC transmission */ + I2Cx->CR1 |= CR1_PEC_Set; + } + else + { + /* Disable the selected I2C PEC transmission */ + I2Cx->CR1 &= CR1_PEC_Reset; + } +} + +/** + * @brief Selects the specified I2C PEC position. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_PECPosition: specifies the PEC position. + * This parameter can be one of the following values: + * @arg I2C_PECPosition_Next: indicates that the next byte is PEC + * @arg I2C_PECPosition_Current: indicates that current byte is PEC + * + * @note This function configures the same bit (POS) as I2C_NACKPositionConfig() + * but is intended to be used in SMBUS mode while I2C_NACKPositionConfig() + * is intended to used in I2C mode. + * + * @retval None + */ +void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_PEC_POSITION(I2C_PECPosition)); + if (I2C_PECPosition == I2C_PECPosition_Next) + { + /* Next byte in shift register is PEC */ + I2Cx->CR1 |= I2C_PECPosition_Next; + } + else + { + /* Current byte in shift register is PEC */ + I2Cx->CR1 &= I2C_PECPosition_Current; + } +} + +/** + * @brief Enables or disables the PEC value calculation of the transferred bytes. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx PEC value calculation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C PEC calculation */ + I2Cx->CR1 |= CR1_ENPEC_Set; + } + else + { + /* Disable the selected I2C PEC calculation */ + I2Cx->CR1 &= CR1_ENPEC_Reset; + } +} + +/** + * @brief Returns the PEC value for the specified I2C. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @retval The PEC value. + */ +uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + /* Return the selected I2C PEC value */ + return ((I2Cx->SR2) >> 8); +} + +/** + * @brief Enables or disables the specified I2C ARP. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx ARP. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C ARP */ + I2Cx->CR1 |= CR1_ENARP_Set; + } + else + { + /* Disable the selected I2C ARP */ + I2Cx->CR1 &= CR1_ENARP_Reset; + } +} + +/** + * @brief Enables or disables the specified I2C Clock stretching. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx Clock stretching. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState == DISABLE) + { + /* Enable the selected I2C Clock stretching */ + I2Cx->CR1 |= CR1_NOSTRETCH_Set; + } + else + { + /* Disable the selected I2C Clock stretching */ + I2Cx->CR1 &= CR1_NOSTRETCH_Reset; + } +} + +/** + * @brief Selects the specified I2C fast mode duty cycle. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_DutyCycle: specifies the fast mode duty cycle. + * This parameter can be one of the following values: + * @arg I2C_DutyCycle_2: I2C fast mode Tlow/Thigh = 2 + * @arg I2C_DutyCycle_16_9: I2C fast mode Tlow/Thigh = 16/9 + * @retval None + */ +void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_DUTY_CYCLE(I2C_DutyCycle)); + if (I2C_DutyCycle != I2C_DutyCycle_16_9) + { + /* I2C fast mode Tlow/Thigh=2 */ + I2Cx->CCR &= I2C_DutyCycle_2; + } + else + { + /* I2C fast mode Tlow/Thigh=16/9 */ + I2Cx->CCR |= I2C_DutyCycle_16_9; + } +} + + + +/** + * @brief + **************************************************************************************** + * + * I2C State Monitoring Functions + * + **************************************************************************************** + * This I2C driver provides three different ways for I2C state monitoring + * depending on the application requirements and constraints: + * + * + * 1) Basic state monitoring: + * Using I2C_CheckEvent() function: + * It compares the status registers (SR1 and SR2) content to a given event + * (can be the combination of one or more flags). + * It returns SUCCESS if the current status includes the given flags + * and returns ERROR if one or more flags are missing in the current status. + * - When to use: + * - This function is suitable for most applications as well as for startup + * activity since the events are fully described in the product reference manual + * (RM0008). + * - It is also suitable for users who need to define their own events. + * - Limitations: + * - If an error occurs (ie. error flags are set besides to the monitored flags), + * the I2C_CheckEvent() function may return SUCCESS despite the communication + * hold or corrupted real state. + * In this case, it is advised to use error interrupts to monitor the error + * events and handle them in the interrupt IRQ handler. + * + * @note + * For error management, it is advised to use the following functions: + * - I2C_ITConfig() to configure and enable the error interrupts (I2C_IT_ERR). + * - I2Cx_ER_IRQHandler() which is called when the error interrupt occurs. + * Where x is the peripheral instance (I2C1, I2C2 ...) + * - I2C_GetFlagStatus() or I2C_GetITStatus() to be called into I2Cx_ER_IRQHandler() + * in order to determine which error occured. + * - I2C_ClearFlag() or I2C_ClearITPendingBit() and/or I2C_SoftwareResetCmd() + * and/or I2C_GenerateStop() in order to clear the error flag and source, + * and return to correct communication status. + * + * + * 2) Advanced state monitoring: + * Using the function I2C_GetLastEvent() which returns the image of both status + * registers in a single word (uint32_t) (Status Register 2 value is shifted left + * by 16 bits and concatenated to Status Register 1). + * - When to use: + * - This function is suitable for the same applications above but it allows to + * overcome the mentioned limitation of I2C_GetFlagStatus() function. + * The returned value could be compared to events already defined in the + * library (stm32f10x_i2c.h) or to custom values defined by user. + * - This function is suitable when multiple flags are monitored at the same time. + * - At the opposite of I2C_CheckEvent() function, this function allows user to + * choose when an event is accepted (when all events flags are set and no + * other flags are set or just when the needed flags are set like + * I2C_CheckEvent() function). + * - Limitations: + * - User may need to define his own events. + * - Same remark concerning the error management is applicable for this + * function if user decides to check only regular communication flags (and + * ignores error flags). + * + * + * 3) Flag-based state monitoring: + * Using the function I2C_GetFlagStatus() which simply returns the status of + * one single flag (ie. I2C_FLAG_RXNE ...). + * - When to use: + * - This function could be used for specific applications or in debug phase. + * - It is suitable when only one flag checking is needed (most I2C events + * are monitored through multiple flags). + * - Limitations: + * - When calling this function, the Status register is accessed. Some flags are + * cleared when the status register is accessed. So checking the status + * of one Flag, may clear other ones. + * - Function may need to be called twice or more in order to monitor one + * single event. + * + * For detailed description of Events, please refer to section I2C_Events in + * stm32f10x_i2c.h file. + * + */ + +/** + * + * 1) Basic state monitoring + ******************************************************************************* + */ + +/** + * @brief Checks whether the last I2Cx Event is equal to the one passed + * as parameter. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_EVENT: specifies the event to be checked. + * This parameter can be one of the following values: + * @arg I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED : EV1 + * @arg I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED : EV1 + * @arg I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED : EV1 + * @arg I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED : EV1 + * @arg I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED : EV1 + * @arg I2C_EVENT_SLAVE_BYTE_RECEIVED : EV2 + * @arg (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF) : EV2 + * @arg (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL) : EV2 + * @arg I2C_EVENT_SLAVE_BYTE_TRANSMITTED : EV3 + * @arg (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF) : EV3 + * @arg (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL) : EV3 + * @arg I2C_EVENT_SLAVE_ACK_FAILURE : EV3_2 + * @arg I2C_EVENT_SLAVE_STOP_DETECTED : EV4 + * @arg I2C_EVENT_MASTER_MODE_SELECT : EV5 + * @arg I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED : EV6 + * @arg I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED : EV6 + * @arg I2C_EVENT_MASTER_BYTE_RECEIVED : EV7 + * @arg I2C_EVENT_MASTER_BYTE_TRANSMITTING : EV8 + * @arg I2C_EVENT_MASTER_BYTE_TRANSMITTED : EV8_2 + * @arg I2C_EVENT_MASTER_MODE_ADDRESS10 : EV9 + * + * @note: For detailed description of Events, please refer to section + * I2C_Events in stm32f10x_i2c.h file. + * + * @retval An ErrorStatus enumeration value: + * - SUCCESS: Last event is equal to the I2C_EVENT + * - ERROR: Last event is different from the I2C_EVENT + */ +ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT) +{ + uint32_t lastevent = 0; + uint32_t flag1 = 0, flag2 = 0; + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_EVENT(I2C_EVENT)); + + /* Read the I2Cx status register */ + flag1 = I2Cx->SR1; + flag2 = I2Cx->SR2; + flag2 = flag2 << 16; + + /* Get the last event value from I2C status register */ + lastevent = (flag1 | flag2) & FLAG_Mask; + + /* Check whether the last event contains the I2C_EVENT */ + if ((lastevent & I2C_EVENT) == I2C_EVENT) + { + /* SUCCESS: last event is equal to I2C_EVENT */ + status = SUCCESS; + } + else + { + /* ERROR: last event is different from I2C_EVENT */ + status = ERROR; + } + /* Return status */ + return status; +} + +/** + * + * 2) Advanced state monitoring + ******************************************************************************* + */ + +/** + * @brief Returns the last I2Cx Event. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * + * @note: For detailed description of Events, please refer to section + * I2C_Events in stm32f10x_i2c.h file. + * + * @retval The last event + */ +uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx) +{ + uint32_t lastevent = 0; + uint32_t flag1 = 0, flag2 = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + /* Read the I2Cx status register */ + flag1 = I2Cx->SR1; + flag2 = I2Cx->SR2; + flag2 = flag2 << 16; + + /* Get the last event value from I2C status register */ + lastevent = (flag1 | flag2) & FLAG_Mask; + + /* Return status */ + return lastevent; +} + +/** + * + * 3) Flag-based state monitoring + ******************************************************************************* + */ + +/** + * @brief Checks whether the specified I2C flag is set or not. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg I2C_FLAG_DUALF: Dual flag (Slave mode) + * @arg I2C_FLAG_SMBHOST: SMBus host header (Slave mode) + * @arg I2C_FLAG_SMBDEFAULT: SMBus default header (Slave mode) + * @arg I2C_FLAG_GENCALL: General call header flag (Slave mode) + * @arg I2C_FLAG_TRA: Transmitter/Receiver flag + * @arg I2C_FLAG_BUSY: Bus busy flag + * @arg I2C_FLAG_MSL: Master/Slave flag + * @arg I2C_FLAG_SMBALERT: SMBus Alert flag + * @arg I2C_FLAG_TIMEOUT: Timeout or Tlow error flag + * @arg I2C_FLAG_PECERR: PEC error in reception flag + * @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode) + * @arg I2C_FLAG_AF: Acknowledge failure flag + * @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode) + * @arg I2C_FLAG_BERR: Bus error flag + * @arg I2C_FLAG_TXE: Data register empty flag (Transmitter) + * @arg I2C_FLAG_RXNE: Data register not empty (Receiver) flag + * @arg I2C_FLAG_STOPF: Stop detection flag (Slave mode) + * @arg I2C_FLAG_ADD10: 10-bit header sent flag (Master mode) + * @arg I2C_FLAG_BTF: Byte transfer finished flag + * @arg I2C_FLAG_ADDR: Address sent flag (Master mode) "ADSL" + * Address matched flag (Slave mode)"ENDA" + * @arg I2C_FLAG_SB: Start bit flag (Master mode) + * @retval The new state of I2C_FLAG (SET or RESET). + */ +FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG) +{ + FlagStatus bitstatus = RESET; + __IO uint32_t i2creg = 0, i2cxbase = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_GET_FLAG(I2C_FLAG)); + + /* Get the I2Cx peripheral base address */ + i2cxbase = (uint32_t)I2Cx; + + /* Read flag register index */ + i2creg = I2C_FLAG >> 28; + + /* Get bit[23:0] of the flag */ + I2C_FLAG &= FLAG_Mask; + + if(i2creg != 0) + { + /* Get the I2Cx SR1 register address */ + i2cxbase += 0x14; + } + else + { + /* Flag in I2Cx SR2 Register */ + I2C_FLAG = (uint32_t)(I2C_FLAG >> 16); + /* Get the I2Cx SR2 register address */ + i2cxbase += 0x18; + } + + if(((*(__IO uint32_t *)i2cxbase) & I2C_FLAG) != (uint32_t)RESET) + { + /* I2C_FLAG is set */ + bitstatus = SET; + } + else + { + /* I2C_FLAG is reset */ + bitstatus = RESET; + } + + /* Return the I2C_FLAG status */ + return bitstatus; +} + + + +/** + * @brief Clears the I2Cx's pending flags. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg I2C_FLAG_SMBALERT: SMBus Alert flag + * @arg I2C_FLAG_TIMEOUT: Timeout or Tlow error flag + * @arg I2C_FLAG_PECERR: PEC error in reception flag + * @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode) + * @arg I2C_FLAG_AF: Acknowledge failure flag + * @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode) + * @arg I2C_FLAG_BERR: Bus error flag + * + * @note + * - STOPF (STOP detection) is cleared by software sequence: a read operation + * to I2C_SR1 register (I2C_GetFlagStatus()) followed by a write operation + * to I2C_CR1 register (I2C_Cmd() to re-enable the I2C peripheral). + * - ADD10 (10-bit header sent) is cleared by software sequence: a read + * operation to I2C_SR1 (I2C_GetFlagStatus()) followed by writing the + * second byte of the address in DR register. + * - BTF (Byte Transfer Finished) is cleared by software sequence: a read + * operation to I2C_SR1 register (I2C_GetFlagStatus()) followed by a + * read/write to I2C_DR register (I2C_SendData()). + * - ADDR (Address sent) is cleared by software sequence: a read operation to + * I2C_SR1 register (I2C_GetFlagStatus()) followed by a read operation to + * I2C_SR2 register ((void)(I2Cx->SR2)). + * - SB (Start Bit) is cleared software sequence: a read operation to I2C_SR1 + * register (I2C_GetFlagStatus()) followed by a write operation to I2C_DR + * register (I2C_SendData()). + * @retval None + */ +void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG) +{ + uint32_t flagpos = 0; + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_CLEAR_FLAG(I2C_FLAG)); + /* Get the I2C flag position */ + flagpos = I2C_FLAG & FLAG_Mask; + /* Clear the selected I2C flag */ + I2Cx->SR1 = (uint16_t)~flagpos; +} + +/** + * @brief Checks whether the specified I2C interrupt has occurred or not. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_IT: specifies the interrupt source to check. + * This parameter can be one of the following values: + * @arg I2C_IT_SMBALERT: SMBus Alert flag + * @arg I2C_IT_TIMEOUT: Timeout or Tlow error flag + * @arg I2C_IT_PECERR: PEC error in reception flag + * @arg I2C_IT_OVR: Overrun/Underrun flag (Slave mode) + * @arg I2C_IT_AF: Acknowledge failure flag + * @arg I2C_IT_ARLO: Arbitration lost flag (Master mode) + * @arg I2C_IT_BERR: Bus error flag + * @arg I2C_IT_TXE: Data register empty flag (Transmitter) + * @arg I2C_IT_RXNE: Data register not empty (Receiver) flag + * @arg I2C_IT_STOPF: Stop detection flag (Slave mode) + * @arg I2C_IT_ADD10: 10-bit header sent flag (Master mode) + * @arg I2C_IT_BTF: Byte transfer finished flag + * @arg I2C_IT_ADDR: Address sent flag (Master mode) "ADSL" + * Address matched flag (Slave mode)"ENDAD" + * @arg I2C_IT_SB: Start bit flag (Master mode) + * @retval The new state of I2C_IT (SET or RESET). + */ +ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_GET_IT(I2C_IT)); + + /* Check if the interrupt source is enabled or not */ + enablestatus = (uint32_t)(((I2C_IT & ITEN_Mask) >> 16) & (I2Cx->CR2)) ; + + /* Get bit[23:0] of the flag */ + I2C_IT &= FLAG_Mask; + + /* Check the status of the specified I2C flag */ + if (((I2Cx->SR1 & I2C_IT) != (uint32_t)RESET) && enablestatus) + { + /* I2C_IT is set */ + bitstatus = SET; + } + else + { + /* I2C_IT is reset */ + bitstatus = RESET; + } + /* Return the I2C_IT status */ + return bitstatus; +} + +/** + * @brief Clears the I2Cx’s interrupt pending bits. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_IT: specifies the interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg I2C_IT_SMBALERT: SMBus Alert interrupt + * @arg I2C_IT_TIMEOUT: Timeout or Tlow error interrupt + * @arg I2C_IT_PECERR: PEC error in reception interrupt + * @arg I2C_IT_OVR: Overrun/Underrun interrupt (Slave mode) + * @arg I2C_IT_AF: Acknowledge failure interrupt + * @arg I2C_IT_ARLO: Arbitration lost interrupt (Master mode) + * @arg I2C_IT_BERR: Bus error interrupt + * + * @note + * - STOPF (STOP detection) is cleared by software sequence: a read operation + * to I2C_SR1 register (I2C_GetITStatus()) followed by a write operation to + * I2C_CR1 register (I2C_Cmd() to re-enable the I2C peripheral). + * - ADD10 (10-bit header sent) is cleared by software sequence: a read + * operation to I2C_SR1 (I2C_GetITStatus()) followed by writing the second + * byte of the address in I2C_DR register. + * - BTF (Byte Transfer Finished) is cleared by software sequence: a read + * operation to I2C_SR1 register (I2C_GetITStatus()) followed by a + * read/write to I2C_DR register (I2C_SendData()). + * - ADDR (Address sent) is cleared by software sequence: a read operation to + * I2C_SR1 register (I2C_GetITStatus()) followed by a read operation to + * I2C_SR2 register ((void)(I2Cx->SR2)). + * - SB (Start Bit) is cleared by software sequence: a read operation to + * I2C_SR1 register (I2C_GetITStatus()) followed by a write operation to + * I2C_DR register (I2C_SendData()). + * @retval None + */ +void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT) +{ + uint32_t flagpos = 0; + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_CLEAR_IT(I2C_IT)); + /* Get the I2C flag position */ + flagpos = I2C_IT & FLAG_Mask; + /* Clear the selected I2C flag */ + I2Cx->SR1 = (uint16_t)~flagpos; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c new file mode 100644 index 0000000..c7cbf7e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c @@ -0,0 +1,190 @@ +/** + ****************************************************************************** + * @file stm32f10x_iwdg.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the IWDG firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_iwdg.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup IWDG + * @brief IWDG driver modules + * @{ + */ + +/** @defgroup IWDG_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Private_Defines + * @{ + */ + +/* ---------------------- IWDG registers bit mask ----------------------------*/ + +/* KR register bit mask */ +#define KR_KEY_Reload ((uint16_t)0xAAAA) +#define KR_KEY_Enable ((uint16_t)0xCCCC) + +/** + * @} + */ + +/** @defgroup IWDG_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Private_Functions + * @{ + */ + +/** + * @brief Enables or disables write access to IWDG_PR and IWDG_RLR registers. + * @param IWDG_WriteAccess: new state of write access to IWDG_PR and IWDG_RLR registers. + * This parameter can be one of the following values: + * @arg IWDG_WriteAccess_Enable: Enable write access to IWDG_PR and IWDG_RLR registers + * @arg IWDG_WriteAccess_Disable: Disable write access to IWDG_PR and IWDG_RLR registers + * @retval None + */ +void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess) +{ + /* Check the parameters */ + assert_param(IS_IWDG_WRITE_ACCESS(IWDG_WriteAccess)); + IWDG->KR = IWDG_WriteAccess; +} + +/** + * @brief Sets IWDG Prescaler value. + * @param IWDG_Prescaler: specifies the IWDG Prescaler value. + * This parameter can be one of the following values: + * @arg IWDG_Prescaler_4: IWDG prescaler set to 4 + * @arg IWDG_Prescaler_8: IWDG prescaler set to 8 + * @arg IWDG_Prescaler_16: IWDG prescaler set to 16 + * @arg IWDG_Prescaler_32: IWDG prescaler set to 32 + * @arg IWDG_Prescaler_64: IWDG prescaler set to 64 + * @arg IWDG_Prescaler_128: IWDG prescaler set to 128 + * @arg IWDG_Prescaler_256: IWDG prescaler set to 256 + * @retval None + */ +void IWDG_SetPrescaler(uint8_t IWDG_Prescaler) +{ + /* Check the parameters */ + assert_param(IS_IWDG_PRESCALER(IWDG_Prescaler)); + IWDG->PR = IWDG_Prescaler; +} + +/** + * @brief Sets IWDG Reload value. + * @param Reload: specifies the IWDG Reload value. + * This parameter must be a number between 0 and 0x0FFF. + * @retval None + */ +void IWDG_SetReload(uint16_t Reload) +{ + /* Check the parameters */ + assert_param(IS_IWDG_RELOAD(Reload)); + IWDG->RLR = Reload; +} + +/** + * @brief Reloads IWDG counter with value defined in the reload register + * (write access to IWDG_PR and IWDG_RLR registers disabled). + * @param None + * @retval None + */ +void IWDG_ReloadCounter(void) +{ + IWDG->KR = KR_KEY_Reload; +} + +/** + * @brief Enables IWDG (write access to IWDG_PR and IWDG_RLR registers disabled). + * @param None + * @retval None + */ +void IWDG_Enable(void) +{ + IWDG->KR = KR_KEY_Enable; +} + +/** + * @brief Checks whether the specified IWDG flag is set or not. + * @param IWDG_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg IWDG_FLAG_PVU: Prescaler Value Update on going + * @arg IWDG_FLAG_RVU: Reload Value Update on going + * @retval The new state of IWDG_FLAG (SET or RESET). + */ +FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_IWDG_FLAG(IWDG_FLAG)); + if ((IWDG->SR & IWDG_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c new file mode 100644 index 0000000..a5a5c57 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c @@ -0,0 +1,307 @@ +/** + ****************************************************************************** + * @file stm32f10x_pwr.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the PWR firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_pwr.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup PWR + * @brief PWR driver modules + * @{ + */ + +/** @defgroup PWR_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Private_Defines + * @{ + */ + +/* --------- PWR registers bit address in the alias region ---------- */ +#define PWR_OFFSET (PWR_BASE - PERIPH_BASE) + +/* --- CR Register ---*/ + +/* Alias word address of DBP bit */ +#define CR_OFFSET (PWR_OFFSET + 0x00) +#define DBP_BitNumber 0x08 +#define CR_DBP_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4)) + +/* Alias word address of PVDE bit */ +#define PVDE_BitNumber 0x04 +#define CR_PVDE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4)) + +/* --- CSR Register ---*/ + +/* Alias word address of EWUP bit */ +#define CSR_OFFSET (PWR_OFFSET + 0x04) +#define EWUP_BitNumber 0x08 +#define CSR_EWUP_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP_BitNumber * 4)) + +/* ------------------ PWR registers bit mask ------------------------ */ + +/* CR register bit mask */ +#define CR_DS_MASK ((uint32_t)0xFFFFFFFC) +#define CR_PLS_MASK ((uint32_t)0xFFFFFF1F) + + +/** + * @} + */ + +/** @defgroup PWR_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the PWR peripheral registers to their default reset values. + * @param None + * @retval None + */ +void PWR_DeInit(void) +{ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, DISABLE); +} + +/** + * @brief Enables or disables access to the RTC and backup registers. + * @param NewState: new state of the access to the RTC and backup registers. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_BackupAccessCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_DBP_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the Power Voltage Detector(PVD). + * @param NewState: new state of the PVD. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_PVDCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the voltage threshold detected by the Power Voltage Detector(PVD). + * @param PWR_PVDLevel: specifies the PVD detection level + * This parameter can be one of the following values: + * @arg PWR_PVDLevel_2V2: PVD detection level set to 2.2V + * @arg PWR_PVDLevel_2V3: PVD detection level set to 2.3V + * @arg PWR_PVDLevel_2V4: PVD detection level set to 2.4V + * @arg PWR_PVDLevel_2V5: PVD detection level set to 2.5V + * @arg PWR_PVDLevel_2V6: PVD detection level set to 2.6V + * @arg PWR_PVDLevel_2V7: PVD detection level set to 2.7V + * @arg PWR_PVDLevel_2V8: PVD detection level set to 2.8V + * @arg PWR_PVDLevel_2V9: PVD detection level set to 2.9V + * @retval None + */ +void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel)); + tmpreg = PWR->CR; + /* Clear PLS[7:5] bits */ + tmpreg &= CR_PLS_MASK; + /* Set PLS[7:5] bits according to PWR_PVDLevel value */ + tmpreg |= PWR_PVDLevel; + /* Store the new value */ + PWR->CR = tmpreg; +} + +/** + * @brief Enables or disables the WakeUp Pin functionality. + * @param NewState: new state of the WakeUp Pin functionality. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_WakeUpPinCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CSR_EWUP_BB = (uint32_t)NewState; +} + +/** + * @brief Enters STOP mode. + * @param PWR_Regulator: specifies the regulator state in STOP mode. + * This parameter can be one of the following values: + * @arg PWR_Regulator_ON: STOP mode with regulator ON + * @arg PWR_Regulator_LowPower: STOP mode with regulator in low power mode + * @param PWR_STOPEntry: specifies if STOP mode in entered with WFI or WFE instruction. + * This parameter can be one of the following values: + * @arg PWR_STOPEntry_WFI: enter STOP mode with WFI instruction + * @arg PWR_STOPEntry_WFE: enter STOP mode with WFE instruction + * @retval None + */ +void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_PWR_REGULATOR(PWR_Regulator)); + assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry)); + + /* Select the regulator state in STOP mode ---------------------------------*/ + tmpreg = PWR->CR; + /* Clear PDDS and LPDS bits */ + tmpreg &= CR_DS_MASK; + /* Set LPDS bit according to PWR_Regulator value */ + tmpreg |= PWR_Regulator; + /* Store the new value */ + PWR->CR = tmpreg; + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR |= SCB_SCR_SLEEPDEEP; + + /* Select STOP mode entry --------------------------------------------------*/ + if(PWR_STOPEntry == PWR_STOPEntry_WFI) + { + /* Request Wait For Interrupt */ + __WFI(); + } + else + { + /* Request Wait For Event */ + __WFE(); + } + + /* Reset SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP); +} + +/** + * @brief Enters STANDBY mode. + * @param None + * @retval None + */ +void PWR_EnterSTANDBYMode(void) +{ + /* Clear Wake-up flag */ + PWR->CR |= PWR_CR_CWUF; + /* Select STANDBY mode */ + PWR->CR |= PWR_CR_PDDS; + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR |= SCB_SCR_SLEEPDEEP; +/* This option is used to ensure that store operations are completed */ +#if defined ( __CC_ARM ) + __force_stores(); +#endif + /* Request Wait For Interrupt */ + __WFI(); +} + +/** + * @brief Checks whether the specified PWR flag is set or not. + * @param PWR_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg PWR_FLAG_WU: Wake Up flag + * @arg PWR_FLAG_SB: StandBy flag + * @arg PWR_FLAG_PVDO: PVD Output + * @retval The new state of PWR_FLAG (SET or RESET). + */ +FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_PWR_GET_FLAG(PWR_FLAG)); + + if ((PWR->CSR & PWR_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @brief Clears the PWR's pending flags. + * @param PWR_FLAG: specifies the flag to clear. + * This parameter can be one of the following values: + * @arg PWR_FLAG_WU: Wake Up flag + * @arg PWR_FLAG_SB: StandBy flag + * @retval None + */ +void PWR_ClearFlag(uint32_t PWR_FLAG) +{ + /* Check the parameters */ + assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG)); + + PWR->CR |= PWR_FLAG << 2; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c new file mode 100644 index 0000000..d817ee9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c @@ -0,0 +1,1471 @@ +/** + ****************************************************************************** + * @file stm32f10x_rcc.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the RCC firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup RCC + * @brief RCC driver modules + * @{ + */ + +/** @defgroup RCC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup RCC_Private_Defines + * @{ + */ + +/* ------------ RCC registers bit address in the alias region ----------- */ +#define RCC_OFFSET (RCC_BASE - PERIPH_BASE) + +/* --- CR Register ---*/ + +/* Alias word address of HSION bit */ +#define CR_OFFSET (RCC_OFFSET + 0x00) +#define HSION_BitNumber 0x00 +#define CR_HSION_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4)) + +/* Alias word address of PLLON bit */ +#define PLLON_BitNumber 0x18 +#define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4)) + +#ifdef STM32F10X_CL + /* Alias word address of PLL2ON bit */ + #define PLL2ON_BitNumber 0x1A + #define CR_PLL2ON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLL2ON_BitNumber * 4)) + + /* Alias word address of PLL3ON bit */ + #define PLL3ON_BitNumber 0x1C + #define CR_PLL3ON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLL3ON_BitNumber * 4)) +#endif /* STM32F10X_CL */ + +/* Alias word address of CSSON bit */ +#define CSSON_BitNumber 0x13 +#define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4)) + +/* --- CFGR Register ---*/ + +/* Alias word address of USBPRE bit */ +#define CFGR_OFFSET (RCC_OFFSET + 0x04) + +#ifndef STM32F10X_CL + #define USBPRE_BitNumber 0x16 + #define CFGR_USBPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (USBPRE_BitNumber * 4)) +#else + #define OTGFSPRE_BitNumber 0x16 + #define CFGR_OTGFSPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (OTGFSPRE_BitNumber * 4)) +#endif /* STM32F10X_CL */ + +/* --- BDCR Register ---*/ + +/* Alias word address of RTCEN bit */ +#define BDCR_OFFSET (RCC_OFFSET + 0x20) +#define RTCEN_BitNumber 0x0F +#define BDCR_RTCEN_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4)) + +/* Alias word address of BDRST bit */ +#define BDRST_BitNumber 0x10 +#define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4)) + +/* --- CSR Register ---*/ + +/* Alias word address of LSION bit */ +#define CSR_OFFSET (RCC_OFFSET + 0x24) +#define LSION_BitNumber 0x00 +#define CSR_LSION_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4)) + +#ifdef STM32F10X_CL +/* --- CFGR2 Register ---*/ + + /* Alias word address of I2S2SRC bit */ + #define CFGR2_OFFSET (RCC_OFFSET + 0x2C) + #define I2S2SRC_BitNumber 0x11 + #define CFGR2_I2S2SRC_BB (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (I2S2SRC_BitNumber * 4)) + + /* Alias word address of I2S3SRC bit */ + #define I2S3SRC_BitNumber 0x12 + #define CFGR2_I2S3SRC_BB (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (I2S3SRC_BitNumber * 4)) +#endif /* STM32F10X_CL */ + +/* ---------------------- RCC registers bit mask ------------------------ */ + +/* CR register bit mask */ +#define CR_HSEBYP_Reset ((uint32_t)0xFFFBFFFF) +#define CR_HSEBYP_Set ((uint32_t)0x00040000) +#define CR_HSEON_Reset ((uint32_t)0xFFFEFFFF) +#define CR_HSEON_Set ((uint32_t)0x00010000) +#define CR_HSITRIM_Mask ((uint32_t)0xFFFFFF07) + +/* CFGR register bit mask */ +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) + #define CFGR_PLL_Mask ((uint32_t)0xFFC2FFFF) +#else + #define CFGR_PLL_Mask ((uint32_t)0xFFC0FFFF) +#endif /* STM32F10X_CL */ + +#define CFGR_PLLMull_Mask ((uint32_t)0x003C0000) +#define CFGR_PLLSRC_Mask ((uint32_t)0x00010000) +#define CFGR_PLLXTPRE_Mask ((uint32_t)0x00020000) +#define CFGR_SWS_Mask ((uint32_t)0x0000000C) +#define CFGR_SW_Mask ((uint32_t)0xFFFFFFFC) +#define CFGR_HPRE_Reset_Mask ((uint32_t)0xFFFFFF0F) +#define CFGR_HPRE_Set_Mask ((uint32_t)0x000000F0) +#define CFGR_PPRE1_Reset_Mask ((uint32_t)0xFFFFF8FF) +#define CFGR_PPRE1_Set_Mask ((uint32_t)0x00000700) +#define CFGR_PPRE2_Reset_Mask ((uint32_t)0xFFFFC7FF) +#define CFGR_PPRE2_Set_Mask ((uint32_t)0x00003800) +#define CFGR_ADCPRE_Reset_Mask ((uint32_t)0xFFFF3FFF) +#define CFGR_ADCPRE_Set_Mask ((uint32_t)0x0000C000) + +/* CSR register bit mask */ +#define CSR_RMVF_Set ((uint32_t)0x01000000) + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) +/* CFGR2 register bit mask */ + #define CFGR2_PREDIV1SRC ((uint32_t)0x00010000) + #define CFGR2_PREDIV1 ((uint32_t)0x0000000F) +#endif +#ifdef STM32F10X_CL + #define CFGR2_PREDIV2 ((uint32_t)0x000000F0) + #define CFGR2_PLL2MUL ((uint32_t)0x00000F00) + #define CFGR2_PLL3MUL ((uint32_t)0x0000F000) +#endif /* STM32F10X_CL */ + +/* RCC Flag Mask */ +#define FLAG_Mask ((uint8_t)0x1F) + +/* CIR register byte 2 (Bits[15:8]) base address */ +#define CIR_BYTE2_ADDRESS ((uint32_t)0x40021009) + +/* CIR register byte 3 (Bits[23:16]) base address */ +#define CIR_BYTE3_ADDRESS ((uint32_t)0x4002100A) + +/* CFGR register byte 4 (Bits[31:24]) base address */ +#define CFGR_BYTE4_ADDRESS ((uint32_t)0x40021007) + +/* BDCR register base address */ +#define BDCR_ADDRESS (PERIPH_BASE + BDCR_OFFSET) + +/** + * @} + */ + +/** @defgroup RCC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup RCC_Private_Variables + * @{ + */ + +static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9}; +static __I uint8_t ADCPrescTable[4] = {2, 4, 6, 8}; +extern uint32_t hse_value; + +/** + * @} + */ + +/** @defgroup RCC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup RCC_Private_Functions + * @{ + */ + +/** + * @brief Resets the RCC clock configuration to the default reset state. + * @param None + * @retval None + */ +void RCC_DeInit(void) +{ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001; + + /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */ +#ifndef STM32F10X_CL + RCC->CFGR &= (uint32_t)0xF8FF0000; +#else + RCC->CFGR &= (uint32_t)0xF0FF0000; +#endif /* STM32F10X_CL */ + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + + /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */ + RCC->CFGR &= (uint32_t)0xFF80FFFF; + +#ifdef STM32F10X_CL + /* Reset PLL2ON and PLL3ON bits */ + RCC->CR &= (uint32_t)0xEBFFFFFF; + + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x00FF0000; + + /* Reset CFGR2 register */ + RCC->CFGR2 = 0x00000000; +#elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x009F0000; + + /* Reset CFGR2 register */ + RCC->CFGR2 = 0x00000000; +#else + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x009F0000; +#endif /* STM32F10X_CL */ + +} + +/** + * @brief Configures the External High Speed oscillator (HSE). + * @note HSE can not be stopped if it is used directly or through the PLL as system clock. + * @param RCC_HSE: specifies the new state of the HSE. + * This parameter can be one of the following values: + * @arg RCC_HSE_OFF: HSE oscillator OFF + * @arg RCC_HSE_ON: HSE oscillator ON + * @arg RCC_HSE_Bypass: HSE oscillator bypassed with external clock + * @retval None + */ +void RCC_HSEConfig(uint32_t RCC_HSE) +{ + /* Check the parameters */ + assert_param(IS_RCC_HSE(RCC_HSE)); + /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/ + /* Reset HSEON bit */ + RCC->CR &= CR_HSEON_Reset; + /* Reset HSEBYP bit */ + RCC->CR &= CR_HSEBYP_Reset; + /* Configure HSE (RCC_HSE_OFF is already covered by the code section above) */ + switch(RCC_HSE) + { + case RCC_HSE_ON: + /* Set HSEON bit */ + RCC->CR |= CR_HSEON_Set; + break; + + case RCC_HSE_Bypass: + /* Set HSEBYP and HSEON bits */ + RCC->CR |= CR_HSEBYP_Set | CR_HSEON_Set; + break; + + default: + break; + } +} + +/** + * @brief Waits for HSE start-up. + * @param None + * @retval An ErrorStatus enumuration value: + * - SUCCESS: HSE oscillator is stable and ready to use + * - ERROR: HSE oscillator not yet ready + */ +ErrorStatus RCC_WaitForHSEStartUp(void) +{ + __IO uint32_t StartUpCounter = 0; + ErrorStatus status = ERROR; + FlagStatus HSEStatus = RESET; + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY); + StartUpCounter++; + } while((StartUpCounter != HSE_STARTUP_TIMEOUT) && (HSEStatus == RESET)); + + if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET) + { + status = SUCCESS; + } + else + { + status = ERROR; + } + return (status); +} + +/** + * @brief Adjusts the Internal High Speed oscillator (HSI) calibration value. + * @param HSICalibrationValue: specifies the calibration trimming value. + * This parameter must be a number between 0 and 0x1F. + * @retval None + */ +void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_CALIBRATION_VALUE(HSICalibrationValue)); + tmpreg = RCC->CR; + /* Clear HSITRIM[4:0] bits */ + tmpreg &= CR_HSITRIM_Mask; + /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */ + tmpreg |= (uint32_t)HSICalibrationValue << 3; + /* Store the new value */ + RCC->CR = tmpreg; +} + +/** + * @brief Enables or disables the Internal High Speed oscillator (HSI). + * @note HSI can not be stopped if it is used directly or through the PLL as system clock. + * @param NewState: new state of the HSI. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_HSICmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_HSION_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the PLL clock source and multiplication factor. + * @note This function must be used only when the PLL is disabled. + * @param RCC_PLLSource: specifies the PLL entry clock source. + * For @b STM32_Connectivity_line_devices or @b STM32_Value_line_devices, + * this parameter can be one of the following values: + * @arg RCC_PLLSource_HSI_Div2: HSI oscillator clock divided by 2 selected as PLL clock entry + * @arg RCC_PLLSource_PREDIV1: PREDIV1 clock selected as PLL clock entry + * For @b other_STM32_devices, this parameter can be one of the following values: + * @arg RCC_PLLSource_HSI_Div2: HSI oscillator clock divided by 2 selected as PLL clock entry + * @arg RCC_PLLSource_HSE_Div1: HSE oscillator clock selected as PLL clock entry + * @arg RCC_PLLSource_HSE_Div2: HSE oscillator clock divided by 2 selected as PLL clock entry + * @param RCC_PLLMul: specifies the PLL multiplication factor. + * For @b STM32_Connectivity_line_devices, this parameter can be RCC_PLLMul_x where x:{[4,9], 6_5} + * For @b other_STM32_devices, this parameter can be RCC_PLLMul_x where x:[2,16] + * @retval None + */ +void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource)); + assert_param(IS_RCC_PLL_MUL(RCC_PLLMul)); + + tmpreg = RCC->CFGR; + /* Clear PLLSRC, PLLXTPRE and PLLMUL[3:0] bits */ + tmpreg &= CFGR_PLL_Mask; + /* Set the PLL configuration bits */ + tmpreg |= RCC_PLLSource | RCC_PLLMul; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Enables or disables the PLL. + * @note The PLL can not be disabled if it is used as system clock. + * @param NewState: new state of the PLL. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_PLLCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CR_PLLON_BB = (uint32_t)NewState; +} + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) +/** + * @brief Configures the PREDIV1 division factor. + * @note + * - This function must be used only when the PLL is disabled. + * - This function applies only to STM32 Connectivity line and Value line + * devices. + * @param RCC_PREDIV1_Source: specifies the PREDIV1 clock source. + * This parameter can be one of the following values: + * @arg RCC_PREDIV1_Source_HSE: HSE selected as PREDIV1 clock + * @arg RCC_PREDIV1_Source_PLL2: PLL2 selected as PREDIV1 clock + * @note + * For @b STM32_Value_line_devices this parameter is always RCC_PREDIV1_Source_HSE + * @param RCC_PREDIV1_Div: specifies the PREDIV1 clock division factor. + * This parameter can be RCC_PREDIV1_Divx where x:[1,16] + * @retval None + */ +void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Source, uint32_t RCC_PREDIV1_Div) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PREDIV1_SOURCE(RCC_PREDIV1_Source)); + assert_param(IS_RCC_PREDIV1(RCC_PREDIV1_Div)); + + tmpreg = RCC->CFGR2; + /* Clear PREDIV1[3:0] and PREDIV1SRC bits */ + tmpreg &= ~(CFGR2_PREDIV1 | CFGR2_PREDIV1SRC); + /* Set the PREDIV1 clock source and division factor */ + tmpreg |= RCC_PREDIV1_Source | RCC_PREDIV1_Div ; + /* Store the new value */ + RCC->CFGR2 = tmpreg; +} +#endif + +#ifdef STM32F10X_CL +/** + * @brief Configures the PREDIV2 division factor. + * @note + * - This function must be used only when both PLL2 and PLL3 are disabled. + * - This function applies only to STM32 Connectivity line devices. + * @param RCC_PREDIV2_Div: specifies the PREDIV2 clock division factor. + * This parameter can be RCC_PREDIV2_Divx where x:[1,16] + * @retval None + */ +void RCC_PREDIV2Config(uint32_t RCC_PREDIV2_Div) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PREDIV2(RCC_PREDIV2_Div)); + + tmpreg = RCC->CFGR2; + /* Clear PREDIV2[3:0] bits */ + tmpreg &= ~CFGR2_PREDIV2; + /* Set the PREDIV2 division factor */ + tmpreg |= RCC_PREDIV2_Div; + /* Store the new value */ + RCC->CFGR2 = tmpreg; +} + +/** + * @brief Configures the PLL2 multiplication factor. + * @note + * - This function must be used only when the PLL2 is disabled. + * - This function applies only to STM32 Connectivity line devices. + * @param RCC_PLL2Mul: specifies the PLL2 multiplication factor. + * This parameter can be RCC_PLL2Mul_x where x:{[8,14], 16, 20} + * @retval None + */ +void RCC_PLL2Config(uint32_t RCC_PLL2Mul) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PLL2_MUL(RCC_PLL2Mul)); + + tmpreg = RCC->CFGR2; + /* Clear PLL2Mul[3:0] bits */ + tmpreg &= ~CFGR2_PLL2MUL; + /* Set the PLL2 configuration bits */ + tmpreg |= RCC_PLL2Mul; + /* Store the new value */ + RCC->CFGR2 = tmpreg; +} + + +/** + * @brief Enables or disables the PLL2. + * @note + * - The PLL2 can not be disabled if it is used indirectly as system clock + * (i.e. it is used as PLL clock entry that is used as System clock). + * - This function applies only to STM32 Connectivity line devices. + * @param NewState: new state of the PLL2. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_PLL2Cmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CR_PLL2ON_BB = (uint32_t)NewState; +} + + +/** + * @brief Configures the PLL3 multiplication factor. + * @note + * - This function must be used only when the PLL3 is disabled. + * - This function applies only to STM32 Connectivity line devices. + * @param RCC_PLL3Mul: specifies the PLL3 multiplication factor. + * This parameter can be RCC_PLL3Mul_x where x:{[8,14], 16, 20} + * @retval None + */ +void RCC_PLL3Config(uint32_t RCC_PLL3Mul) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PLL3_MUL(RCC_PLL3Mul)); + + tmpreg = RCC->CFGR2; + /* Clear PLL3Mul[3:0] bits */ + tmpreg &= ~CFGR2_PLL3MUL; + /* Set the PLL3 configuration bits */ + tmpreg |= RCC_PLL3Mul; + /* Store the new value */ + RCC->CFGR2 = tmpreg; +} + + +/** + * @brief Enables or disables the PLL3. + * @note This function applies only to STM32 Connectivity line devices. + * @param NewState: new state of the PLL3. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_PLL3Cmd(FunctionalState NewState) +{ + /* Check the parameters */ + + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_PLL3ON_BB = (uint32_t)NewState; +} +#endif /* STM32F10X_CL */ + +/** + * @brief Configures the system clock (SYSCLK). + * @param RCC_SYSCLKSource: specifies the clock source used as system clock. + * This parameter can be one of the following values: + * @arg RCC_SYSCLKSource_HSI: HSI selected as system clock + * @arg RCC_SYSCLKSource_HSE: HSE selected as system clock + * @arg RCC_SYSCLKSource_PLLCLK: PLL selected as system clock + * @retval None + */ +void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource)); + tmpreg = RCC->CFGR; + /* Clear SW[1:0] bits */ + tmpreg &= CFGR_SW_Mask; + /* Set SW[1:0] bits according to RCC_SYSCLKSource value */ + tmpreg |= RCC_SYSCLKSource; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Returns the clock source used as system clock. + * @param None + * @retval The clock source used as system clock. The returned value can + * be one of the following: + * - 0x00: HSI used as system clock + * - 0x04: HSE used as system clock + * - 0x08: PLL used as system clock + */ +uint8_t RCC_GetSYSCLKSource(void) +{ + return ((uint8_t)(RCC->CFGR & CFGR_SWS_Mask)); +} + +/** + * @brief Configures the AHB clock (HCLK). + * @param RCC_SYSCLK: defines the AHB clock divider. This clock is derived from + * the system clock (SYSCLK). + * This parameter can be one of the following values: + * @arg RCC_SYSCLK_Div1: AHB clock = SYSCLK + * @arg RCC_SYSCLK_Div2: AHB clock = SYSCLK/2 + * @arg RCC_SYSCLK_Div4: AHB clock = SYSCLK/4 + * @arg RCC_SYSCLK_Div8: AHB clock = SYSCLK/8 + * @arg RCC_SYSCLK_Div16: AHB clock = SYSCLK/16 + * @arg RCC_SYSCLK_Div64: AHB clock = SYSCLK/64 + * @arg RCC_SYSCLK_Div128: AHB clock = SYSCLK/128 + * @arg RCC_SYSCLK_Div256: AHB clock = SYSCLK/256 + * @arg RCC_SYSCLK_Div512: AHB clock = SYSCLK/512 + * @retval None + */ +void RCC_HCLKConfig(uint32_t RCC_SYSCLK) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_HCLK(RCC_SYSCLK)); + tmpreg = RCC->CFGR; + /* Clear HPRE[3:0] bits */ + tmpreg &= CFGR_HPRE_Reset_Mask; + /* Set HPRE[3:0] bits according to RCC_SYSCLK value */ + tmpreg |= RCC_SYSCLK; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Configures the Low Speed APB clock (PCLK1). + * @param RCC_HCLK: defines the APB1 clock divider. This clock is derived from + * the AHB clock (HCLK). + * This parameter can be one of the following values: + * @arg RCC_HCLK_Div1: APB1 clock = HCLK + * @arg RCC_HCLK_Div2: APB1 clock = HCLK/2 + * @arg RCC_HCLK_Div4: APB1 clock = HCLK/4 + * @arg RCC_HCLK_Div8: APB1 clock = HCLK/8 + * @arg RCC_HCLK_Div16: APB1 clock = HCLK/16 + * @retval None + */ +void RCC_PCLK1Config(uint32_t RCC_HCLK) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_PCLK(RCC_HCLK)); + tmpreg = RCC->CFGR; + /* Clear PPRE1[2:0] bits */ + tmpreg &= CFGR_PPRE1_Reset_Mask; + /* Set PPRE1[2:0] bits according to RCC_HCLK value */ + tmpreg |= RCC_HCLK; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Configures the High Speed APB clock (PCLK2). + * @param RCC_HCLK: defines the APB2 clock divider. This clock is derived from + * the AHB clock (HCLK). + * This parameter can be one of the following values: + * @arg RCC_HCLK_Div1: APB2 clock = HCLK + * @arg RCC_HCLK_Div2: APB2 clock = HCLK/2 + * @arg RCC_HCLK_Div4: APB2 clock = HCLK/4 + * @arg RCC_HCLK_Div8: APB2 clock = HCLK/8 + * @arg RCC_HCLK_Div16: APB2 clock = HCLK/16 + * @retval None + */ +void RCC_PCLK2Config(uint32_t RCC_HCLK) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_PCLK(RCC_HCLK)); + tmpreg = RCC->CFGR; + /* Clear PPRE2[2:0] bits */ + tmpreg &= CFGR_PPRE2_Reset_Mask; + /* Set PPRE2[2:0] bits according to RCC_HCLK value */ + tmpreg |= RCC_HCLK << 3; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Enables or disables the specified RCC interrupts. + * @param RCC_IT: specifies the RCC interrupt sources to be enabled or disabled. + * + * For @b STM32_Connectivity_line_devices, this parameter can be any combination + * of the following values + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * @arg RCC_IT_PLL2RDY: PLL2 ready interrupt + * @arg RCC_IT_PLL3RDY: PLL3 ready interrupt + * + * For @b other_STM32_devices, this parameter can be any combination of the + * following values + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * + * @param NewState: new state of the specified RCC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_IT(RCC_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Perform Byte access to RCC_CIR bits to enable the selected interrupts */ + *(__IO uint8_t *) CIR_BYTE2_ADDRESS |= RCC_IT; + } + else + { + /* Perform Byte access to RCC_CIR bits to disable the selected interrupts */ + *(__IO uint8_t *) CIR_BYTE2_ADDRESS &= (uint8_t)~RCC_IT; + } +} + +#ifndef STM32F10X_CL +/** + * @brief Configures the USB clock (USBCLK). + * @param RCC_USBCLKSource: specifies the USB clock source. This clock is + * derived from the PLL output. + * This parameter can be one of the following values: + * @arg RCC_USBCLKSource_PLLCLK_1Div5: PLL clock divided by 1,5 selected as USB + * clock source + * @arg RCC_USBCLKSource_PLLCLK_Div1: PLL clock selected as USB clock source + * @retval None + */ +void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_USBCLK_SOURCE(RCC_USBCLKSource)); + + *(__IO uint32_t *) CFGR_USBPRE_BB = RCC_USBCLKSource; +} +#else +/** + * @brief Configures the USB OTG FS clock (OTGFSCLK). + * This function applies only to STM32 Connectivity line devices. + * @param RCC_OTGFSCLKSource: specifies the USB OTG FS clock source. + * This clock is derived from the PLL output. + * This parameter can be one of the following values: + * @arg RCC_OTGFSCLKSource_PLLVCO_Div3: PLL VCO clock divided by 2 selected as USB OTG FS clock source + * @arg RCC_OTGFSCLKSource_PLLVCO_Div2: PLL VCO clock divided by 2 selected as USB OTG FS clock source + * @retval None + */ +void RCC_OTGFSCLKConfig(uint32_t RCC_OTGFSCLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_OTGFSCLK_SOURCE(RCC_OTGFSCLKSource)); + + *(__IO uint32_t *) CFGR_OTGFSPRE_BB = RCC_OTGFSCLKSource; +} +#endif /* STM32F10X_CL */ + +/** + * @brief Configures the ADC clock (ADCCLK). + * @param RCC_PCLK2: defines the ADC clock divider. This clock is derived from + * the APB2 clock (PCLK2). + * This parameter can be one of the following values: + * @arg RCC_PCLK2_Div2: ADC clock = PCLK2/2 + * @arg RCC_PCLK2_Div4: ADC clock = PCLK2/4 + * @arg RCC_PCLK2_Div6: ADC clock = PCLK2/6 + * @arg RCC_PCLK2_Div8: ADC clock = PCLK2/8 + * @retval None + */ +void RCC_ADCCLKConfig(uint32_t RCC_PCLK2) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_ADCCLK(RCC_PCLK2)); + tmpreg = RCC->CFGR; + /* Clear ADCPRE[1:0] bits */ + tmpreg &= CFGR_ADCPRE_Reset_Mask; + /* Set ADCPRE[1:0] bits according to RCC_PCLK2 value */ + tmpreg |= RCC_PCLK2; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +#ifdef STM32F10X_CL +/** + * @brief Configures the I2S2 clock source(I2S2CLK). + * @note + * - This function must be called before enabling I2S2 APB clock. + * - This function applies only to STM32 Connectivity line devices. + * @param RCC_I2S2CLKSource: specifies the I2S2 clock source. + * This parameter can be one of the following values: + * @arg RCC_I2S2CLKSource_SYSCLK: system clock selected as I2S2 clock entry + * @arg RCC_I2S2CLKSource_PLL3_VCO: PLL3 VCO clock selected as I2S2 clock entry + * @retval None + */ +void RCC_I2S2CLKConfig(uint32_t RCC_I2S2CLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_I2S2CLK_SOURCE(RCC_I2S2CLKSource)); + + *(__IO uint32_t *) CFGR2_I2S2SRC_BB = RCC_I2S2CLKSource; +} + +/** + * @brief Configures the I2S3 clock source(I2S2CLK). + * @note + * - This function must be called before enabling I2S3 APB clock. + * - This function applies only to STM32 Connectivity line devices. + * @param RCC_I2S3CLKSource: specifies the I2S3 clock source. + * This parameter can be one of the following values: + * @arg RCC_I2S3CLKSource_SYSCLK: system clock selected as I2S3 clock entry + * @arg RCC_I2S3CLKSource_PLL3_VCO: PLL3 VCO clock selected as I2S3 clock entry + * @retval None + */ +void RCC_I2S3CLKConfig(uint32_t RCC_I2S3CLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_I2S3CLK_SOURCE(RCC_I2S3CLKSource)); + + *(__IO uint32_t *) CFGR2_I2S3SRC_BB = RCC_I2S3CLKSource; +} +#endif /* STM32F10X_CL */ + +/** + * @brief Configures the External Low Speed oscillator (LSE). + * @param RCC_LSE: specifies the new state of the LSE. + * This parameter can be one of the following values: + * @arg RCC_LSE_OFF: LSE oscillator OFF + * @arg RCC_LSE_ON: LSE oscillator ON + * @arg RCC_LSE_Bypass: LSE oscillator bypassed with external clock + * @retval None + */ +void RCC_LSEConfig(uint8_t RCC_LSE) +{ + /* Check the parameters */ + assert_param(IS_RCC_LSE(RCC_LSE)); + /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/ + /* Reset LSEON bit */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF; + /* Reset LSEBYP bit */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF; + /* Configure LSE (RCC_LSE_OFF is already covered by the code section above) */ + switch(RCC_LSE) + { + case RCC_LSE_ON: + /* Set LSEON bit */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_ON; + break; + + case RCC_LSE_Bypass: + /* Set LSEBYP and LSEON bits */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_Bypass | RCC_LSE_ON; + break; + + default: + break; + } +} + +/** + * @brief Enables or disables the Internal Low Speed oscillator (LSI). + * @note LSI can not be disabled if the IWDG is running. + * @param NewState: new state of the LSI. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_LSICmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the RTC clock (RTCCLK). + * @note Once the RTC clock is selected it can't be changed unless the Backup domain is reset. + * @param RCC_RTCCLKSource: specifies the RTC clock source. + * This parameter can be one of the following values: + * @arg RCC_RTCCLKSource_LSE: LSE selected as RTC clock + * @arg RCC_RTCCLKSource_LSI: LSI selected as RTC clock + * @arg RCC_RTCCLKSource_HSE_Div128: HSE clock divided by 128 selected as RTC clock + * @retval None + */ +void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource)); + /* Select the RTC clock source */ + RCC->BDCR |= RCC_RTCCLKSource; +} + +/** + * @brief Enables or disables the RTC clock. + * @note This function must be used only after the RTC clock was selected using the RCC_RTCCLKConfig function. + * @param NewState: new state of the RTC clock. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_RTCCLKCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) BDCR_RTCEN_BB = (uint32_t)NewState; +} + +/** + * @brief Returns the frequencies of different on chip clocks. + * @param RCC_Clocks: pointer to a RCC_ClocksTypeDef structure which will hold + * the clocks frequencies. + * @note The result of this function could be not correct when using + * fractional value for HSE crystal. + * @retval None + */ +void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) +{ + uint32_t tmp = 0, pllmull = 0, pllsource = 0, presc = 0; + +#ifdef STM32F10X_CL + uint32_t prediv1source = 0, prediv1factor = 0, prediv2factor = 0, pll2mull = 0; +#endif /* STM32F10X_CL */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + uint32_t prediv1factor = 0; +#endif + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & CFGR_SWS_Mask; + + switch (tmp) + { + case 0x00: /* HSI used as system clock */ + RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; + break; + case 0x04: /* HSE used as system clock */ + RCC_Clocks->SYSCLK_Frequency = hse_value; + break; + case 0x08: /* PLL used as system clock */ + + /* Get PLL clock source and multiplication factor ----------------------*/ + pllmull = RCC->CFGR & CFGR_PLLMull_Mask; + pllsource = RCC->CFGR & CFGR_PLLSRC_Mask; + +#ifndef STM32F10X_CL + pllmull = ( pllmull >> 18) + 2; + + if (pllsource == 0x00) + {/* HSI oscillator clock divided by 2 selected as PLL clock entry */ + RCC_Clocks->SYSCLK_Frequency = (HSI_VALUE >> 1) * pllmull; + } + else + { + #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + prediv1factor = (RCC->CFGR2 & CFGR2_PREDIV1) + 1; + /* HSE oscillator clock selected as PREDIV1 clock entry */ + RCC_Clocks->SYSCLK_Frequency = (HSE_VALUE / prediv1factor) * pllmull; + #else + /* HSE selected as PLL clock entry */ + if ((RCC->CFGR & CFGR_PLLXTPRE_Mask) != (uint32_t)RESET) + {/* HSE oscillator clock divided by 2 */ + RCC_Clocks->SYSCLK_Frequency = (hse_value >> 1) * pllmull; + } + else + { + RCC_Clocks->SYSCLK_Frequency = hse_value * pllmull; + } + #endif + } +#else + pllmull = pllmull >> 18; + + if (pllmull != 0x0D) + { + pllmull += 2; + } + else + { /* PLL multiplication factor = PLL input clock * 6.5 */ + pllmull = 13 / 2; + } + + if (pllsource == 0x00) + {/* HSI oscillator clock divided by 2 selected as PLL clock entry */ + RCC_Clocks->SYSCLK_Frequency = (hse_value >> 1) * pllmull; + } + else + {/* PREDIV1 selected as PLL clock entry */ + + /* Get PREDIV1 clock source and division factor */ + prediv1source = RCC->CFGR2 & CFGR2_PREDIV1SRC; + prediv1factor = (RCC->CFGR2 & CFGR2_PREDIV1) + 1; + + if (prediv1source == 0) + { /* HSE oscillator clock selected as PREDIV1 clock entry */ + RCC_Clocks->SYSCLK_Frequency = (hse_value / prediv1factor) * pllmull; + } + else + {/* PLL2 clock selected as PREDIV1 clock entry */ + + /* Get PREDIV2 division factor and PLL2 multiplication factor */ + prediv2factor = ((RCC->CFGR2 & CFGR2_PREDIV2) >> 4) + 1; + pll2mull = ((RCC->CFGR2 & CFGR2_PLL2MUL) >> 8 ) + 2; + RCC_Clocks->SYSCLK_Frequency = (((hse_value / prediv2factor) * pll2mull) / prediv1factor) * pllmull; + } + } +#endif /* STM32F10X_CL */ + break; + + default: + RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; + break; + } + + /* Compute HCLK, PCLK1, PCLK2 and ADCCLK clocks frequencies ----------------*/ + /* Get HCLK prescaler */ + tmp = RCC->CFGR & CFGR_HPRE_Set_Mask; + tmp = tmp >> 4; + presc = APBAHBPrescTable[tmp]; + /* HCLK clock frequency */ + RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> presc; + /* Get PCLK1 prescaler */ + tmp = RCC->CFGR & CFGR_PPRE1_Set_Mask; + tmp = tmp >> 8; + presc = APBAHBPrescTable[tmp]; + /* PCLK1 clock frequency */ + RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc; + /* Get PCLK2 prescaler */ + tmp = RCC->CFGR & CFGR_PPRE2_Set_Mask; + tmp = tmp >> 11; + presc = APBAHBPrescTable[tmp]; + /* PCLK2 clock frequency */ + RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> presc; + /* Get ADCCLK prescaler */ + tmp = RCC->CFGR & CFGR_ADCPRE_Set_Mask; + tmp = tmp >> 14; + presc = ADCPrescTable[tmp]; + /* ADCCLK clock frequency */ + RCC_Clocks->ADCCLK_Frequency = RCC_Clocks->PCLK2_Frequency / presc; +} + +/** + * @brief Enables or disables the AHB peripheral clock. + * @param RCC_AHBPeriph: specifies the AHB peripheral to gates its clock. + * + * For @b STM32_Connectivity_line_devices, this parameter can be any combination + * of the following values: + * @arg RCC_AHBPeriph_DMA1 + * @arg RCC_AHBPeriph_DMA2 + * @arg RCC_AHBPeriph_SRAM + * @arg RCC_AHBPeriph_FLITF + * @arg RCC_AHBPeriph_CRC + * @arg RCC_AHBPeriph_OTG_FS + * @arg RCC_AHBPeriph_ETH_MAC + * @arg RCC_AHBPeriph_ETH_MAC_Tx + * @arg RCC_AHBPeriph_ETH_MAC_Rx + * + * For @b other_STM32_devices, this parameter can be any combination of the + * following values: + * @arg RCC_AHBPeriph_DMA1 + * @arg RCC_AHBPeriph_DMA2 + * @arg RCC_AHBPeriph_SRAM + * @arg RCC_AHBPeriph_FLITF + * @arg RCC_AHBPeriph_CRC + * @arg RCC_AHBPeriph_FSMC + * @arg RCC_AHBPeriph_SDIO + * + * @note SRAM and FLITF clock can be disabled only during sleep mode. + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB_PERIPH(RCC_AHBPeriph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->AHBENR |= RCC_AHBPeriph; + } + else + { + RCC->AHBENR &= ~RCC_AHBPeriph; + } +} + +/** + * @brief Enables or disables the High Speed APB (APB2) peripheral clock. + * @param RCC_APB2Periph: specifies the APB2 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB, + * RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE, + * RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1, + * RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1, + * RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3, + * RCC_APB2Periph_TIM15, RCC_APB2Periph_TIM16, RCC_APB2Periph_TIM17, + * RCC_APB2Periph_TIM9, RCC_APB2Periph_TIM10, RCC_APB2Periph_TIM11 + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB2ENR |= RCC_APB2Periph; + } + else + { + RCC->APB2ENR &= ~RCC_APB2Periph; + } +} + +/** + * @brief Enables or disables the Low Speed APB (APB1) peripheral clock. + * @param RCC_APB1Periph: specifies the APB1 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4, + * RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7, + * RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3, + * RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4, + * RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2, + * RCC_APB1Periph_USB, RCC_APB1Periph_CAN1, RCC_APB1Periph_BKP, + * RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_CEC, + * RCC_APB1Periph_TIM12, RCC_APB1Periph_TIM13, RCC_APB1Periph_TIM14 + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB1ENR |= RCC_APB1Periph; + } + else + { + RCC->APB1ENR &= ~RCC_APB1Periph; + } +} + +#ifdef STM32F10X_CL +/** + * @brief Forces or releases AHB peripheral reset. + * @note This function applies only to STM32 Connectivity line devices. + * @param RCC_AHBPeriph: specifies the AHB peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_AHBPeriph_OTG_FS + * @arg RCC_AHBPeriph_ETH_MAC + * @param NewState: new state of the specified peripheral reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB_PERIPH_RESET(RCC_AHBPeriph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->AHBRSTR |= RCC_AHBPeriph; + } + else + { + RCC->AHBRSTR &= ~RCC_AHBPeriph; + } +} +#endif /* STM32F10X_CL */ + +/** + * @brief Forces or releases High Speed APB (APB2) peripheral reset. + * @param RCC_APB2Periph: specifies the APB2 peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB, + * RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE, + * RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1, + * RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1, + * RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3, + * RCC_APB2Periph_TIM15, RCC_APB2Periph_TIM16, RCC_APB2Periph_TIM17, + * RCC_APB2Periph_TIM9, RCC_APB2Periph_TIM10, RCC_APB2Periph_TIM11 + * @param NewState: new state of the specified peripheral reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB2RSTR |= RCC_APB2Periph; + } + else + { + RCC->APB2RSTR &= ~RCC_APB2Periph; + } +} + +/** + * @brief Forces or releases Low Speed APB (APB1) peripheral reset. + * @param RCC_APB1Periph: specifies the APB1 peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4, + * RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7, + * RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3, + * RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4, + * RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2, + * RCC_APB1Periph_USB, RCC_APB1Periph_CAN1, RCC_APB1Periph_BKP, + * RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_CEC, + * RCC_APB1Periph_TIM12, RCC_APB1Periph_TIM13, RCC_APB1Periph_TIM14 + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB1RSTR |= RCC_APB1Periph; + } + else + { + RCC->APB1RSTR &= ~RCC_APB1Periph; + } +} + +/** + * @brief Forces or releases the Backup domain reset. + * @param NewState: new state of the Backup domain reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_BackupResetCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the Clock Security System. + * @param NewState: new state of the Clock Security System.. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_ClockSecuritySystemCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_CSSON_BB = (uint32_t)NewState; +} + +/** + * @brief Selects the clock source to output on MCO pin. + * @param RCC_MCO: specifies the clock source to output. + * + * For @b STM32_Connectivity_line_devices, this parameter can be one of the + * following values: + * @arg RCC_MCO_NoClock: No clock selected + * @arg RCC_MCO_SYSCLK: System clock selected + * @arg RCC_MCO_HSI: HSI oscillator clock selected + * @arg RCC_MCO_HSE: HSE oscillator clock selected + * @arg RCC_MCO_PLLCLK_Div2: PLL clock divided by 2 selected + * @arg RCC_MCO_PLL2CLK: PLL2 clock selected + * @arg RCC_MCO_PLL3CLK_Div2: PLL3 clock divided by 2 selected + * @arg RCC_MCO_XT1: External 3-25 MHz oscillator clock selected + * @arg RCC_MCO_PLL3CLK: PLL3 clock selected + * + * For @b other_STM32_devices, this parameter can be one of the following values: + * @arg RCC_MCO_NoClock: No clock selected + * @arg RCC_MCO_SYSCLK: System clock selected + * @arg RCC_MCO_HSI: HSI oscillator clock selected + * @arg RCC_MCO_HSE: HSE oscillator clock selected + * @arg RCC_MCO_PLLCLK_Div2: PLL clock divided by 2 selected + * + * @retval None + */ +void RCC_MCOConfig(uint8_t RCC_MCO) +{ + /* Check the parameters */ + assert_param(IS_RCC_MCO(RCC_MCO)); + + /* Perform Byte access to MCO bits to select the MCO source */ + *(__IO uint8_t *) CFGR_BYTE4_ADDRESS = RCC_MCO; +} + +/** + * @brief Checks whether the specified RCC flag is set or not. + * @param RCC_FLAG: specifies the flag to check. + * + * For @b STM32_Connectivity_line_devices, this parameter can be one of the + * following values: + * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready + * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready + * @arg RCC_FLAG_PLLRDY: PLL clock ready + * @arg RCC_FLAG_PLL2RDY: PLL2 clock ready + * @arg RCC_FLAG_PLL3RDY: PLL3 clock ready + * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready + * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready + * @arg RCC_FLAG_PINRST: Pin reset + * @arg RCC_FLAG_PORRST: POR/PDR reset + * @arg RCC_FLAG_SFTRST: Software reset + * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset + * @arg RCC_FLAG_WWDGRST: Window Watchdog reset + * @arg RCC_FLAG_LPWRRST: Low Power reset + * + * For @b other_STM32_devices, this parameter can be one of the following values: + * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready + * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready + * @arg RCC_FLAG_PLLRDY: PLL clock ready + * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready + * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready + * @arg RCC_FLAG_PINRST: Pin reset + * @arg RCC_FLAG_PORRST: POR/PDR reset + * @arg RCC_FLAG_SFTRST: Software reset + * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset + * @arg RCC_FLAG_WWDGRST: Window Watchdog reset + * @arg RCC_FLAG_LPWRRST: Low Power reset + * + * @retval The new state of RCC_FLAG (SET or RESET). + */ +FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG) +{ + uint32_t tmp = 0; + uint32_t statusreg = 0; + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_RCC_FLAG(RCC_FLAG)); + + /* Get the RCC register index */ + tmp = RCC_FLAG >> 5; + if (tmp == 1) /* The flag to check is in CR register */ + { + statusreg = RCC->CR; + } + else if (tmp == 2) /* The flag to check is in BDCR register */ + { + statusreg = RCC->BDCR; + } + else /* The flag to check is in CSR register */ + { + statusreg = RCC->CSR; + } + + /* Get the flag position */ + tmp = RCC_FLAG & FLAG_Mask; + if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + + /* Return the flag status */ + return bitstatus; +} + +/** + * @brief Clears the RCC reset flags. + * @note The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST, RCC_FLAG_SFTRST, + * RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST + * @param None + * @retval None + */ +void RCC_ClearFlag(void) +{ + /* Set RMVF bit to clear the reset flags */ + RCC->CSR |= CSR_RMVF_Set; +} + +/** + * @brief Checks whether the specified RCC interrupt has occurred or not. + * @param RCC_IT: specifies the RCC interrupt source to check. + * + * For @b STM32_Connectivity_line_devices, this parameter can be one of the + * following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * @arg RCC_IT_PLL2RDY: PLL2 ready interrupt + * @arg RCC_IT_PLL3RDY: PLL3 ready interrupt + * @arg RCC_IT_CSS: Clock Security System interrupt + * + * For @b other_STM32_devices, this parameter can be one of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * @arg RCC_IT_CSS: Clock Security System interrupt + * + * @retval The new state of RCC_IT (SET or RESET). + */ +ITStatus RCC_GetITStatus(uint8_t RCC_IT) +{ + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_RCC_GET_IT(RCC_IT)); + + /* Check the status of the specified RCC interrupt */ + if ((RCC->CIR & RCC_IT) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + + /* Return the RCC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the RCC's interrupt pending bits. + * @param RCC_IT: specifies the interrupt pending bit to clear. + * + * For @b STM32_Connectivity_line_devices, this parameter can be any combination + * of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * @arg RCC_IT_PLL2RDY: PLL2 ready interrupt + * @arg RCC_IT_PLL3RDY: PLL3 ready interrupt + * @arg RCC_IT_CSS: Clock Security System interrupt + * + * For @b other_STM32_devices, this parameter can be any combination of the + * following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * + * @arg RCC_IT_CSS: Clock Security System interrupt + * @retval None + */ +void RCC_ClearITPendingBit(uint8_t RCC_IT) +{ + /* Check the parameters */ + assert_param(IS_RCC_CLEAR_IT(RCC_IT)); + + /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt + pending bits */ + *(__IO uint8_t *) CIR_BYTE3_ADDRESS = RCC_IT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c new file mode 100644 index 0000000..f05aef5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c @@ -0,0 +1,339 @@ +/** + ****************************************************************************** + * @file stm32f10x_rtc.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the RTC firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_rtc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup RTC + * @brief RTC driver modules + * @{ + */ + +/** @defgroup RTC_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + +/** @defgroup RTC_Private_Defines + * @{ + */ +#define RTC_LSB_MASK ((uint32_t)0x0000FFFF) /*!< RTC LSB Mask */ +#define PRLH_MSB_MASK ((uint32_t)0x000F0000) /*!< RTC Prescaler MSB Mask */ + +/** + * @} + */ + +/** @defgroup RTC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup RTC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup RTC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup RTC_Private_Functions + * @{ + */ + +/** + * @brief Enables or disables the specified RTC interrupts. + * @param RTC_IT: specifies the RTC interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg RTC_IT_OW: Overflow interrupt + * @arg RTC_IT_ALR: Alarm interrupt + * @arg RTC_IT_SEC: Second interrupt + * @param NewState: new state of the specified RTC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_ITConfig(uint16_t RTC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RTC_IT(RTC_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RTC->CRH |= RTC_IT; + } + else + { + RTC->CRH &= (uint16_t)~RTC_IT; + } +} + +/** + * @brief Enters the RTC configuration mode. + * @param None + * @retval None + */ +void RTC_EnterConfigMode(void) +{ + /* Set the CNF flag to enter in the Configuration Mode */ + RTC->CRL |= RTC_CRL_CNF; +} + +/** + * @brief Exits from the RTC configuration mode. + * @param None + * @retval None + */ +void RTC_ExitConfigMode(void) +{ + /* Reset the CNF flag to exit from the Configuration Mode */ + RTC->CRL &= (uint16_t)~((uint16_t)RTC_CRL_CNF); +} + +/** + * @brief Gets the RTC counter value. + * @param None + * @retval RTC counter value. + */ +uint32_t RTC_GetCounter(void) +{ + uint16_t tmp = 0; + tmp = RTC->CNTL; + return (((uint32_t)RTC->CNTH << 16 ) | tmp) ; +} + +/** + * @brief Sets the RTC counter value. + * @param CounterValue: RTC counter new value. + * @retval None + */ +void RTC_SetCounter(uint32_t CounterValue) +{ + RTC_EnterConfigMode(); + /* Set RTC COUNTER MSB word */ + RTC->CNTH = CounterValue >> 16; + /* Set RTC COUNTER LSB word */ + RTC->CNTL = (CounterValue & RTC_LSB_MASK); + RTC_ExitConfigMode(); +} + +/** + * @brief Sets the RTC prescaler value. + * @param PrescalerValue: RTC prescaler new value. + * @retval None + */ +void RTC_SetPrescaler(uint32_t PrescalerValue) +{ + /* Check the parameters */ + assert_param(IS_RTC_PRESCALER(PrescalerValue)); + + RTC_EnterConfigMode(); + /* Set RTC PRESCALER MSB word */ + RTC->PRLH = (PrescalerValue & PRLH_MSB_MASK) >> 16; + /* Set RTC PRESCALER LSB word */ + RTC->PRLL = (PrescalerValue & RTC_LSB_MASK); + RTC_ExitConfigMode(); +} + +/** + * @brief Sets the RTC alarm value. + * @param AlarmValue: RTC alarm new value. + * @retval None + */ +void RTC_SetAlarm(uint32_t AlarmValue) +{ + RTC_EnterConfigMode(); + /* Set the ALARM MSB word */ + RTC->ALRH = AlarmValue >> 16; + /* Set the ALARM LSB word */ + RTC->ALRL = (AlarmValue & RTC_LSB_MASK); + RTC_ExitConfigMode(); +} + +/** + * @brief Gets the RTC divider value. + * @param None + * @retval RTC Divider value. + */ +uint32_t RTC_GetDivider(void) +{ + uint32_t tmp = 0x00; + tmp = ((uint32_t)RTC->DIVH & (uint32_t)0x000F) << 16; + tmp |= RTC->DIVL; + return tmp; +} + +/** + * @brief Waits until last write operation on RTC registers has finished. + * @note This function must be called before any write to RTC registers. + * @param None + * @retval None + */ +void RTC_WaitForLastTask(void) +{ + /* Loop until RTOFF flag is set */ + while ((RTC->CRL & RTC_FLAG_RTOFF) == (uint16_t)RESET) + { + } +} + +/** + * @brief Waits until the RTC registers (RTC_CNT, RTC_ALR and RTC_PRL) + * are synchronized with RTC APB clock. + * @note This function must be called before any read operation after an APB reset + * or an APB clock stop. + * @param None + * @retval None + */ +void RTC_WaitForSynchro(void) +{ + /* Clear RSF flag */ + RTC->CRL &= (uint16_t)~RTC_FLAG_RSF; + /* Loop until RSF flag is set */ + while ((RTC->CRL & RTC_FLAG_RSF) == (uint16_t)RESET) + { + } +} + +/** + * @brief Checks whether the specified RTC flag is set or not. + * @param RTC_FLAG: specifies the flag to check. + * This parameter can be one the following values: + * @arg RTC_FLAG_RTOFF: RTC Operation OFF flag + * @arg RTC_FLAG_RSF: Registers Synchronized flag + * @arg RTC_FLAG_OW: Overflow flag + * @arg RTC_FLAG_ALR: Alarm flag + * @arg RTC_FLAG_SEC: Second flag + * @retval The new state of RTC_FLAG (SET or RESET). + */ +FlagStatus RTC_GetFlagStatus(uint16_t RTC_FLAG) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_RTC_GET_FLAG(RTC_FLAG)); + + if ((RTC->CRL & RTC_FLAG) != (uint16_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the RTC's pending flags. + * @param RTC_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg RTC_FLAG_RSF: Registers Synchronized flag. This flag is cleared only after + * an APB reset or an APB Clock stop. + * @arg RTC_FLAG_OW: Overflow flag + * @arg RTC_FLAG_ALR: Alarm flag + * @arg RTC_FLAG_SEC: Second flag + * @retval None + */ +void RTC_ClearFlag(uint16_t RTC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_RTC_CLEAR_FLAG(RTC_FLAG)); + + /* Clear the corresponding RTC flag */ + RTC->CRL &= (uint16_t)~RTC_FLAG; +} + +/** + * @brief Checks whether the specified RTC interrupt has occurred or not. + * @param RTC_IT: specifies the RTC interrupts sources to check. + * This parameter can be one of the following values: + * @arg RTC_IT_OW: Overflow interrupt + * @arg RTC_IT_ALR: Alarm interrupt + * @arg RTC_IT_SEC: Second interrupt + * @retval The new state of the RTC_IT (SET or RESET). + */ +ITStatus RTC_GetITStatus(uint16_t RTC_IT) +{ + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_RTC_GET_IT(RTC_IT)); + + bitstatus = (ITStatus)(RTC->CRL & RTC_IT); + if (((RTC->CRH & RTC_IT) != (uint16_t)RESET) && (bitstatus != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the RTC's interrupt pending bits. + * @param RTC_IT: specifies the interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg RTC_IT_OW: Overflow interrupt + * @arg RTC_IT_ALR: Alarm interrupt + * @arg RTC_IT_SEC: Second interrupt + * @retval None + */ +void RTC_ClearITPendingBit(uint16_t RTC_IT) +{ + /* Check the parameters */ + assert_param(IS_RTC_IT(RTC_IT)); + + /* Clear the corresponding RTC pending bit */ + RTC->CRL &= (uint16_t)~RTC_IT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c new file mode 100644 index 0000000..bc1719d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c @@ -0,0 +1,799 @@ +/** + ****************************************************************************** + * @file stm32f10x_sdio.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the SDIO firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_sdio.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup SDIO + * @brief SDIO driver modules + * @{ + */ + +/** @defgroup SDIO_Private_TypesDefinitions + * @{ + */ + +/* ------------ SDIO registers bit address in the alias region ----------- */ +#define SDIO_OFFSET (SDIO_BASE - PERIPH_BASE) + +/* --- CLKCR Register ---*/ + +/* Alias word address of CLKEN bit */ +#define CLKCR_OFFSET (SDIO_OFFSET + 0x04) +#define CLKEN_BitNumber 0x08 +#define CLKCR_CLKEN_BB (PERIPH_BB_BASE + (CLKCR_OFFSET * 32) + (CLKEN_BitNumber * 4)) + +/* --- CMD Register ---*/ + +/* Alias word address of SDIOSUSPEND bit */ +#define CMD_OFFSET (SDIO_OFFSET + 0x0C) +#define SDIOSUSPEND_BitNumber 0x0B +#define CMD_SDIOSUSPEND_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (SDIOSUSPEND_BitNumber * 4)) + +/* Alias word address of ENCMDCOMPL bit */ +#define ENCMDCOMPL_BitNumber 0x0C +#define CMD_ENCMDCOMPL_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ENCMDCOMPL_BitNumber * 4)) + +/* Alias word address of NIEN bit */ +#define NIEN_BitNumber 0x0D +#define CMD_NIEN_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (NIEN_BitNumber * 4)) + +/* Alias word address of ATACMD bit */ +#define ATACMD_BitNumber 0x0E +#define CMD_ATACMD_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ATACMD_BitNumber * 4)) + +/* --- DCTRL Register ---*/ + +/* Alias word address of DMAEN bit */ +#define DCTRL_OFFSET (SDIO_OFFSET + 0x2C) +#define DMAEN_BitNumber 0x03 +#define DCTRL_DMAEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (DMAEN_BitNumber * 4)) + +/* Alias word address of RWSTART bit */ +#define RWSTART_BitNumber 0x08 +#define DCTRL_RWSTART_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTART_BitNumber * 4)) + +/* Alias word address of RWSTOP bit */ +#define RWSTOP_BitNumber 0x09 +#define DCTRL_RWSTOP_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTOP_BitNumber * 4)) + +/* Alias word address of RWMOD bit */ +#define RWMOD_BitNumber 0x0A +#define DCTRL_RWMOD_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWMOD_BitNumber * 4)) + +/* Alias word address of SDIOEN bit */ +#define SDIOEN_BitNumber 0x0B +#define DCTRL_SDIOEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (SDIOEN_BitNumber * 4)) + +/* ---------------------- SDIO registers bit mask ------------------------ */ + +/* --- CLKCR Register ---*/ + +/* CLKCR register clear mask */ +#define CLKCR_CLEAR_MASK ((uint32_t)0xFFFF8100) + +/* --- PWRCTRL Register ---*/ + +/* SDIO PWRCTRL Mask */ +#define PWR_PWRCTRL_MASK ((uint32_t)0xFFFFFFFC) + +/* --- DCTRL Register ---*/ + +/* SDIO DCTRL Clear Mask */ +#define DCTRL_CLEAR_MASK ((uint32_t)0xFFFFFF08) + +/* --- CMD Register ---*/ + +/* CMD Register clear mask */ +#define CMD_CLEAR_MASK ((uint32_t)0xFFFFF800) + +/* SDIO RESP Registers Address */ +#define SDIO_RESP_ADDR ((uint32_t)(SDIO_BASE + 0x14)) + +/** + * @} + */ + +/** @defgroup SDIO_Private_Defines + * @{ + */ + +/** + * @} + */ + +/** @defgroup SDIO_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup SDIO_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup SDIO_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup SDIO_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the SDIO peripheral registers to their default reset values. + * @param None + * @retval None + */ +void SDIO_DeInit(void) +{ + SDIO->POWER = 0x00000000; + SDIO->CLKCR = 0x00000000; + SDIO->ARG = 0x00000000; + SDIO->CMD = 0x00000000; + SDIO->DTIMER = 0x00000000; + SDIO->DLEN = 0x00000000; + SDIO->DCTRL = 0x00000000; + SDIO->ICR = 0x00C007FF; + SDIO->MASK = 0x00000000; +} + +/** + * @brief Initializes the SDIO peripheral according to the specified + * parameters in the SDIO_InitStruct. + * @param SDIO_InitStruct : pointer to a SDIO_InitTypeDef structure + * that contains the configuration information for the SDIO peripheral. + * @retval None + */ +void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_CLOCK_EDGE(SDIO_InitStruct->SDIO_ClockEdge)); + assert_param(IS_SDIO_CLOCK_BYPASS(SDIO_InitStruct->SDIO_ClockBypass)); + assert_param(IS_SDIO_CLOCK_POWER_SAVE(SDIO_InitStruct->SDIO_ClockPowerSave)); + assert_param(IS_SDIO_BUS_WIDE(SDIO_InitStruct->SDIO_BusWide)); + assert_param(IS_SDIO_HARDWARE_FLOW_CONTROL(SDIO_InitStruct->SDIO_HardwareFlowControl)); + +/*---------------------------- SDIO CLKCR Configuration ------------------------*/ + /* Get the SDIO CLKCR value */ + tmpreg = SDIO->CLKCR; + + /* Clear CLKDIV, PWRSAV, BYPASS, WIDBUS, NEGEDGE, HWFC_EN bits */ + tmpreg &= CLKCR_CLEAR_MASK; + + /* Set CLKDIV bits according to SDIO_ClockDiv value */ + /* Set PWRSAV bit according to SDIO_ClockPowerSave value */ + /* Set BYPASS bit according to SDIO_ClockBypass value */ + /* Set WIDBUS bits according to SDIO_BusWide value */ + /* Set NEGEDGE bits according to SDIO_ClockEdge value */ + /* Set HWFC_EN bits according to SDIO_HardwareFlowControl value */ + tmpreg |= (SDIO_InitStruct->SDIO_ClockDiv | SDIO_InitStruct->SDIO_ClockPowerSave | + SDIO_InitStruct->SDIO_ClockBypass | SDIO_InitStruct->SDIO_BusWide | + SDIO_InitStruct->SDIO_ClockEdge | SDIO_InitStruct->SDIO_HardwareFlowControl); + + /* Write to SDIO CLKCR */ + SDIO->CLKCR = tmpreg; +} + +/** + * @brief Fills each SDIO_InitStruct member with its default value. + * @param SDIO_InitStruct: pointer to an SDIO_InitTypeDef structure which + * will be initialized. + * @retval None + */ +void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct) +{ + /* SDIO_InitStruct members default value */ + SDIO_InitStruct->SDIO_ClockDiv = 0x00; + SDIO_InitStruct->SDIO_ClockEdge = SDIO_ClockEdge_Rising; + SDIO_InitStruct->SDIO_ClockBypass = SDIO_ClockBypass_Disable; + SDIO_InitStruct->SDIO_ClockPowerSave = SDIO_ClockPowerSave_Disable; + SDIO_InitStruct->SDIO_BusWide = SDIO_BusWide_1b; + SDIO_InitStruct->SDIO_HardwareFlowControl = SDIO_HardwareFlowControl_Disable; +} + +/** + * @brief Enables or disables the SDIO Clock. + * @param NewState: new state of the SDIO Clock. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_ClockCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CLKCR_CLKEN_BB = (uint32_t)NewState; +} + +/** + * @brief Sets the power status of the controller. + * @param SDIO_PowerState: new state of the Power state. + * This parameter can be one of the following values: + * @arg SDIO_PowerState_OFF + * @arg SDIO_PowerState_ON + * @retval None + */ +void SDIO_SetPowerState(uint32_t SDIO_PowerState) +{ + /* Check the parameters */ + assert_param(IS_SDIO_POWER_STATE(SDIO_PowerState)); + + SDIO->POWER &= PWR_PWRCTRL_MASK; + SDIO->POWER |= SDIO_PowerState; +} + +/** + * @brief Gets the power status of the controller. + * @param None + * @retval Power status of the controller. The returned value can + * be one of the following: + * - 0x00: Power OFF + * - 0x02: Power UP + * - 0x03: Power ON + */ +uint32_t SDIO_GetPowerState(void) +{ + return (SDIO->POWER & (~PWR_PWRCTRL_MASK)); +} + +/** + * @brief Enables or disables the SDIO interrupts. + * @param SDIO_IT: specifies the SDIO interrupt sources to be enabled or disabled. + * This parameter can be one or a combination of the following values: + * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt + * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt + * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt + * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt + * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt + * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt + * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt + * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt + * @arg SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is zero) interrupt + * @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide + * bus mode interrupt + * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt + * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt + * @arg SDIO_IT_TXACT: Data transmit in progress interrupt + * @arg SDIO_IT_RXACT: Data receive in progress interrupt + * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt + * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt + * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt + * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt + * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt + * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt + * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt + * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt + * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt + * @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 interrupt + * @param NewState: new state of the specified SDIO interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_ITConfig(uint32_t SDIO_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SDIO_IT(SDIO_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the SDIO interrupts */ + SDIO->MASK |= SDIO_IT; + } + else + { + /* Disable the SDIO interrupts */ + SDIO->MASK &= ~SDIO_IT; + } +} + +/** + * @brief Enables or disables the SDIO DMA request. + * @param NewState: new state of the selected SDIO DMA request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_DMACmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_DMAEN_BB = (uint32_t)NewState; +} + +/** + * @brief Initializes the SDIO Command according to the specified + * parameters in the SDIO_CmdInitStruct and send the command. + * @param SDIO_CmdInitStruct : pointer to a SDIO_CmdInitTypeDef + * structure that contains the configuration information for the SDIO command. + * @retval None + */ +void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_CMD_INDEX(SDIO_CmdInitStruct->SDIO_CmdIndex)); + assert_param(IS_SDIO_RESPONSE(SDIO_CmdInitStruct->SDIO_Response)); + assert_param(IS_SDIO_WAIT(SDIO_CmdInitStruct->SDIO_Wait)); + assert_param(IS_SDIO_CPSM(SDIO_CmdInitStruct->SDIO_CPSM)); + +/*---------------------------- SDIO ARG Configuration ------------------------*/ + /* Set the SDIO Argument value */ + SDIO->ARG = SDIO_CmdInitStruct->SDIO_Argument; + +/*---------------------------- SDIO CMD Configuration ------------------------*/ + /* Get the SDIO CMD value */ + tmpreg = SDIO->CMD; + /* Clear CMDINDEX, WAITRESP, WAITINT, WAITPEND, CPSMEN bits */ + tmpreg &= CMD_CLEAR_MASK; + /* Set CMDINDEX bits according to SDIO_CmdIndex value */ + /* Set WAITRESP bits according to SDIO_Response value */ + /* Set WAITINT and WAITPEND bits according to SDIO_Wait value */ + /* Set CPSMEN bits according to SDIO_CPSM value */ + tmpreg |= (uint32_t)SDIO_CmdInitStruct->SDIO_CmdIndex | SDIO_CmdInitStruct->SDIO_Response + | SDIO_CmdInitStruct->SDIO_Wait | SDIO_CmdInitStruct->SDIO_CPSM; + + /* Write to SDIO CMD */ + SDIO->CMD = tmpreg; +} + +/** + * @brief Fills each SDIO_CmdInitStruct member with its default value. + * @param SDIO_CmdInitStruct: pointer to an SDIO_CmdInitTypeDef + * structure which will be initialized. + * @retval None + */ +void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct) +{ + /* SDIO_CmdInitStruct members default value */ + SDIO_CmdInitStruct->SDIO_Argument = 0x00; + SDIO_CmdInitStruct->SDIO_CmdIndex = 0x00; + SDIO_CmdInitStruct->SDIO_Response = SDIO_Response_No; + SDIO_CmdInitStruct->SDIO_Wait = SDIO_Wait_No; + SDIO_CmdInitStruct->SDIO_CPSM = SDIO_CPSM_Disable; +} + +/** + * @brief Returns command index of last command for which response received. + * @param None + * @retval Returns the command index of the last command response received. + */ +uint8_t SDIO_GetCommandResponse(void) +{ + return (uint8_t)(SDIO->RESPCMD); +} + +/** + * @brief Returns response received from the card for the last command. + * @param SDIO_RESP: Specifies the SDIO response register. + * This parameter can be one of the following values: + * @arg SDIO_RESP1: Response Register 1 + * @arg SDIO_RESP2: Response Register 2 + * @arg SDIO_RESP3: Response Register 3 + * @arg SDIO_RESP4: Response Register 4 + * @retval The Corresponding response register value. + */ +uint32_t SDIO_GetResponse(uint32_t SDIO_RESP) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_RESP(SDIO_RESP)); + + tmp = SDIO_RESP_ADDR + SDIO_RESP; + + return (*(__IO uint32_t *) tmp); +} + +/** + * @brief Initializes the SDIO data path according to the specified + * parameters in the SDIO_DataInitStruct. + * @param SDIO_DataInitStruct : pointer to a SDIO_DataInitTypeDef structure that + * contains the configuration information for the SDIO command. + * @retval None + */ +void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_DATA_LENGTH(SDIO_DataInitStruct->SDIO_DataLength)); + assert_param(IS_SDIO_BLOCK_SIZE(SDIO_DataInitStruct->SDIO_DataBlockSize)); + assert_param(IS_SDIO_TRANSFER_DIR(SDIO_DataInitStruct->SDIO_TransferDir)); + assert_param(IS_SDIO_TRANSFER_MODE(SDIO_DataInitStruct->SDIO_TransferMode)); + assert_param(IS_SDIO_DPSM(SDIO_DataInitStruct->SDIO_DPSM)); + +/*---------------------------- SDIO DTIMER Configuration ---------------------*/ + /* Set the SDIO Data TimeOut value */ + SDIO->DTIMER = SDIO_DataInitStruct->SDIO_DataTimeOut; + +/*---------------------------- SDIO DLEN Configuration -----------------------*/ + /* Set the SDIO DataLength value */ + SDIO->DLEN = SDIO_DataInitStruct->SDIO_DataLength; + +/*---------------------------- SDIO DCTRL Configuration ----------------------*/ + /* Get the SDIO DCTRL value */ + tmpreg = SDIO->DCTRL; + /* Clear DEN, DTMODE, DTDIR and DBCKSIZE bits */ + tmpreg &= DCTRL_CLEAR_MASK; + /* Set DEN bit according to SDIO_DPSM value */ + /* Set DTMODE bit according to SDIO_TransferMode value */ + /* Set DTDIR bit according to SDIO_TransferDir value */ + /* Set DBCKSIZE bits according to SDIO_DataBlockSize value */ + tmpreg |= (uint32_t)SDIO_DataInitStruct->SDIO_DataBlockSize | SDIO_DataInitStruct->SDIO_TransferDir + | SDIO_DataInitStruct->SDIO_TransferMode | SDIO_DataInitStruct->SDIO_DPSM; + + /* Write to SDIO DCTRL */ + SDIO->DCTRL = tmpreg; +} + +/** + * @brief Fills each SDIO_DataInitStruct member with its default value. + * @param SDIO_DataInitStruct: pointer to an SDIO_DataInitTypeDef structure which + * will be initialized. + * @retval None + */ +void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct) +{ + /* SDIO_DataInitStruct members default value */ + SDIO_DataInitStruct->SDIO_DataTimeOut = 0xFFFFFFFF; + SDIO_DataInitStruct->SDIO_DataLength = 0x00; + SDIO_DataInitStruct->SDIO_DataBlockSize = SDIO_DataBlockSize_1b; + SDIO_DataInitStruct->SDIO_TransferDir = SDIO_TransferDir_ToCard; + SDIO_DataInitStruct->SDIO_TransferMode = SDIO_TransferMode_Block; + SDIO_DataInitStruct->SDIO_DPSM = SDIO_DPSM_Disable; +} + +/** + * @brief Returns number of remaining data bytes to be transferred. + * @param None + * @retval Number of remaining data bytes to be transferred + */ +uint32_t SDIO_GetDataCounter(void) +{ + return SDIO->DCOUNT; +} + +/** + * @brief Read one data word from Rx FIFO. + * @param None + * @retval Data received + */ +uint32_t SDIO_ReadData(void) +{ + return SDIO->FIFO; +} + +/** + * @brief Write one data word to Tx FIFO. + * @param Data: 32-bit data word to write. + * @retval None + */ +void SDIO_WriteData(uint32_t Data) +{ + SDIO->FIFO = Data; +} + +/** + * @brief Returns the number of words left to be written to or read from FIFO. + * @param None + * @retval Remaining number of words. + */ +uint32_t SDIO_GetFIFOCount(void) +{ + return SDIO->FIFOCNT; +} + +/** + * @brief Starts the SD I/O Read Wait operation. + * @param NewState: new state of the Start SDIO Read Wait operation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_StartSDIOReadWait(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_RWSTART_BB = (uint32_t) NewState; +} + +/** + * @brief Stops the SD I/O Read Wait operation. + * @param NewState: new state of the Stop SDIO Read Wait operation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_StopSDIOReadWait(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_RWSTOP_BB = (uint32_t) NewState; +} + +/** + * @brief Sets one of the two options of inserting read wait interval. + * @param SDIO_ReadWaitMode: SD I/O Read Wait operation mode. + * This parameter can be: + * @arg SDIO_ReadWaitMode_CLK: Read Wait control by stopping SDIOCLK + * @arg SDIO_ReadWaitMode_DATA2: Read Wait control using SDIO_DATA2 + * @retval None + */ +void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode) +{ + /* Check the parameters */ + assert_param(IS_SDIO_READWAIT_MODE(SDIO_ReadWaitMode)); + + *(__IO uint32_t *) DCTRL_RWMOD_BB = SDIO_ReadWaitMode; +} + +/** + * @brief Enables or disables the SD I/O Mode Operation. + * @param NewState: new state of SDIO specific operation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_SetSDIOOperation(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_SDIOEN_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the SD I/O Mode suspend command sending. + * @param NewState: new state of the SD I/O Mode suspend command. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_SendSDIOSuspendCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_SDIOSUSPEND_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the command completion signal. + * @param NewState: new state of command completion signal. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_CommandCompletionCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_ENCMDCOMPL_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the CE-ATA interrupt. + * @param NewState: new state of CE-ATA interrupt. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_CEATAITCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_NIEN_BB = (uint32_t)((~((uint32_t)NewState)) & ((uint32_t)0x1)); +} + +/** + * @brief Sends CE-ATA command (CMD61). + * @param NewState: new state of CE-ATA command. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_SendCEATACmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_ATACMD_BB = (uint32_t)NewState; +} + +/** + * @brief Checks whether the specified SDIO flag is set or not. + * @param SDIO_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) + * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) + * @arg SDIO_FLAG_CTIMEOUT: Command response timeout + * @arg SDIO_FLAG_DTIMEOUT: Data timeout + * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error + * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error + * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) + * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) + * @arg SDIO_FLAG_DATAEND: Data end (data counter, SDIDCOUNT, is zero) + * @arg SDIO_FLAG_STBITERR: Start bit not detected on all data signals in wide + * bus mode. + * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) + * @arg SDIO_FLAG_CMDACT: Command transfer in progress + * @arg SDIO_FLAG_TXACT: Data transmit in progress + * @arg SDIO_FLAG_RXACT: Data receive in progress + * @arg SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty + * @arg SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full + * @arg SDIO_FLAG_TXFIFOF: Transmit FIFO full + * @arg SDIO_FLAG_RXFIFOF: Receive FIFO full + * @arg SDIO_FLAG_TXFIFOE: Transmit FIFO empty + * @arg SDIO_FLAG_RXFIFOE: Receive FIFO empty + * @arg SDIO_FLAG_TXDAVL: Data available in transmit FIFO + * @arg SDIO_FLAG_RXDAVL: Data available in receive FIFO + * @arg SDIO_FLAG_SDIOIT: SD I/O interrupt received + * @arg SDIO_FLAG_CEATAEND: CE-ATA command completion signal received for CMD61 + * @retval The new state of SDIO_FLAG (SET or RESET). + */ +FlagStatus SDIO_GetFlagStatus(uint32_t SDIO_FLAG) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_SDIO_FLAG(SDIO_FLAG)); + + if ((SDIO->STA & SDIO_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the SDIO's pending flags. + * @param SDIO_FLAG: specifies the flag to clear. + * This parameter can be one or a combination of the following values: + * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) + * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) + * @arg SDIO_FLAG_CTIMEOUT: Command response timeout + * @arg SDIO_FLAG_DTIMEOUT: Data timeout + * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error + * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error + * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) + * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) + * @arg SDIO_FLAG_DATAEND: Data end (data counter, SDIDCOUNT, is zero) + * @arg SDIO_FLAG_STBITERR: Start bit not detected on all data signals in wide + * bus mode + * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) + * @arg SDIO_FLAG_SDIOIT: SD I/O interrupt received + * @arg SDIO_FLAG_CEATAEND: CE-ATA command completion signal received for CMD61 + * @retval None + */ +void SDIO_ClearFlag(uint32_t SDIO_FLAG) +{ + /* Check the parameters */ + assert_param(IS_SDIO_CLEAR_FLAG(SDIO_FLAG)); + + SDIO->ICR = SDIO_FLAG; +} + +/** + * @brief Checks whether the specified SDIO interrupt has occurred or not. + * @param SDIO_IT: specifies the SDIO interrupt source to check. + * This parameter can be one of the following values: + * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt + * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt + * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt + * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt + * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt + * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt + * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt + * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt + * @arg SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is zero) interrupt + * @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide + * bus mode interrupt + * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt + * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt + * @arg SDIO_IT_TXACT: Data transmit in progress interrupt + * @arg SDIO_IT_RXACT: Data receive in progress interrupt + * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt + * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt + * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt + * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt + * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt + * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt + * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt + * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt + * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt + * @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 interrupt + * @retval The new state of SDIO_IT (SET or RESET). + */ +ITStatus SDIO_GetITStatus(uint32_t SDIO_IT) +{ + ITStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_SDIO_GET_IT(SDIO_IT)); + if ((SDIO->STA & SDIO_IT) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the SDIO's interrupt pending bits. + * @param SDIO_IT: specifies the interrupt pending bit to clear. + * This parameter can be one or a combination of the following values: + * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt + * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt + * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt + * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt + * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt + * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt + * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt + * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt + * @arg SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is zero) interrupt + * @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide + * bus mode interrupt + * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt + * @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 + * @retval None + */ +void SDIO_ClearITPendingBit(uint32_t SDIO_IT) +{ + /* Check the parameters */ + assert_param(IS_SDIO_CLEAR_IT(SDIO_IT)); + + SDIO->ICR = SDIO_IT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c new file mode 100644 index 0000000..4ec65b2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c @@ -0,0 +1,908 @@ +/** + ****************************************************************************** + * @file stm32f10x_spi.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the SPI firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_spi.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup SPI + * @brief SPI driver modules + * @{ + */ + +/** @defgroup SPI_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + + +/** @defgroup SPI_Private_Defines + * @{ + */ + +/* SPI SPE mask */ +#define CR1_SPE_Set ((uint16_t)0x0040) +#define CR1_SPE_Reset ((uint16_t)0xFFBF) + +/* I2S I2SE mask */ +#define I2SCFGR_I2SE_Set ((uint16_t)0x0400) +#define I2SCFGR_I2SE_Reset ((uint16_t)0xFBFF) + +/* SPI CRCNext mask */ +#define CR1_CRCNext_Set ((uint16_t)0x1000) + +/* SPI CRCEN mask */ +#define CR1_CRCEN_Set ((uint16_t)0x2000) +#define CR1_CRCEN_Reset ((uint16_t)0xDFFF) + +/* SPI SSOE mask */ +#define CR2_SSOE_Set ((uint16_t)0x0004) +#define CR2_SSOE_Reset ((uint16_t)0xFFFB) + +/* SPI registers Masks */ +#define CR1_CLEAR_Mask ((uint16_t)0x3040) +#define I2SCFGR_CLEAR_Mask ((uint16_t)0xF040) + +/* SPI or I2S mode selection masks */ +#define SPI_Mode_Select ((uint16_t)0xF7FF) +#define I2S_Mode_Select ((uint16_t)0x0800) + +/* I2S clock source selection masks */ +#define I2S2_CLOCK_SRC ((uint32_t)(0x00020000)) +#define I2S3_CLOCK_SRC ((uint32_t)(0x00040000)) +#define I2S_MUL_MASK ((uint32_t)(0x0000F000)) +#define I2S_DIV_MASK ((uint32_t)(0x000000F0)) + +/** + * @} + */ + +/** @defgroup SPI_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup SPI_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup SPI_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup SPI_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the SPIx peripheral registers to their default + * reset values (Affects also the I2Ss). + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval None + */ +void SPI_I2S_DeInit(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + if (SPIx == SPI1) + { + /* Enable SPI1 reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, ENABLE); + /* Release SPI1 from reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, DISABLE); + } + else if (SPIx == SPI2) + { + /* Enable SPI2 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE); + /* Release SPI2 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, DISABLE); + } + else + { + if (SPIx == SPI3) + { + /* Enable SPI3 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE); + /* Release SPI3 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, DISABLE); + } + } +} + +/** + * @brief Initializes the SPIx peripheral according to the specified + * parameters in the SPI_InitStruct. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_InitStruct: pointer to a SPI_InitTypeDef structure that + * contains the configuration information for the specified SPI peripheral. + * @retval None + */ +void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct) +{ + uint16_t tmpreg = 0; + + /* check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Check the SPI parameters */ + assert_param(IS_SPI_DIRECTION_MODE(SPI_InitStruct->SPI_Direction)); + assert_param(IS_SPI_MODE(SPI_InitStruct->SPI_Mode)); + assert_param(IS_SPI_DATASIZE(SPI_InitStruct->SPI_DataSize)); + assert_param(IS_SPI_CPOL(SPI_InitStruct->SPI_CPOL)); + assert_param(IS_SPI_CPHA(SPI_InitStruct->SPI_CPHA)); + assert_param(IS_SPI_NSS(SPI_InitStruct->SPI_NSS)); + assert_param(IS_SPI_BAUDRATE_PRESCALER(SPI_InitStruct->SPI_BaudRatePrescaler)); + assert_param(IS_SPI_FIRST_BIT(SPI_InitStruct->SPI_FirstBit)); + assert_param(IS_SPI_CRC_POLYNOMIAL(SPI_InitStruct->SPI_CRCPolynomial)); + +/*---------------------------- SPIx CR1 Configuration ------------------------*/ + /* Get the SPIx CR1 value */ + tmpreg = SPIx->CR1; + /* Clear BIDIMode, BIDIOE, RxONLY, SSM, SSI, LSBFirst, BR, MSTR, CPOL and CPHA bits */ + tmpreg &= CR1_CLEAR_Mask; + /* Configure SPIx: direction, NSS management, first transmitted bit, BaudRate prescaler + master/salve mode, CPOL and CPHA */ + /* Set BIDImode, BIDIOE and RxONLY bits according to SPI_Direction value */ + /* Set SSM, SSI and MSTR bits according to SPI_Mode and SPI_NSS values */ + /* Set LSBFirst bit according to SPI_FirstBit value */ + /* Set BR bits according to SPI_BaudRatePrescaler value */ + /* Set CPOL bit according to SPI_CPOL value */ + /* Set CPHA bit according to SPI_CPHA value */ + tmpreg |= (uint16_t)((uint32_t)SPI_InitStruct->SPI_Direction | SPI_InitStruct->SPI_Mode | + SPI_InitStruct->SPI_DataSize | SPI_InitStruct->SPI_CPOL | + SPI_InitStruct->SPI_CPHA | SPI_InitStruct->SPI_NSS | + SPI_InitStruct->SPI_BaudRatePrescaler | SPI_InitStruct->SPI_FirstBit); + /* Write to SPIx CR1 */ + SPIx->CR1 = tmpreg; + + /* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */ + SPIx->I2SCFGR &= SPI_Mode_Select; + +/*---------------------------- SPIx CRCPOLY Configuration --------------------*/ + /* Write to SPIx CRCPOLY */ + SPIx->CRCPR = SPI_InitStruct->SPI_CRCPolynomial; +} + +/** + * @brief Initializes the SPIx peripheral according to the specified + * parameters in the I2S_InitStruct. + * @param SPIx: where x can be 2 or 3 to select the SPI peripheral + * (configured in I2S mode). + * @param I2S_InitStruct: pointer to an I2S_InitTypeDef structure that + * contains the configuration information for the specified SPI peripheral + * configured in I2S mode. + * @note + * The function calculates the optimal prescaler needed to obtain the most + * accurate audio frequency (depending on the I2S clock source, the PLL values + * and the product configuration). But in case the prescaler value is greater + * than 511, the default value (0x02) will be configured instead. * + * @retval None + */ +void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct) +{ + uint16_t tmpreg = 0, i2sdiv = 2, i2sodd = 0, packetlength = 1; + uint32_t tmp = 0; + RCC_ClocksTypeDef RCC_Clocks; + uint32_t sourceclock = 0; + + /* Check the I2S parameters */ + assert_param(IS_SPI_23_PERIPH(SPIx)); + assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode)); + assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard)); + assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat)); + assert_param(IS_I2S_MCLK_OUTPUT(I2S_InitStruct->I2S_MCLKOutput)); + assert_param(IS_I2S_AUDIO_FREQ(I2S_InitStruct->I2S_AudioFreq)); + assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL)); + +/*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/ + /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */ + SPIx->I2SCFGR &= I2SCFGR_CLEAR_Mask; + SPIx->I2SPR = 0x0002; + + /* Get the I2SCFGR register value */ + tmpreg = SPIx->I2SCFGR; + + /* If the default value has to be written, reinitialize i2sdiv and i2sodd*/ + if(I2S_InitStruct->I2S_AudioFreq == I2S_AudioFreq_Default) + { + i2sodd = (uint16_t)0; + i2sdiv = (uint16_t)2; + } + /* If the requested audio frequency is not the default, compute the prescaler */ + else + { + /* Check the frame length (For the Prescaler computing) */ + if(I2S_InitStruct->I2S_DataFormat == I2S_DataFormat_16b) + { + /* Packet length is 16 bits */ + packetlength = 1; + } + else + { + /* Packet length is 32 bits */ + packetlength = 2; + } + + /* Get the I2S clock source mask depending on the peripheral number */ + if(((uint32_t)SPIx) == SPI2_BASE) + { + /* The mask is relative to I2S2 */ + tmp = I2S2_CLOCK_SRC; + } + else + { + /* The mask is relative to I2S3 */ + tmp = I2S3_CLOCK_SRC; + } + + /* Check the I2S clock source configuration depending on the Device: + Only Connectivity line devices have the PLL3 VCO clock */ +#ifdef STM32F10X_CL + if((RCC->CFGR2 & tmp) != 0) + { + /* Get the configuration bits of RCC PLL3 multiplier */ + tmp = (uint32_t)((RCC->CFGR2 & I2S_MUL_MASK) >> 12); + + /* Get the value of the PLL3 multiplier */ + if((tmp > 5) && (tmp < 15)) + { + /* Multiplier is between 8 and 14 (value 15 is forbidden) */ + tmp += 2; + } + else + { + if (tmp == 15) + { + /* Multiplier is 20 */ + tmp = 20; + } + } + /* Get the PREDIV2 value */ + sourceclock = (uint32_t)(((RCC->CFGR2 & I2S_DIV_MASK) >> 4) + 1); + + /* Calculate the Source Clock frequency based on PLL3 and PREDIV2 values */ + sourceclock = (uint32_t) ((HSE_Value / sourceclock) * tmp * 2); + } + else + { + /* I2S Clock source is System clock: Get System Clock frequency */ + RCC_GetClocksFreq(&RCC_Clocks); + + /* Get the source clock value: based on System Clock value */ + sourceclock = RCC_Clocks.SYSCLK_Frequency; + } +#else /* STM32F10X_HD */ + /* I2S Clock source is System clock: Get System Clock frequency */ + RCC_GetClocksFreq(&RCC_Clocks); + + /* Get the source clock value: based on System Clock value */ + sourceclock = RCC_Clocks.SYSCLK_Frequency; +#endif /* STM32F10X_CL */ + + /* Compute the Real divider depending on the MCLK output state with a floating point */ + if(I2S_InitStruct->I2S_MCLKOutput == I2S_MCLKOutput_Enable) + { + /* MCLK output is enabled */ + tmp = (uint16_t)(((((sourceclock / 256) * 10) / I2S_InitStruct->I2S_AudioFreq)) + 5); + } + else + { + /* MCLK output is disabled */ + tmp = (uint16_t)(((((sourceclock / (32 * packetlength)) *10 ) / I2S_InitStruct->I2S_AudioFreq)) + 5); + } + + /* Remove the floating point */ + tmp = tmp / 10; + + /* Check the parity of the divider */ + i2sodd = (uint16_t)(tmp & (uint16_t)0x0001); + + /* Compute the i2sdiv prescaler */ + i2sdiv = (uint16_t)((tmp - i2sodd) / 2); + + /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */ + i2sodd = (uint16_t) (i2sodd << 8); + } + + /* Test if the divider is 1 or 0 or greater than 0xFF */ + if ((i2sdiv < 2) || (i2sdiv > 0xFF)) + { + /* Set the default values */ + i2sdiv = 2; + i2sodd = 0; + } + + /* Write to SPIx I2SPR register the computed value */ + SPIx->I2SPR = (uint16_t)(i2sdiv | (uint16_t)(i2sodd | (uint16_t)I2S_InitStruct->I2S_MCLKOutput)); + + /* Configure the I2S with the SPI_InitStruct values */ + tmpreg |= (uint16_t)(I2S_Mode_Select | (uint16_t)(I2S_InitStruct->I2S_Mode | \ + (uint16_t)(I2S_InitStruct->I2S_Standard | (uint16_t)(I2S_InitStruct->I2S_DataFormat | \ + (uint16_t)I2S_InitStruct->I2S_CPOL)))); + + /* Write to SPIx I2SCFGR */ + SPIx->I2SCFGR = tmpreg; +} + +/** + * @brief Fills each SPI_InitStruct member with its default value. + * @param SPI_InitStruct : pointer to a SPI_InitTypeDef structure which will be initialized. + * @retval None + */ +void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct) +{ +/*--------------- Reset SPI init structure parameters values -----------------*/ + /* Initialize the SPI_Direction member */ + SPI_InitStruct->SPI_Direction = SPI_Direction_2Lines_FullDuplex; + /* initialize the SPI_Mode member */ + SPI_InitStruct->SPI_Mode = SPI_Mode_Slave; + /* initialize the SPI_DataSize member */ + SPI_InitStruct->SPI_DataSize = SPI_DataSize_8b; + /* Initialize the SPI_CPOL member */ + SPI_InitStruct->SPI_CPOL = SPI_CPOL_Low; + /* Initialize the SPI_CPHA member */ + SPI_InitStruct->SPI_CPHA = SPI_CPHA_1Edge; + /* Initialize the SPI_NSS member */ + SPI_InitStruct->SPI_NSS = SPI_NSS_Hard; + /* Initialize the SPI_BaudRatePrescaler member */ + SPI_InitStruct->SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2; + /* Initialize the SPI_FirstBit member */ + SPI_InitStruct->SPI_FirstBit = SPI_FirstBit_MSB; + /* Initialize the SPI_CRCPolynomial member */ + SPI_InitStruct->SPI_CRCPolynomial = 7; +} + +/** + * @brief Fills each I2S_InitStruct member with its default value. + * @param I2S_InitStruct : pointer to a I2S_InitTypeDef structure which will be initialized. + * @retval None + */ +void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct) +{ +/*--------------- Reset I2S init structure parameters values -----------------*/ + /* Initialize the I2S_Mode member */ + I2S_InitStruct->I2S_Mode = I2S_Mode_SlaveTx; + + /* Initialize the I2S_Standard member */ + I2S_InitStruct->I2S_Standard = I2S_Standard_Phillips; + + /* Initialize the I2S_DataFormat member */ + I2S_InitStruct->I2S_DataFormat = I2S_DataFormat_16b; + + /* Initialize the I2S_MCLKOutput member */ + I2S_InitStruct->I2S_MCLKOutput = I2S_MCLKOutput_Disable; + + /* Initialize the I2S_AudioFreq member */ + I2S_InitStruct->I2S_AudioFreq = I2S_AudioFreq_Default; + + /* Initialize the I2S_CPOL member */ + I2S_InitStruct->I2S_CPOL = I2S_CPOL_Low; +} + +/** + * @brief Enables or disables the specified SPI peripheral. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI peripheral */ + SPIx->CR1 |= CR1_SPE_Set; + } + else + { + /* Disable the selected SPI peripheral */ + SPIx->CR1 &= CR1_SPE_Reset; + } +} + +/** + * @brief Enables or disables the specified SPI peripheral (in I2S mode). + * @param SPIx: where x can be 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_23_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI peripheral (in I2S mode) */ + SPIx->I2SCFGR |= I2SCFGR_I2SE_Set; + } + else + { + /* Disable the selected SPI peripheral (in I2S mode) */ + SPIx->I2SCFGR &= I2SCFGR_I2SE_Reset; + } +} + +/** + * @brief Enables or disables the specified SPI/I2S interrupts. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @param SPI_I2S_IT: specifies the SPI/I2S interrupt source to be enabled or disabled. + * This parameter can be one of the following values: + * @arg SPI_I2S_IT_TXE: Tx buffer empty interrupt mask + * @arg SPI_I2S_IT_RXNE: Rx buffer not empty interrupt mask + * @arg SPI_I2S_IT_ERR: Error interrupt mask + * @param NewState: new state of the specified SPI/I2S interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState) +{ + uint16_t itpos = 0, itmask = 0 ; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_SPI_I2S_CONFIG_IT(SPI_I2S_IT)); + + /* Get the SPI/I2S IT index */ + itpos = SPI_I2S_IT >> 4; + + /* Set the IT mask */ + itmask = (uint16_t)1 << (uint16_t)itpos; + + if (NewState != DISABLE) + { + /* Enable the selected SPI/I2S interrupt */ + SPIx->CR2 |= itmask; + } + else + { + /* Disable the selected SPI/I2S interrupt */ + SPIx->CR2 &= (uint16_t)~itmask; + } +} + +/** + * @brief Enables or disables the SPIx/I2Sx DMA interface. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @param SPI_I2S_DMAReq: specifies the SPI/I2S DMA transfer request to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg SPI_I2S_DMAReq_Tx: Tx buffer DMA transfer request + * @arg SPI_I2S_DMAReq_Rx: Rx buffer DMA transfer request + * @param NewState: new state of the selected SPI/I2S DMA transfer request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_SPI_I2S_DMAREQ(SPI_I2S_DMAReq)); + if (NewState != DISABLE) + { + /* Enable the selected SPI/I2S DMA requests */ + SPIx->CR2 |= SPI_I2S_DMAReq; + } + else + { + /* Disable the selected SPI/I2S DMA requests */ + SPIx->CR2 &= (uint16_t)~SPI_I2S_DMAReq; + } +} + +/** + * @brief Transmits a Data through the SPIx/I2Sx peripheral. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @param Data : Data to be transmitted. + * @retval None + */ +void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Write in the DR register the data to be sent */ + SPIx->DR = Data; +} + +/** + * @brief Returns the most recent received data by the SPIx/I2Sx peripheral. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @retval The value of the received data. + */ +uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Return the data in the DR register */ + return SPIx->DR; +} + +/** + * @brief Configures internally by software the NSS pin for the selected SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_NSSInternalSoft: specifies the SPI NSS internal state. + * This parameter can be one of the following values: + * @arg SPI_NSSInternalSoft_Set: Set NSS pin internally + * @arg SPI_NSSInternalSoft_Reset: Reset NSS pin internally + * @retval None + */ +void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_NSS_INTERNAL(SPI_NSSInternalSoft)); + if (SPI_NSSInternalSoft != SPI_NSSInternalSoft_Reset) + { + /* Set NSS pin internally by software */ + SPIx->CR1 |= SPI_NSSInternalSoft_Set; + } + else + { + /* Reset NSS pin internally by software */ + SPIx->CR1 &= SPI_NSSInternalSoft_Reset; + } +} + +/** + * @brief Enables or disables the SS output for the selected SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx SS output. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI SS output */ + SPIx->CR2 |= CR2_SSOE_Set; + } + else + { + /* Disable the selected SPI SS output */ + SPIx->CR2 &= CR2_SSOE_Reset; + } +} + +/** + * @brief Configures the data size for the selected SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_DataSize: specifies the SPI data size. + * This parameter can be one of the following values: + * @arg SPI_DataSize_16b: Set data frame format to 16bit + * @arg SPI_DataSize_8b: Set data frame format to 8bit + * @retval None + */ +void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_DATASIZE(SPI_DataSize)); + /* Clear DFF bit */ + SPIx->CR1 &= (uint16_t)~SPI_DataSize_16b; + /* Set new DFF bit value */ + SPIx->CR1 |= SPI_DataSize; +} + +/** + * @brief Transmit the SPIx CRC value. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval None + */ +void SPI_TransmitCRC(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Enable the selected SPI CRC transmission */ + SPIx->CR1 |= CR1_CRCNext_Set; +} + +/** + * @brief Enables or disables the CRC value calculation of the transferred bytes. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx CRC value calculation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI CRC calculation */ + SPIx->CR1 |= CR1_CRCEN_Set; + } + else + { + /* Disable the selected SPI CRC calculation */ + SPIx->CR1 &= CR1_CRCEN_Reset; + } +} + +/** + * @brief Returns the transmit or the receive CRC register value for the specified SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_CRC: specifies the CRC register to be read. + * This parameter can be one of the following values: + * @arg SPI_CRC_Tx: Selects Tx CRC register + * @arg SPI_CRC_Rx: Selects Rx CRC register + * @retval The selected CRC register value.. + */ +uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC) +{ + uint16_t crcreg = 0; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_CRC(SPI_CRC)); + if (SPI_CRC != SPI_CRC_Rx) + { + /* Get the Tx CRC register */ + crcreg = SPIx->TXCRCR; + } + else + { + /* Get the Rx CRC register */ + crcreg = SPIx->RXCRCR; + } + /* Return the selected CRC register */ + return crcreg; +} + +/** + * @brief Returns the CRC Polynomial register value for the specified SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval The CRC Polynomial register value. + */ +uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Return the CRC polynomial register */ + return SPIx->CRCPR; +} + +/** + * @brief Selects the data transfer direction in bi-directional mode for the specified SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_Direction: specifies the data transfer direction in bi-directional mode. + * This parameter can be one of the following values: + * @arg SPI_Direction_Tx: Selects Tx transmission direction + * @arg SPI_Direction_Rx: Selects Rx receive direction + * @retval None + */ +void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_DIRECTION(SPI_Direction)); + if (SPI_Direction == SPI_Direction_Tx) + { + /* Set the Tx only mode */ + SPIx->CR1 |= SPI_Direction_Tx; + } + else + { + /* Set the Rx only mode */ + SPIx->CR1 &= SPI_Direction_Rx; + } +} + +/** + * @brief Checks whether the specified SPI/I2S flag is set or not. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @param SPI_I2S_FLAG: specifies the SPI/I2S flag to check. + * This parameter can be one of the following values: + * @arg SPI_I2S_FLAG_TXE: Transmit buffer empty flag. + * @arg SPI_I2S_FLAG_RXNE: Receive buffer not empty flag. + * @arg SPI_I2S_FLAG_BSY: Busy flag. + * @arg SPI_I2S_FLAG_OVR: Overrun flag. + * @arg SPI_FLAG_MODF: Mode Fault flag. + * @arg SPI_FLAG_CRCERR: CRC Error flag. + * @arg I2S_FLAG_UDR: Underrun Error flag. + * @arg I2S_FLAG_CHSIDE: Channel Side flag. + * @retval The new state of SPI_I2S_FLAG (SET or RESET). + */ +FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_I2S_GET_FLAG(SPI_I2S_FLAG)); + /* Check the status of the specified SPI/I2S flag */ + if ((SPIx->SR & SPI_I2S_FLAG) != (uint16_t)RESET) + { + /* SPI_I2S_FLAG is set */ + bitstatus = SET; + } + else + { + /* SPI_I2S_FLAG is reset */ + bitstatus = RESET; + } + /* Return the SPI_I2S_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the SPIx CRC Error (CRCERR) flag. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * @param SPI_I2S_FLAG: specifies the SPI flag to clear. + * This function clears only CRCERR flag. + * @note + * - OVR (OverRun error) flag is cleared by software sequence: a read + * operation to SPI_DR register (SPI_I2S_ReceiveData()) followed by a read + * operation to SPI_SR register (SPI_I2S_GetFlagStatus()). + * - UDR (UnderRun error) flag is cleared by a read operation to + * SPI_SR register (SPI_I2S_GetFlagStatus()). + * - MODF (Mode Fault) flag is cleared by software sequence: a read/write + * operation to SPI_SR register (SPI_I2S_GetFlagStatus()) followed by a + * write operation to SPI_CR1 register (SPI_Cmd() to enable the SPI). + * @retval None + */ +void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_I2S_CLEAR_FLAG(SPI_I2S_FLAG)); + + /* Clear the selected SPI CRC Error (CRCERR) flag */ + SPIx->SR = (uint16_t)~SPI_I2S_FLAG; +} + +/** + * @brief Checks whether the specified SPI/I2S interrupt has occurred or not. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @param SPI_I2S_IT: specifies the SPI/I2S interrupt source to check. + * This parameter can be one of the following values: + * @arg SPI_I2S_IT_TXE: Transmit buffer empty interrupt. + * @arg SPI_I2S_IT_RXNE: Receive buffer not empty interrupt. + * @arg SPI_I2S_IT_OVR: Overrun interrupt. + * @arg SPI_IT_MODF: Mode Fault interrupt. + * @arg SPI_IT_CRCERR: CRC Error interrupt. + * @arg I2S_IT_UDR: Underrun Error interrupt. + * @retval The new state of SPI_I2S_IT (SET or RESET). + */ +ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT) +{ + ITStatus bitstatus = RESET; + uint16_t itpos = 0, itmask = 0, enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_I2S_GET_IT(SPI_I2S_IT)); + + /* Get the SPI/I2S IT index */ + itpos = 0x01 << (SPI_I2S_IT & 0x0F); + + /* Get the SPI/I2S IT mask */ + itmask = SPI_I2S_IT >> 4; + + /* Set the IT mask */ + itmask = 0x01 << itmask; + + /* Get the SPI_I2S_IT enable bit status */ + enablestatus = (SPIx->CR2 & itmask) ; + + /* Check the status of the specified SPI/I2S interrupt */ + if (((SPIx->SR & itpos) != (uint16_t)RESET) && enablestatus) + { + /* SPI_I2S_IT is set */ + bitstatus = SET; + } + else + { + /* SPI_I2S_IT is reset */ + bitstatus = RESET; + } + /* Return the SPI_I2S_IT status */ + return bitstatus; +} + +/** + * @brief Clears the SPIx CRC Error (CRCERR) interrupt pending bit. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * @param SPI_I2S_IT: specifies the SPI interrupt pending bit to clear. + * This function clears only CRCERR interrupt pending bit. + * @note + * - OVR (OverRun Error) interrupt pending bit is cleared by software + * sequence: a read operation to SPI_DR register (SPI_I2S_ReceiveData()) + * followed by a read operation to SPI_SR register (SPI_I2S_GetITStatus()). + * - UDR (UnderRun Error) interrupt pending bit is cleared by a read + * operation to SPI_SR register (SPI_I2S_GetITStatus()). + * - MODF (Mode Fault) interrupt pending bit is cleared by software sequence: + * a read/write operation to SPI_SR register (SPI_I2S_GetITStatus()) + * followed by a write operation to SPI_CR1 register (SPI_Cmd() to enable + * the SPI). + * @retval None + */ +void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT) +{ + uint16_t itpos = 0; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_I2S_CLEAR_IT(SPI_I2S_IT)); + + /* Get the SPI IT index */ + itpos = 0x01 << (SPI_I2S_IT & 0x0F); + + /* Clear the selected SPI CRC Error (CRCERR) interrupt pending bit */ + SPIx->SR = (uint16_t)~itpos; +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c new file mode 100644 index 0000000..bfb4dd1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c @@ -0,0 +1,2890 @@ +/** + ****************************************************************************** + * @file stm32f10x_tim.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the TIM firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_tim.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup TIM + * @brief TIM driver modules + * @{ + */ + +/** @defgroup TIM_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_Defines + * @{ + */ + +/* ---------------------- TIM registers bit mask ------------------------ */ +#define SMCR_ETR_Mask ((uint16_t)0x00FF) +#define CCMR_Offset ((uint16_t)0x0018) +#define CCER_CCE_Set ((uint16_t)0x0001) +#define CCER_CCNE_Set ((uint16_t)0x0004) + +/** + * @} + */ + +/** @defgroup TIM_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_FunctionPrototypes + * @{ + */ + +static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +/** + * @} + */ + +/** @defgroup TIM_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the TIMx peripheral registers to their default reset values. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @retval None + */ +void TIM_DeInit(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + if (TIMx == TIM1) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, DISABLE); + } + else if (TIMx == TIM2) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, DISABLE); + } + else if (TIMx == TIM3) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, DISABLE); + } + else if (TIMx == TIM4) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, DISABLE); + } + else if (TIMx == TIM5) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, DISABLE); + } + else if (TIMx == TIM6) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, DISABLE); + } + else if (TIMx == TIM7) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, DISABLE); + } + else if (TIMx == TIM8) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, DISABLE); + } + else if (TIMx == TIM9) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM9, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM9, DISABLE); + } + else if (TIMx == TIM10) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM10, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM10, DISABLE); + } + else if (TIMx == TIM11) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM11, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM11, DISABLE); + } + else if (TIMx == TIM12) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM12, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM12, DISABLE); + } + else if (TIMx == TIM13) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM13, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM13, DISABLE); + } + else if (TIMx == TIM14) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM14, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM14, DISABLE); + } + else if (TIMx == TIM15) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM15, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM15, DISABLE); + } + else if (TIMx == TIM16) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM16, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM16, DISABLE); + } + else + { + if (TIMx == TIM17) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM17, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM17, DISABLE); + } + } +} + +/** + * @brief Initializes the TIMx Time Base Unit peripheral according to + * the specified parameters in the TIM_TimeBaseInitStruct. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_TimeBaseInitStruct: pointer to a TIM_TimeBaseInitTypeDef + * structure that contains the configuration information for the + * specified TIM peripheral. + * @retval None + */ +void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) +{ + uint16_t tmpcr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_COUNTER_MODE(TIM_TimeBaseInitStruct->TIM_CounterMode)); + assert_param(IS_TIM_CKD_DIV(TIM_TimeBaseInitStruct->TIM_ClockDivision)); + + tmpcr1 = TIMx->CR1; + + if((TIMx == TIM1) || (TIMx == TIM8)|| (TIMx == TIM2) || (TIMx == TIM3)|| + (TIMx == TIM4) || (TIMx == TIM5)) + { + /* Select the Counter Mode */ + tmpcr1 &= (uint16_t)(~((uint16_t)(TIM_CR1_DIR | TIM_CR1_CMS))); + tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_CounterMode; + } + + if((TIMx != TIM6) && (TIMx != TIM7)) + { + /* Set the clock division */ + tmpcr1 &= (uint16_t)(~((uint16_t)TIM_CR1_CKD)); + tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_ClockDivision; + } + + TIMx->CR1 = tmpcr1; + + /* Set the Autoreload value */ + TIMx->ARR = TIM_TimeBaseInitStruct->TIM_Period ; + + /* Set the Prescaler value */ + TIMx->PSC = TIM_TimeBaseInitStruct->TIM_Prescaler; + + if ((TIMx == TIM1) || (TIMx == TIM8)|| (TIMx == TIM15)|| (TIMx == TIM16) || (TIMx == TIM17)) + { + /* Set the Repetition Counter value */ + TIMx->RCR = TIM_TimeBaseInitStruct->TIM_RepetitionCounter; + } + + /* Generate an update event to reload the Prescaler and the Repetition counter + values immediately */ + TIMx->EGR = TIM_PSCReloadMode_Immediate; +} + +/** + * @brief Initializes the TIMx Channel1 according to the specified + * parameters in the TIM_OCInitStruct. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + /* Disable the Channel 1: Reset the CC1E Bit */ + TIMx->CCER &= (uint16_t)(~(uint16_t)TIM_CCER_CC1E); + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR1; + + /* Reset the Output Compare Mode Bits */ + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_OC1M)); + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_CC1S)); + + /* Select the Output Compare Mode */ + tmpccmrx |= TIM_OCInitStruct->TIM_OCMode; + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC1P)); + /* Set the Output Compare Polarity */ + tmpccer |= TIM_OCInitStruct->TIM_OCPolarity; + + /* Set the Output State */ + tmpccer |= TIM_OCInitStruct->TIM_OutputState; + + if((TIMx == TIM1) || (TIMx == TIM8)|| (TIMx == TIM15)|| + (TIMx == TIM16)|| (TIMx == TIM17)) + { + assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); + assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + + /* Reset the Output N Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC1NP)); + /* Set the Output N Polarity */ + tmpccer |= TIM_OCInitStruct->TIM_OCNPolarity; + + /* Reset the Output N State */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC1NE)); + /* Set the Output N State */ + tmpccer |= TIM_OCInitStruct->TIM_OutputNState; + + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS1)); + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS1N)); + + /* Set the Output Idle state */ + tmpcr2 |= TIM_OCInitStruct->TIM_OCIdleState; + /* Set the Output N Idle state */ + tmpcr2 |= TIM_OCInitStruct->TIM_OCNIdleState; + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR1 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel2 according to the specified + * parameters in the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select + * the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= (uint16_t)(~((uint16_t)TIM_CCER_CC2E)); + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR1; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_OC2M)); + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_CC2S)); + + /* Select the Output Compare Mode */ + tmpccmrx |= (uint16_t)(TIM_OCInitStruct->TIM_OCMode << 8); + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC2P)); + /* Set the Output Compare Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 4); + + /* Set the Output State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 4); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); + assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + + /* Reset the Output N Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC2NP)); + /* Set the Output N Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCNPolarity << 4); + + /* Reset the Output N State */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC2NE)); + /* Set the Output N State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputNState << 4); + + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS2)); + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS2N)); + + /* Set the Output Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 2); + /* Set the Output N Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCNIdleState << 2); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR2 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel3 according to the specified + * parameters in the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= (uint16_t)(~((uint16_t)TIM_CCER_CC3E)); + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR2 register value */ + tmpccmrx = TIMx->CCMR2; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_OC3M)); + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_CC3S)); + /* Select the Output Compare Mode */ + tmpccmrx |= TIM_OCInitStruct->TIM_OCMode; + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC3P)); + /* Set the Output Compare Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 8); + + /* Set the Output State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 8); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); + assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + + /* Reset the Output N Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC3NP)); + /* Set the Output N Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCNPolarity << 8); + /* Reset the Output N State */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC3NE)); + + /* Set the Output N State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputNState << 8); + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS3)); + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS3N)); + /* Set the Output Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 4); + /* Set the Output N Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCNIdleState << 4); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR3 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel4 according to the specified + * parameters in the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + /* Disable the Channel 2: Reset the CC4E Bit */ + TIMx->CCER &= (uint16_t)(~((uint16_t)TIM_CCER_CC4E)); + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR2 register value */ + tmpccmrx = TIMx->CCMR2; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_OC4M)); + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_CC4S)); + + /* Select the Output Compare Mode */ + tmpccmrx |= (uint16_t)(TIM_OCInitStruct->TIM_OCMode << 8); + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC4P)); + /* Set the Output Compare Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 12); + + /* Set the Output State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 12); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + /* Reset the Output Compare IDLE State */ + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS4)); + /* Set the Output Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 6); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR4 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIM peripheral according to the specified + * parameters in the TIM_ICInitStruct. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct) +{ + /* Check the parameters */ + assert_param(IS_TIM_CHANNEL(TIM_ICInitStruct->TIM_Channel)); + assert_param(IS_TIM_IC_SELECTION(TIM_ICInitStruct->TIM_ICSelection)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICInitStruct->TIM_ICPrescaler)); + assert_param(IS_TIM_IC_FILTER(TIM_ICInitStruct->TIM_ICFilter)); + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || + (TIMx == TIM4) ||(TIMx == TIM5)) + { + assert_param(IS_TIM_IC_POLARITY(TIM_ICInitStruct->TIM_ICPolarity)); + } + else + { + assert_param(IS_TIM_IC_POLARITY_LITE(TIM_ICInitStruct->TIM_ICPolarity)); + } + if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1) + { + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + /* TI1 Configuration */ + TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_2) + { + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + /* TI2 Configuration */ + TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_3) + { + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* TI3 Configuration */ + TI3_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC3Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else + { + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* TI4 Configuration */ + TI4_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC4Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } +} + +/** + * @brief Configures the TIM peripheral according to the specified + * parameters in the TIM_ICInitStruct to measure an external PWM signal. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct) +{ + uint16_t icoppositepolarity = TIM_ICPolarity_Rising; + uint16_t icoppositeselection = TIM_ICSelection_DirectTI; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + /* Select the Opposite Input Polarity */ + if (TIM_ICInitStruct->TIM_ICPolarity == TIM_ICPolarity_Rising) + { + icoppositepolarity = TIM_ICPolarity_Falling; + } + else + { + icoppositepolarity = TIM_ICPolarity_Rising; + } + /* Select the Opposite Input */ + if (TIM_ICInitStruct->TIM_ICSelection == TIM_ICSelection_DirectTI) + { + icoppositeselection = TIM_ICSelection_IndirectTI; + } + else + { + icoppositeselection = TIM_ICSelection_DirectTI; + } + if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1) + { + /* TI1 Configuration */ + TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + /* TI2 Configuration */ + TI2_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else + { + /* TI2 Configuration */ + TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + /* TI1 Configuration */ + TI1_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } +} + +/** + * @brief Configures the: Break feature, dead time, Lock level, the OSSI, + * the OSSR State and the AOE(automatic output enable). + * @param TIMx: where x can be 1 or 8 to select the TIM + * @param TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure that + * contains the BDTR Register configuration information for the TIM peripheral. + * @retval None + */ +void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OSSR_STATE(TIM_BDTRInitStruct->TIM_OSSRState)); + assert_param(IS_TIM_OSSI_STATE(TIM_BDTRInitStruct->TIM_OSSIState)); + assert_param(IS_TIM_LOCK_LEVEL(TIM_BDTRInitStruct->TIM_LOCKLevel)); + assert_param(IS_TIM_BREAK_STATE(TIM_BDTRInitStruct->TIM_Break)); + assert_param(IS_TIM_BREAK_POLARITY(TIM_BDTRInitStruct->TIM_BreakPolarity)); + assert_param(IS_TIM_AUTOMATIC_OUTPUT_STATE(TIM_BDTRInitStruct->TIM_AutomaticOutput)); + /* Set the Lock level, the Break enable Bit and the Ploarity, the OSSR State, + the OSSI State, the dead time value and the Automatic Output Enable Bit */ + TIMx->BDTR = (uint32_t)TIM_BDTRInitStruct->TIM_OSSRState | TIM_BDTRInitStruct->TIM_OSSIState | + TIM_BDTRInitStruct->TIM_LOCKLevel | TIM_BDTRInitStruct->TIM_DeadTime | + TIM_BDTRInitStruct->TIM_Break | TIM_BDTRInitStruct->TIM_BreakPolarity | + TIM_BDTRInitStruct->TIM_AutomaticOutput; +} + +/** + * @brief Fills each TIM_TimeBaseInitStruct member with its default value. + * @param TIM_TimeBaseInitStruct : pointer to a TIM_TimeBaseInitTypeDef + * structure which will be initialized. + * @retval None + */ +void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) +{ + /* Set the default configuration */ + TIM_TimeBaseInitStruct->TIM_Period = 0xFFFF; + TIM_TimeBaseInitStruct->TIM_Prescaler = 0x0000; + TIM_TimeBaseInitStruct->TIM_ClockDivision = TIM_CKD_DIV1; + TIM_TimeBaseInitStruct->TIM_CounterMode = TIM_CounterMode_Up; + TIM_TimeBaseInitStruct->TIM_RepetitionCounter = 0x0000; +} + +/** + * @brief Fills each TIM_OCInitStruct member with its default value. + * @param TIM_OCInitStruct : pointer to a TIM_OCInitTypeDef structure which will + * be initialized. + * @retval None + */ +void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + /* Set the default configuration */ + TIM_OCInitStruct->TIM_OCMode = TIM_OCMode_Timing; + TIM_OCInitStruct->TIM_OutputState = TIM_OutputState_Disable; + TIM_OCInitStruct->TIM_OutputNState = TIM_OutputNState_Disable; + TIM_OCInitStruct->TIM_Pulse = 0x0000; + TIM_OCInitStruct->TIM_OCPolarity = TIM_OCPolarity_High; + TIM_OCInitStruct->TIM_OCNPolarity = TIM_OCPolarity_High; + TIM_OCInitStruct->TIM_OCIdleState = TIM_OCIdleState_Reset; + TIM_OCInitStruct->TIM_OCNIdleState = TIM_OCNIdleState_Reset; +} + +/** + * @brief Fills each TIM_ICInitStruct member with its default value. + * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure which will + * be initialized. + * @retval None + */ +void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct) +{ + /* Set the default configuration */ + TIM_ICInitStruct->TIM_Channel = TIM_Channel_1; + TIM_ICInitStruct->TIM_ICPolarity = TIM_ICPolarity_Rising; + TIM_ICInitStruct->TIM_ICSelection = TIM_ICSelection_DirectTI; + TIM_ICInitStruct->TIM_ICPrescaler = TIM_ICPSC_DIV1; + TIM_ICInitStruct->TIM_ICFilter = 0x00; +} + +/** + * @brief Fills each TIM_BDTRInitStruct member with its default value. + * @param TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure which + * will be initialized. + * @retval None + */ +void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct) +{ + /* Set the default configuration */ + TIM_BDTRInitStruct->TIM_OSSRState = TIM_OSSRState_Disable; + TIM_BDTRInitStruct->TIM_OSSIState = TIM_OSSIState_Disable; + TIM_BDTRInitStruct->TIM_LOCKLevel = TIM_LOCKLevel_OFF; + TIM_BDTRInitStruct->TIM_DeadTime = 0x00; + TIM_BDTRInitStruct->TIM_Break = TIM_Break_Disable; + TIM_BDTRInitStruct->TIM_BreakPolarity = TIM_BreakPolarity_Low; + TIM_BDTRInitStruct->TIM_AutomaticOutput = TIM_AutomaticOutput_Disable; +} + +/** + * @brief Enables or disables the specified TIM peripheral. + * @param TIMx: where x can be 1 to 17 to select the TIMx peripheral. + * @param NewState: new state of the TIMx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the TIM Counter */ + TIMx->CR1 |= TIM_CR1_CEN; + } + else + { + /* Disable the TIM Counter */ + TIMx->CR1 &= (uint16_t)(~((uint16_t)TIM_CR1_CEN)); + } +} + +/** + * @brief Enables or disables the TIM peripheral Main Outputs. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIMx peripheral. + * @param NewState: new state of the TIM peripheral Main Outputs. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the TIM Main Output */ + TIMx->BDTR |= TIM_BDTR_MOE; + } + else + { + /* Disable the TIM Main Output */ + TIMx->BDTR &= (uint16_t)(~((uint16_t)TIM_BDTR_MOE)); + } +} + +/** + * @brief Enables or disables the specified TIM interrupts. + * @param TIMx: where x can be 1 to 17 to select the TIMx peripheral. + * @param TIM_IT: specifies the TIM interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg TIM_IT_Update: TIM update Interrupt source + * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source + * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source + * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source + * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source + * @arg TIM_IT_COM: TIM Commutation Interrupt source + * @arg TIM_IT_Trigger: TIM Trigger Interrupt source + * @arg TIM_IT_Break: TIM Break Interrupt source + * @note + * - TIM6 and TIM7 can only generate an update interrupt. + * - TIM9, TIM12 and TIM15 can have only TIM_IT_Update, TIM_IT_CC1, + * TIM_IT_CC2 or TIM_IT_Trigger. + * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_IT_Update or TIM_IT_CC1. + * - TIM_IT_Break is used only with TIM1, TIM8 and TIM15. + * - TIM_IT_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. + * @param NewState: new state of the TIM interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_IT(TIM_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Interrupt sources */ + TIMx->DIER |= TIM_IT; + } + else + { + /* Disable the Interrupt sources */ + TIMx->DIER &= (uint16_t)~TIM_IT; + } +} + +/** + * @brief Configures the TIMx event to be generate by software. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_EventSource: specifies the event source. + * This parameter can be one or more of the following values: + * @arg TIM_EventSource_Update: Timer update Event source + * @arg TIM_EventSource_CC1: Timer Capture Compare 1 Event source + * @arg TIM_EventSource_CC2: Timer Capture Compare 2 Event source + * @arg TIM_EventSource_CC3: Timer Capture Compare 3 Event source + * @arg TIM_EventSource_CC4: Timer Capture Compare 4 Event source + * @arg TIM_EventSource_COM: Timer COM event source + * @arg TIM_EventSource_Trigger: Timer Trigger Event source + * @arg TIM_EventSource_Break: Timer Break event source + * @note + * - TIM6 and TIM7 can only generate an update event. + * - TIM_EventSource_COM and TIM_EventSource_Break are used only with TIM1 and TIM8. + * @retval None + */ +void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_EVENT_SOURCE(TIM_EventSource)); + + /* Set the event sources */ + TIMx->EGR = TIM_EventSource; +} + +/** + * @brief Configures the TIMx's DMA interface. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 15, 16 or 17 to select + * the TIM peripheral. + * @param TIM_DMABase: DMA Base address. + * This parameter can be one of the following values: + * @arg TIM_DMABase_CR, TIM_DMABase_CR2, TIM_DMABase_SMCR, + * TIM_DMABase_DIER, TIM1_DMABase_SR, TIM_DMABase_EGR, + * TIM_DMABase_CCMR1, TIM_DMABase_CCMR2, TIM_DMABase_CCER, + * TIM_DMABase_CNT, TIM_DMABase_PSC, TIM_DMABase_ARR, + * TIM_DMABase_RCR, TIM_DMABase_CCR1, TIM_DMABase_CCR2, + * TIM_DMABase_CCR3, TIM_DMABase_CCR4, TIM_DMABase_BDTR, + * TIM_DMABase_DCR. + * @param TIM_DMABurstLength: DMA Burst length. + * This parameter can be one value between: + * TIM_DMABurstLength_1Transfer and TIM_DMABurstLength_18Transfers. + * @retval None + */ +void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_DMA_BASE(TIM_DMABase)); + assert_param(IS_TIM_DMA_LENGTH(TIM_DMABurstLength)); + /* Set the DMA Base and the DMA Burst Length */ + TIMx->DCR = TIM_DMABase | TIM_DMABurstLength; +} + +/** + * @brief Enables or disables the TIMx's DMA Requests. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 6, 7, 8, 15, 16 or 17 + * to select the TIM peripheral. + * @param TIM_DMASource: specifies the DMA Request sources. + * This parameter can be any combination of the following values: + * @arg TIM_DMA_Update: TIM update Interrupt source + * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source + * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source + * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source + * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source + * @arg TIM_DMA_COM: TIM Commutation DMA source + * @arg TIM_DMA_Trigger: TIM Trigger DMA source + * @param NewState: new state of the DMA Request sources. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST9_PERIPH(TIMx)); + assert_param(IS_TIM_DMA_SOURCE(TIM_DMASource)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the DMA sources */ + TIMx->DIER |= TIM_DMASource; + } + else + { + /* Disable the DMA sources */ + TIMx->DIER &= (uint16_t)~TIM_DMASource; + } +} + +/** + * @brief Configures the TIMx internal Clock + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 + * to select the TIM peripheral. + * @retval None + */ +void TIM_InternalClockConfig(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + /* Disable slave mode to clock the prescaler directly with the internal clock */ + TIMx->SMCR &= (uint16_t)(~((uint16_t)TIM_SMCR_SMS)); +} + +/** + * @brief Configures the TIMx Internal Trigger as External Clock + * @param TIMx: where x can be 1, 2, 3, 4, 5, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_ITRSource: Trigger source. + * This parameter can be one of the following values: + * @param TIM_TS_ITR0: Internal Trigger 0 + * @param TIM_TS_ITR1: Internal Trigger 1 + * @param TIM_TS_ITR2: Internal Trigger 2 + * @param TIM_TS_ITR3: Internal Trigger 3 + * @retval None + */ +void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_INTERNAL_TRIGGER_SELECTION(TIM_InputTriggerSource)); + /* Select the Internal Trigger */ + TIM_SelectInputTrigger(TIMx, TIM_InputTriggerSource); + /* Select the External clock mode1 */ + TIMx->SMCR |= TIM_SlaveMode_External1; +} + +/** + * @brief Configures the TIMx Trigger as External Clock + * @param TIMx: where x can be 1, 2, 3, 4, 5, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_TIxExternalCLKSource: Trigger source. + * This parameter can be one of the following values: + * @arg TIM_TIxExternalCLK1Source_TI1ED: TI1 Edge Detector + * @arg TIM_TIxExternalCLK1Source_TI1: Filtered Timer Input 1 + * @arg TIM_TIxExternalCLK1Source_TI2: Filtered Timer Input 2 + * @param TIM_ICPolarity: specifies the TIx Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param ICFilter : specifies the filter value. + * This parameter must be a value between 0x0 and 0xF. + * @retval None + */ +void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource, + uint16_t TIM_ICPolarity, uint16_t ICFilter) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_TIXCLK_SOURCE(TIM_TIxExternalCLKSource)); + assert_param(IS_TIM_IC_POLARITY(TIM_ICPolarity)); + assert_param(IS_TIM_IC_FILTER(ICFilter)); + /* Configure the Timer Input Clock Source */ + if (TIM_TIxExternalCLKSource == TIM_TIxExternalCLK1Source_TI2) + { + TI2_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter); + } + else + { + TI1_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter); + } + /* Select the Trigger source */ + TIM_SelectInputTrigger(TIMx, TIM_TIxExternalCLKSource); + /* Select the External clock mode1 */ + TIMx->SMCR |= TIM_SlaveMode_External1; +} + +/** + * @brief Configures the External clock Mode1 + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. + * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. + * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. + * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity: The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. + * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. + * @param ExtTRGFilter: External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter) +{ + uint16_t tmpsmcr = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); + assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); + assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); + /* Configure the ETR Clock source */ + TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter); + + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + /* Reset the SMS Bits */ + tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_SMS)); + /* Select the External clock mode1 */ + tmpsmcr |= TIM_SlaveMode_External1; + /* Select the Trigger selection : ETRF */ + tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_TS)); + tmpsmcr |= TIM_TS_ETRF; + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} + +/** + * @brief Configures the External clock Mode2 + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. + * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. + * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. + * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity: The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. + * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. + * @param ExtTRGFilter: External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, + uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); + assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); + assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); + /* Configure the ETR Clock source */ + TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter); + /* Enable the External clock mode2 */ + TIMx->SMCR |= TIM_SMCR_ECE; +} + +/** + * @brief Configures the TIMx External Trigger (ETR). + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. + * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. + * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. + * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity: The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. + * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. + * @param ExtTRGFilter: External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter) +{ + uint16_t tmpsmcr = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); + assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); + assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); + tmpsmcr = TIMx->SMCR; + /* Reset the ETR Bits */ + tmpsmcr &= SMCR_ETR_Mask; + /* Set the Prescaler, the Filter value and the Polarity */ + tmpsmcr |= (uint16_t)(TIM_ExtTRGPrescaler | (uint16_t)(TIM_ExtTRGPolarity | (uint16_t)(ExtTRGFilter << (uint16_t)8))); + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} + +/** + * @brief Configures the TIMx Prescaler. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param Prescaler: specifies the Prescaler Register value + * @param TIM_PSCReloadMode: specifies the TIM Prescaler Reload mode + * This parameter can be one of the following values: + * @arg TIM_PSCReloadMode_Update: The Prescaler is loaded at the update event. + * @arg TIM_PSCReloadMode_Immediate: The Prescaler is loaded immediately. + * @retval None + */ +void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_PRESCALER_RELOAD(TIM_PSCReloadMode)); + /* Set the Prescaler value */ + TIMx->PSC = Prescaler; + /* Set or reset the UG Bit */ + TIMx->EGR = TIM_PSCReloadMode; +} + +/** + * @brief Specifies the TIMx Counter Mode to be used. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_CounterMode: specifies the Counter Mode to be used + * This parameter can be one of the following values: + * @arg TIM_CounterMode_Up: TIM Up Counting Mode + * @arg TIM_CounterMode_Down: TIM Down Counting Mode + * @arg TIM_CounterMode_CenterAligned1: TIM Center Aligned Mode1 + * @arg TIM_CounterMode_CenterAligned2: TIM Center Aligned Mode2 + * @arg TIM_CounterMode_CenterAligned3: TIM Center Aligned Mode3 + * @retval None + */ +void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode) +{ + uint16_t tmpcr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_COUNTER_MODE(TIM_CounterMode)); + tmpcr1 = TIMx->CR1; + /* Reset the CMS and DIR Bits */ + tmpcr1 &= (uint16_t)(~((uint16_t)(TIM_CR1_DIR | TIM_CR1_CMS))); + /* Set the Counter Mode */ + tmpcr1 |= TIM_CounterMode; + /* Write to TIMx CR1 register */ + TIMx->CR1 = tmpcr1; +} + +/** + * @brief Selects the Input Trigger source + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_InputTriggerSource: The Input Trigger source. + * This parameter can be one of the following values: + * @arg TIM_TS_ITR0: Internal Trigger 0 + * @arg TIM_TS_ITR1: Internal Trigger 1 + * @arg TIM_TS_ITR2: Internal Trigger 2 + * @arg TIM_TS_ITR3: Internal Trigger 3 + * @arg TIM_TS_TI1F_ED: TI1 Edge Detector + * @arg TIM_TS_TI1FP1: Filtered Timer Input 1 + * @arg TIM_TS_TI2FP2: Filtered Timer Input 2 + * @arg TIM_TS_ETRF: External Trigger input + * @retval None + */ +void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource) +{ + uint16_t tmpsmcr = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_TRIGGER_SELECTION(TIM_InputTriggerSource)); + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + /* Reset the TS Bits */ + tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_TS)); + /* Set the Input Trigger source */ + tmpsmcr |= TIM_InputTriggerSource; + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} + +/** + * @brief Configures the TIMx Encoder Interface. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_EncoderMode: specifies the TIMx Encoder Mode. + * This parameter can be one of the following values: + * @arg TIM_EncoderMode_TI1: Counter counts on TI1FP1 edge depending on TI2FP2 level. + * @arg TIM_EncoderMode_TI2: Counter counts on TI2FP2 edge depending on TI1FP1 level. + * @arg TIM_EncoderMode_TI12: Counter counts on both TI1FP1 and TI2FP2 edges depending + * on the level of the other input. + * @param TIM_IC1Polarity: specifies the IC1 Polarity + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Falling: IC Falling edge. + * @arg TIM_ICPolarity_Rising: IC Rising edge. + * @param TIM_IC2Polarity: specifies the IC2 Polarity + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Falling: IC Falling edge. + * @arg TIM_ICPolarity_Rising: IC Rising edge. + * @retval None + */ +void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode, + uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity) +{ + uint16_t tmpsmcr = 0; + uint16_t tmpccmr1 = 0; + uint16_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST5_PERIPH(TIMx)); + assert_param(IS_TIM_ENCODER_MODE(TIM_EncoderMode)); + assert_param(IS_TIM_IC_POLARITY(TIM_IC1Polarity)); + assert_param(IS_TIM_IC_POLARITY(TIM_IC2Polarity)); + + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = TIMx->CCMR1; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + + /* Set the encoder Mode */ + tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_SMS)); + tmpsmcr |= TIM_EncoderMode; + + /* Select the Capture Compare 1 and the Capture Compare 2 as input */ + tmpccmr1 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR1_CC1S)) & (uint16_t)(~((uint16_t)TIM_CCMR1_CC2S))); + tmpccmr1 |= TIM_CCMR1_CC1S_0 | TIM_CCMR1_CC2S_0; + + /* Set the TI1 and the TI2 Polarities */ + tmpccer &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCER_CC1P)) & ((uint16_t)~((uint16_t)TIM_CCER_CC2P))); + tmpccer |= (uint16_t)(TIM_IC1Polarity | (uint16_t)(TIM_IC2Polarity << (uint16_t)4)); + + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmr1; + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Forces the TIMx output 1 waveform to active or inactive level. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC1REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC1REF. + * @retval None + */ +void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC1M Bits */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1M); + /* Configure The Forced output Mode */ + tmpccmr1 |= TIM_ForcedAction; + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Forces the TIMx output 2 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC2REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC2REF. + * @retval None + */ +void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC2M Bits */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2M); + /* Configure The Forced output Mode */ + tmpccmr1 |= (uint16_t)(TIM_ForcedAction << 8); + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Forces the TIMx output 3 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC3REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC3REF. + * @retval None + */ +void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC1M Bits */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3M); + /* Configure The Forced output Mode */ + tmpccmr2 |= TIM_ForcedAction; + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Forces the TIMx output 4 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC4REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC4REF. + * @retval None + */ +void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC2M Bits */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4M); + /* Configure The Forced output Mode */ + tmpccmr2 |= (uint16_t)(TIM_ForcedAction << 8); + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Enables or disables TIMx peripheral Preload register on ARR. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param NewState: new state of the TIMx peripheral Preload register + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the ARR Preload Bit */ + TIMx->CR1 |= TIM_CR1_ARPE; + } + else + { + /* Reset the ARR Preload Bit */ + TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_ARPE); + } +} + +/** + * @brief Selects the TIM peripheral Commutation event. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIMx peripheral + * @param NewState: new state of the Commutation event. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the COM Bit */ + TIMx->CR2 |= TIM_CR2_CCUS; + } + else + { + /* Reset the COM Bit */ + TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_CCUS); + } +} + +/** + * @brief Selects the TIMx peripheral Capture Compare DMA source. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 15, 16 or 17 to select + * the TIM peripheral. + * @param NewState: new state of the Capture Compare DMA source + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the CCDS Bit */ + TIMx->CR2 |= TIM_CR2_CCDS; + } + else + { + /* Reset the CCDS Bit */ + TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_CCDS); + } +} + +/** + * @brief Sets or Resets the TIM peripheral Capture Compare Preload Control bit. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8 or 15 + * to select the TIMx peripheral + * @param NewState: new state of the Capture Compare Preload Control bit + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST5_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the CCPC Bit */ + TIMx->CR2 |= TIM_CR2_CCPC; + } + else + { + /* Reset the CCPC Bit */ + TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_CCPC); + } +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR1. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC1PE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1PE); + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr1 |= TIM_OCPreload; + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR2. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select + * the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC2PE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2PE); + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr1 |= (uint16_t)(TIM_OCPreload << 8); + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR3. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC3PE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3PE); + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr2 |= TIM_OCPreload; + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR4. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC4PE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4PE); + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr2 |= (uint16_t)(TIM_OCPreload << 8); + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Configures the TIMx Output Compare 1 Fast feature. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC1FE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1FE); + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr1 |= TIM_OCFast; + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Configures the TIMx Output Compare 2 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select + * the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC2FE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2FE); + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr1 |= (uint16_t)(TIM_OCFast << 8); + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Configures the TIMx Output Compare 3 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + /* Get the TIMx CCMR2 register value */ + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC3FE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3FE); + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr2 |= TIM_OCFast; + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Configures the TIMx Output Compare 4 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + /* Get the TIMx CCMR2 register value */ + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC4FE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4FE); + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr2 |= (uint16_t)(TIM_OCFast << 8); + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Clears or safeguards the OCREF1 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC1CE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1CE); + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr1 |= TIM_OCClear; + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Clears or safeguards the OCREF2 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC2CE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2CE); + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr1 |= (uint16_t)(TIM_OCClear << 8); + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Clears or safeguards the OCREF3 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC3CE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3CE); + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr2 |= TIM_OCClear; + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Clears or safeguards the OCREF4 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC4CE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4CE); + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr2 |= (uint16_t)(TIM_OCClear << 8); + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Configures the TIMx channel 1 polarity. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC1 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + tmpccer = TIMx->CCER; + /* Set or Reset the CC1P Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC1P); + tmpccer |= TIM_OCPolarity; + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx Channel 1N polarity. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_OCNPolarity: specifies the OC1N Polarity + * This parameter can be one of the following values: + * @arg TIM_OCNPolarity_High: Output Compare active high + * @arg TIM_OCNPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); + + tmpccer = TIMx->CCER; + /* Set or Reset the CC1NP Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC1NP); + tmpccer |= TIM_OCNPolarity; + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 2 polarity. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC2 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + tmpccer = TIMx->CCER; + /* Set or Reset the CC2P Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC2P); + tmpccer |= (uint16_t)(TIM_OCPolarity << 4); + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx Channel 2N polarity. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCNPolarity: specifies the OC2N Polarity + * This parameter can be one of the following values: + * @arg TIM_OCNPolarity_High: Output Compare active high + * @arg TIM_OCNPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); + + tmpccer = TIMx->CCER; + /* Set or Reset the CC2NP Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC2NP); + tmpccer |= (uint16_t)(TIM_OCNPolarity << 4); + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 3 polarity. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC3 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + tmpccer = TIMx->CCER; + /* Set or Reset the CC3P Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC3P); + tmpccer |= (uint16_t)(TIM_OCPolarity << 8); + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx Channel 3N polarity. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCNPolarity: specifies the OC3N Polarity + * This parameter can be one of the following values: + * @arg TIM_OCNPolarity_High: Output Compare active high + * @arg TIM_OCNPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) +{ + uint16_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); + + tmpccer = TIMx->CCER; + /* Set or Reset the CC3NP Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC3NP); + tmpccer |= (uint16_t)(TIM_OCNPolarity << 8); + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 4 polarity. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC4 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + tmpccer = TIMx->CCER; + /* Set or Reset the CC4P Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC4P); + tmpccer |= (uint16_t)(TIM_OCPolarity << 12); + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Enables or disables the TIM Capture Compare Channel x. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_Channel: specifies the TIM Channel + * This parameter can be one of the following values: + * @arg TIM_Channel_1: TIM Channel 1 + * @arg TIM_Channel_2: TIM Channel 2 + * @arg TIM_Channel_3: TIM Channel 3 + * @arg TIM_Channel_4: TIM Channel 4 + * @param TIM_CCx: specifies the TIM Channel CCxE bit new state. + * This parameter can be: TIM_CCx_Enable or TIM_CCx_Disable. + * @retval None + */ +void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx) +{ + uint16_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_CCX(TIM_CCx)); + + tmp = CCER_CCE_Set << TIM_Channel; + + /* Reset the CCxE Bit */ + TIMx->CCER &= (uint16_t)~ tmp; + + /* Set or reset the CCxE Bit */ + TIMx->CCER |= (uint16_t)(TIM_CCx << TIM_Channel); +} + +/** + * @brief Enables or disables the TIM Capture Compare Channel xN. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_Channel: specifies the TIM Channel + * This parameter can be one of the following values: + * @arg TIM_Channel_1: TIM Channel 1 + * @arg TIM_Channel_2: TIM Channel 2 + * @arg TIM_Channel_3: TIM Channel 3 + * @param TIM_CCxN: specifies the TIM Channel CCxNE bit new state. + * This parameter can be: TIM_CCxN_Enable or TIM_CCxN_Disable. + * @retval None + */ +void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN) +{ + uint16_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_COMPLEMENTARY_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_CCXN(TIM_CCxN)); + + tmp = CCER_CCNE_Set << TIM_Channel; + + /* Reset the CCxNE Bit */ + TIMx->CCER &= (uint16_t) ~tmp; + + /* Set or reset the CCxNE Bit */ + TIMx->CCER |= (uint16_t)(TIM_CCxN << TIM_Channel); +} + +/** + * @brief Selects the TIM Output Compare Mode. + * @note This function disables the selected channel before changing the Output + * Compare Mode. + * User has to enable this channel using TIM_CCxCmd and TIM_CCxNCmd functions. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_Channel: specifies the TIM Channel + * This parameter can be one of the following values: + * @arg TIM_Channel_1: TIM Channel 1 + * @arg TIM_Channel_2: TIM Channel 2 + * @arg TIM_Channel_3: TIM Channel 3 + * @arg TIM_Channel_4: TIM Channel 4 + * @param TIM_OCMode: specifies the TIM Output Compare Mode. + * This parameter can be one of the following values: + * @arg TIM_OCMode_Timing + * @arg TIM_OCMode_Active + * @arg TIM_OCMode_Toggle + * @arg TIM_OCMode_PWM1 + * @arg TIM_OCMode_PWM2 + * @arg TIM_ForcedAction_Active + * @arg TIM_ForcedAction_InActive + * @retval None + */ +void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode) +{ + uint32_t tmp = 0; + uint16_t tmp1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_OCM(TIM_OCMode)); + + tmp = (uint32_t) TIMx; + tmp += CCMR_Offset; + + tmp1 = CCER_CCE_Set << (uint16_t)TIM_Channel; + + /* Disable the Channel: Reset the CCxE Bit */ + TIMx->CCER &= (uint16_t) ~tmp1; + + if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) + { + tmp += (TIM_Channel>>1); + + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC1M); + + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= TIM_OCMode; + } + else + { + tmp += (uint16_t)(TIM_Channel - (uint16_t)4)>> (uint16_t)1; + + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC2M); + + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= (uint16_t)(TIM_OCMode << 8); + } +} + +/** + * @brief Enables or Disables the TIMx Update event. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param NewState: new state of the TIMx UDIS bit + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the Update Disable Bit */ + TIMx->CR1 |= TIM_CR1_UDIS; + } + else + { + /* Reset the Update Disable Bit */ + TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_UDIS); + } +} + +/** + * @brief Configures the TIMx Update Request Interrupt source. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_UpdateSource: specifies the Update source. + * This parameter can be one of the following values: + * @arg TIM_UpdateSource_Regular: Source of update is the counter overflow/underflow + or the setting of UG bit, or an update generation + through the slave mode controller. + * @arg TIM_UpdateSource_Global: Source of update is counter overflow/underflow. + * @retval None + */ +void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_UPDATE_SOURCE(TIM_UpdateSource)); + if (TIM_UpdateSource != TIM_UpdateSource_Global) + { + /* Set the URS Bit */ + TIMx->CR1 |= TIM_CR1_URS; + } + else + { + /* Reset the URS Bit */ + TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_URS); + } +} + +/** + * @brief Enables or disables the TIMx's Hall sensor interface. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param NewState: new state of the TIMx Hall sensor interface. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the TI1S Bit */ + TIMx->CR2 |= TIM_CR2_TI1S; + } + else + { + /* Reset the TI1S Bit */ + TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_TI1S); + } +} + +/** + * @brief Selects the TIMx's One Pulse Mode. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_OPMode: specifies the OPM Mode to be used. + * This parameter can be one of the following values: + * @arg TIM_OPMode_Single + * @arg TIM_OPMode_Repetitive + * @retval None + */ +void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_OPM_MODE(TIM_OPMode)); + /* Reset the OPM Bit */ + TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_OPM); + /* Configure the OPM Mode */ + TIMx->CR1 |= TIM_OPMode; +} + +/** + * @brief Selects the TIMx Trigger Output Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 6, 7, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_TRGOSource: specifies the Trigger Output source. + * This paramter can be one of the following values: + * + * - For all TIMx + * @arg TIM_TRGOSource_Reset: The UG bit in the TIM_EGR register is used as the trigger output (TRGO). + * @arg TIM_TRGOSource_Enable: The Counter Enable CEN is used as the trigger output (TRGO). + * @arg TIM_TRGOSource_Update: The update event is selected as the trigger output (TRGO). + * + * - For all TIMx except TIM6 and TIM7 + * @arg TIM_TRGOSource_OC1: The trigger output sends a positive pulse when the CC1IF flag + * is to be set, as soon as a capture or compare match occurs (TRGO). + * @arg TIM_TRGOSource_OC1Ref: OC1REF signal is used as the trigger output (TRGO). + * @arg TIM_TRGOSource_OC2Ref: OC2REF signal is used as the trigger output (TRGO). + * @arg TIM_TRGOSource_OC3Ref: OC3REF signal is used as the trigger output (TRGO). + * @arg TIM_TRGOSource_OC4Ref: OC4REF signal is used as the trigger output (TRGO). + * + * @retval None + */ +void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST7_PERIPH(TIMx)); + assert_param(IS_TIM_TRGO_SOURCE(TIM_TRGOSource)); + /* Reset the MMS Bits */ + TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_MMS); + /* Select the TRGO source */ + TIMx->CR2 |= TIM_TRGOSource; +} + +/** + * @brief Selects the TIMx Slave Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_SlaveMode: specifies the Timer Slave Mode. + * This parameter can be one of the following values: + * @arg TIM_SlaveMode_Reset: Rising edge of the selected trigger signal (TRGI) re-initializes + * the counter and triggers an update of the registers. + * @arg TIM_SlaveMode_Gated: The counter clock is enabled when the trigger signal (TRGI) is high. + * @arg TIM_SlaveMode_Trigger: The counter starts at a rising edge of the trigger TRGI. + * @arg TIM_SlaveMode_External1: Rising edges of the selected trigger (TRGI) clock the counter. + * @retval None + */ +void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_SLAVE_MODE(TIM_SlaveMode)); + /* Reset the SMS Bits */ + TIMx->SMCR &= (uint16_t)~((uint16_t)TIM_SMCR_SMS); + /* Select the Slave Mode */ + TIMx->SMCR |= TIM_SlaveMode; +} + +/** + * @brief Sets or Resets the TIMx Master/Slave Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_MasterSlaveMode: specifies the Timer Master Slave Mode. + * This parameter can be one of the following values: + * @arg TIM_MasterSlaveMode_Enable: synchronization between the current timer + * and its slaves (through TRGO). + * @arg TIM_MasterSlaveMode_Disable: No action + * @retval None + */ +void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_MSM_STATE(TIM_MasterSlaveMode)); + /* Reset the MSM Bit */ + TIMx->SMCR &= (uint16_t)~((uint16_t)TIM_SMCR_MSM); + + /* Set or Reset the MSM Bit */ + TIMx->SMCR |= TIM_MasterSlaveMode; +} + +/** + * @brief Sets the TIMx Counter Register value + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param Counter: specifies the Counter register new value. + * @retval None + */ +void TIM_SetCounter(TIM_TypeDef* TIMx, uint16_t Counter) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + /* Set the Counter Register value */ + TIMx->CNT = Counter; +} + +/** + * @brief Sets the TIMx Autoreload Register value + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param Autoreload: specifies the Autoreload register new value. + * @retval None + */ +void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint16_t Autoreload) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + /* Set the Autoreload Register value */ + TIMx->ARR = Autoreload; +} + +/** + * @brief Sets the TIMx Capture Compare1 Register value + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param Compare1: specifies the Capture Compare1 register new value. + * @retval None + */ +void TIM_SetCompare1(TIM_TypeDef* TIMx, uint16_t Compare1) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + /* Set the Capture Compare1 Register value */ + TIMx->CCR1 = Compare1; +} + +/** + * @brief Sets the TIMx Capture Compare2 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param Compare2: specifies the Capture Compare2 register new value. + * @retval None + */ +void TIM_SetCompare2(TIM_TypeDef* TIMx, uint16_t Compare2) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + /* Set the Capture Compare2 Register value */ + TIMx->CCR2 = Compare2; +} + +/** + * @brief Sets the TIMx Capture Compare3 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param Compare3: specifies the Capture Compare3 register new value. + * @retval None + */ +void TIM_SetCompare3(TIM_TypeDef* TIMx, uint16_t Compare3) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* Set the Capture Compare3 Register value */ + TIMx->CCR3 = Compare3; +} + +/** + * @brief Sets the TIMx Capture Compare4 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param Compare4: specifies the Capture Compare4 register new value. + * @retval None + */ +void TIM_SetCompare4(TIM_TypeDef* TIMx, uint16_t Compare4) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* Set the Capture Compare4 Register value */ + TIMx->CCR4 = Compare4; +} + +/** + * @brief Sets the TIMx Input Capture 1 prescaler. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture1 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + /* Reset the IC1PSC Bits */ + TIMx->CCMR1 &= (uint16_t)~((uint16_t)TIM_CCMR1_IC1PSC); + /* Set the IC1PSC value */ + TIMx->CCMR1 |= TIM_ICPSC; +} + +/** + * @brief Sets the TIMx Input Capture 2 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture2 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + /* Reset the IC2PSC Bits */ + TIMx->CCMR1 &= (uint16_t)~((uint16_t)TIM_CCMR1_IC2PSC); + /* Set the IC2PSC value */ + TIMx->CCMR1 |= (uint16_t)(TIM_ICPSC << 8); +} + +/** + * @brief Sets the TIMx Input Capture 3 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture3 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + /* Reset the IC3PSC Bits */ + TIMx->CCMR2 &= (uint16_t)~((uint16_t)TIM_CCMR2_IC3PSC); + /* Set the IC3PSC value */ + TIMx->CCMR2 |= TIM_ICPSC; +} + +/** + * @brief Sets the TIMx Input Capture 4 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture4 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + /* Reset the IC4PSC Bits */ + TIMx->CCMR2 &= (uint16_t)~((uint16_t)TIM_CCMR2_IC4PSC); + /* Set the IC4PSC value */ + TIMx->CCMR2 |= (uint16_t)(TIM_ICPSC << 8); +} + +/** + * @brief Sets the TIMx Clock Division value. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select + * the TIM peripheral. + * @param TIM_CKD: specifies the clock division value. + * This parameter can be one of the following value: + * @arg TIM_CKD_DIV1: TDTS = Tck_tim + * @arg TIM_CKD_DIV2: TDTS = 2*Tck_tim + * @arg TIM_CKD_DIV4: TDTS = 4*Tck_tim + * @retval None + */ +void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_CKD_DIV(TIM_CKD)); + /* Reset the CKD Bits */ + TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_CKD); + /* Set the CKD value */ + TIMx->CR1 |= TIM_CKD; +} + +/** + * @brief Gets the TIMx Input Capture 1 value. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @retval Capture Compare 1 Register value. + */ +uint16_t TIM_GetCapture1(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + /* Get the Capture 1 Register value */ + return TIMx->CCR1; +} + +/** + * @brief Gets the TIMx Input Capture 2 value. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @retval Capture Compare 2 Register value. + */ +uint16_t TIM_GetCapture2(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + /* Get the Capture 2 Register value */ + return TIMx->CCR2; +} + +/** + * @brief Gets the TIMx Input Capture 3 value. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @retval Capture Compare 3 Register value. + */ +uint16_t TIM_GetCapture3(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* Get the Capture 3 Register value */ + return TIMx->CCR3; +} + +/** + * @brief Gets the TIMx Input Capture 4 value. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @retval Capture Compare 4 Register value. + */ +uint16_t TIM_GetCapture4(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* Get the Capture 4 Register value */ + return TIMx->CCR4; +} + +/** + * @brief Gets the TIMx Counter value. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @retval Counter Register value. + */ +uint16_t TIM_GetCounter(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + /* Get the Counter Register value */ + return TIMx->CNT; +} + +/** + * @brief Gets the TIMx Prescaler value. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @retval Prescaler Register value. + */ +uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + /* Get the Prescaler Register value */ + return TIMx->PSC; +} + +/** + * @brief Checks whether the specified TIM flag is set or not. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg TIM_FLAG_Update: TIM update Flag + * @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag + * @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag + * @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag + * @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag + * @arg TIM_FLAG_COM: TIM Commutation Flag + * @arg TIM_FLAG_Trigger: TIM Trigger Flag + * @arg TIM_FLAG_Break: TIM Break Flag + * @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 overcapture Flag + * @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 overcapture Flag + * @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 overcapture Flag + * @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 overcapture Flag + * @note + * - TIM6 and TIM7 can have only one update flag. + * - TIM9, TIM12 and TIM15 can have only TIM_FLAG_Update, TIM_FLAG_CC1, + * TIM_FLAG_CC2 or TIM_FLAG_Trigger. + * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_FLAG_Update or TIM_FLAG_CC1. + * - TIM_FLAG_Break is used only with TIM1, TIM8 and TIM15. + * - TIM_FLAG_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. + * @retval The new state of TIM_FLAG (SET or RESET). + */ +FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint16_t TIM_FLAG) +{ + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_GET_FLAG(TIM_FLAG)); + + if ((TIMx->SR & TIM_FLAG) != (uint16_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the TIMx's pending flags. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_FLAG: specifies the flag bit to clear. + * This parameter can be any combination of the following values: + * @arg TIM_FLAG_Update: TIM update Flag + * @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag + * @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag + * @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag + * @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag + * @arg TIM_FLAG_COM: TIM Commutation Flag + * @arg TIM_FLAG_Trigger: TIM Trigger Flag + * @arg TIM_FLAG_Break: TIM Break Flag + * @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 overcapture Flag + * @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 overcapture Flag + * @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 overcapture Flag + * @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 overcapture Flag + * @note + * - TIM6 and TIM7 can have only one update flag. + * - TIM9, TIM12 and TIM15 can have only TIM_FLAG_Update, TIM_FLAG_CC1, + * TIM_FLAG_CC2 or TIM_FLAG_Trigger. + * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_FLAG_Update or TIM_FLAG_CC1. + * - TIM_FLAG_Break is used only with TIM1, TIM8 and TIM15. + * - TIM_FLAG_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. + * @retval None + */ +void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_CLEAR_FLAG(TIM_FLAG)); + + /* Clear the flags */ + TIMx->SR = (uint16_t)~TIM_FLAG; +} + +/** + * @brief Checks whether the TIM interrupt has occurred or not. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_IT: specifies the TIM interrupt source to check. + * This parameter can be one of the following values: + * @arg TIM_IT_Update: TIM update Interrupt source + * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source + * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source + * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source + * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source + * @arg TIM_IT_COM: TIM Commutation Interrupt source + * @arg TIM_IT_Trigger: TIM Trigger Interrupt source + * @arg TIM_IT_Break: TIM Break Interrupt source + * @note + * - TIM6 and TIM7 can generate only an update interrupt. + * - TIM9, TIM12 and TIM15 can have only TIM_IT_Update, TIM_IT_CC1, + * TIM_IT_CC2 or TIM_IT_Trigger. + * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_IT_Update or TIM_IT_CC1. + * - TIM_IT_Break is used only with TIM1, TIM8 and TIM15. + * - TIM_IT_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. + * @retval The new state of the TIM_IT(SET or RESET). + */ +ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT) +{ + ITStatus bitstatus = RESET; + uint16_t itstatus = 0x0, itenable = 0x0; + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_GET_IT(TIM_IT)); + + itstatus = TIMx->SR & TIM_IT; + + itenable = TIMx->DIER & TIM_IT; + if ((itstatus != (uint16_t)RESET) && (itenable != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the TIMx's interrupt pending bits. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_IT: specifies the pending bit to clear. + * This parameter can be any combination of the following values: + * @arg TIM_IT_Update: TIM1 update Interrupt source + * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source + * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source + * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source + * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source + * @arg TIM_IT_COM: TIM Commutation Interrupt source + * @arg TIM_IT_Trigger: TIM Trigger Interrupt source + * @arg TIM_IT_Break: TIM Break Interrupt source + * @note + * - TIM6 and TIM7 can generate only an update interrupt. + * - TIM9, TIM12 and TIM15 can have only TIM_IT_Update, TIM_IT_CC1, + * TIM_IT_CC2 or TIM_IT_Trigger. + * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_IT_Update or TIM_IT_CC1. + * - TIM_IT_Break is used only with TIM1, TIM8 and TIM15. + * - TIM_IT_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. + * @retval None + */ +void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_IT(TIM_IT)); + /* Clear the IT pending Bit */ + TIMx->SR = (uint16_t)~TIM_IT; +} + +/** + * @brief Configure the TI1 as Input. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 1 is selected to be connected to IC1. + * @arg TIM_ICSelection_IndirectTI: TIM Input 1 is selected to be connected to IC2. + * @arg TIM_ICSelection_TRC: TIM Input 1 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr1 = 0, tmpccer = 0; + /* Disable the Channel 1: Reset the CC1E Bit */ + TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC1E); + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + /* Select the Input and set the filter */ + tmpccmr1 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR1_CC1S)) & ((uint16_t)~((uint16_t)TIM_CCMR1_IC1F))); + tmpccmr1 |= (uint16_t)(TIM_ICSelection | (uint16_t)(TIM_ICFilter << (uint16_t)4)); + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || + (TIMx == TIM4) ||(TIMx == TIM5)) + { + /* Select the Polarity and set the CC1E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC1P)); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC1E); + } + else + { + /* Select the Polarity and set the CC1E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC1P | TIM_CCER_CC1NP)); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC1E); + } + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI2 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 2 is selected to be connected to IC2. + * @arg TIM_ICSelection_IndirectTI: TIM Input 2 is selected to be connected to IC1. + * @arg TIM_ICSelection_TRC: TIM Input 2 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr1 = 0, tmpccer = 0, tmp = 0; + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC2E); + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + tmp = (uint16_t)(TIM_ICPolarity << 4); + /* Select the Input and set the filter */ + tmpccmr1 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR1_CC2S)) & ((uint16_t)~((uint16_t)TIM_CCMR1_IC2F))); + tmpccmr1 |= (uint16_t)(TIM_ICFilter << 12); + tmpccmr1 |= (uint16_t)(TIM_ICSelection << 8); + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || + (TIMx == TIM4) ||(TIMx == TIM5)) + { + /* Select the Polarity and set the CC2E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC2P)); + tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC2E); + } + else + { + /* Select the Polarity and set the CC2E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC2P | TIM_CCER_CC2NP)); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC2E); + } + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1 ; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI3 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 3 is selected to be connected to IC3. + * @arg TIM_ICSelection_IndirectTI: TIM Input 3 is selected to be connected to IC4. + * @arg TIM_ICSelection_TRC: TIM Input 3 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0; + /* Disable the Channel 3: Reset the CC3E Bit */ + TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC3E); + tmpccmr2 = TIMx->CCMR2; + tmpccer = TIMx->CCER; + tmp = (uint16_t)(TIM_ICPolarity << 8); + /* Select the Input and set the filter */ + tmpccmr2 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR2_CC3S)) & ((uint16_t)~((uint16_t)TIM_CCMR2_IC3F))); + tmpccmr2 |= (uint16_t)(TIM_ICSelection | (uint16_t)(TIM_ICFilter << (uint16_t)4)); + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || + (TIMx == TIM4) ||(TIMx == TIM5)) + { + /* Select the Polarity and set the CC3E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC3P)); + tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC3E); + } + else + { + /* Select the Polarity and set the CC3E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC3P | TIM_CCER_CC3NP)); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC3E); + } + + /* Write to TIMx CCMR2 and CCER registers */ + TIMx->CCMR2 = tmpccmr2; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI4 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 4 is selected to be connected to IC4. + * @arg TIM_ICSelection_IndirectTI: TIM Input 4 is selected to be connected to IC3. + * @arg TIM_ICSelection_TRC: TIM Input 4 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0; + + /* Disable the Channel 4: Reset the CC4E Bit */ + TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC4E); + tmpccmr2 = TIMx->CCMR2; + tmpccer = TIMx->CCER; + tmp = (uint16_t)(TIM_ICPolarity << 12); + /* Select the Input and set the filter */ + tmpccmr2 &= (uint16_t)((uint16_t)(~(uint16_t)TIM_CCMR2_CC4S) & ((uint16_t)~((uint16_t)TIM_CCMR2_IC4F))); + tmpccmr2 |= (uint16_t)(TIM_ICSelection << 8); + tmpccmr2 |= (uint16_t)(TIM_ICFilter << 12); + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || + (TIMx == TIM4) ||(TIMx == TIM5)) + { + /* Select the Polarity and set the CC4E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC4P)); + tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC4E); + } + else + { + /* Select the Polarity and set the CC4E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC3P | TIM_CCER_CC4NP)); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC4E); + } + /* Write to TIMx CCMR2 and CCER registers */ + TIMx->CCMR2 = tmpccmr2; + TIMx->CCER = tmpccer; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c new file mode 100644 index 0000000..e794eae --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c @@ -0,0 +1,1058 @@ +/** + ****************************************************************************** + * @file stm32f10x_usart.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the USART firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_usart.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup USART + * @brief USART driver modules + * @{ + */ + +/** @defgroup USART_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup USART_Private_Defines + * @{ + */ + +#define CR1_UE_Set ((uint16_t)0x2000) /*!< USART Enable Mask */ +#define CR1_UE_Reset ((uint16_t)0xDFFF) /*!< USART Disable Mask */ + +#define CR1_WAKE_Mask ((uint16_t)0xF7FF) /*!< USART WakeUp Method Mask */ + +#define CR1_RWU_Set ((uint16_t)0x0002) /*!< USART mute mode Enable Mask */ +#define CR1_RWU_Reset ((uint16_t)0xFFFD) /*!< USART mute mode Enable Mask */ +#define CR1_SBK_Set ((uint16_t)0x0001) /*!< USART Break Character send Mask */ +#define CR1_CLEAR_Mask ((uint16_t)0xE9F3) /*!< USART CR1 Mask */ +#define CR2_Address_Mask ((uint16_t)0xFFF0) /*!< USART address Mask */ + +#define CR2_LINEN_Set ((uint16_t)0x4000) /*!< USART LIN Enable Mask */ +#define CR2_LINEN_Reset ((uint16_t)0xBFFF) /*!< USART LIN Disable Mask */ + +#define CR2_LBDL_Mask ((uint16_t)0xFFDF) /*!< USART LIN Break detection Mask */ +#define CR2_STOP_CLEAR_Mask ((uint16_t)0xCFFF) /*!< USART CR2 STOP Bits Mask */ +#define CR2_CLOCK_CLEAR_Mask ((uint16_t)0xF0FF) /*!< USART CR2 Clock Mask */ + +#define CR3_SCEN_Set ((uint16_t)0x0020) /*!< USART SC Enable Mask */ +#define CR3_SCEN_Reset ((uint16_t)0xFFDF) /*!< USART SC Disable Mask */ + +#define CR3_NACK_Set ((uint16_t)0x0010) /*!< USART SC NACK Enable Mask */ +#define CR3_NACK_Reset ((uint16_t)0xFFEF) /*!< USART SC NACK Disable Mask */ + +#define CR3_HDSEL_Set ((uint16_t)0x0008) /*!< USART Half-Duplex Enable Mask */ +#define CR3_HDSEL_Reset ((uint16_t)0xFFF7) /*!< USART Half-Duplex Disable Mask */ + +#define CR3_IRLP_Mask ((uint16_t)0xFFFB) /*!< USART IrDA LowPower mode Mask */ +#define CR3_CLEAR_Mask ((uint16_t)0xFCFF) /*!< USART CR3 Mask */ + +#define CR3_IREN_Set ((uint16_t)0x0002) /*!< USART IrDA Enable Mask */ +#define CR3_IREN_Reset ((uint16_t)0xFFFD) /*!< USART IrDA Disable Mask */ +#define GTPR_LSB_Mask ((uint16_t)0x00FF) /*!< Guard Time Register LSB Mask */ +#define GTPR_MSB_Mask ((uint16_t)0xFF00) /*!< Guard Time Register MSB Mask */ +#define IT_Mask ((uint16_t)0x001F) /*!< USART Interrupt Mask */ + +/* USART OverSampling-8 Mask */ +#define CR1_OVER8_Set ((u16)0x8000) /* USART OVER8 mode Enable Mask */ +#define CR1_OVER8_Reset ((u16)0x7FFF) /* USART OVER8 mode Disable Mask */ + +/* USART One Bit Sampling Mask */ +#define CR3_ONEBITE_Set ((u16)0x0800) /* USART ONEBITE mode Enable Mask */ +#define CR3_ONEBITE_Reset ((u16)0xF7FF) /* USART ONEBITE mode Disable Mask */ + +/** + * @} + */ + +/** @defgroup USART_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup USART_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup USART_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup USART_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the USARTx peripheral registers to their default reset values. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @retval None + */ +void USART_DeInit(USART_TypeDef* USARTx) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + if (USARTx == USART1) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, DISABLE); + } + else if (USARTx == USART2) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, DISABLE); + } + else if (USARTx == USART3) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, DISABLE); + } + else if (USARTx == UART4) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, DISABLE); + } + else + { + if (USARTx == UART5) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, DISABLE); + } + } +} + +/** + * @brief Initializes the USARTx peripheral according to the specified + * parameters in the USART_InitStruct . + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_InitStruct: pointer to a USART_InitTypeDef structure + * that contains the configuration information for the specified USART + * peripheral. + * @retval None + */ +void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct) +{ + uint32_t tmpreg = 0x00, apbclock = 0x00; + uint32_t integerdivider = 0x00; + uint32_t fractionaldivider = 0x00; + uint32_t usartxbase = 0; + RCC_ClocksTypeDef RCC_ClocksStatus; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_BAUDRATE(USART_InitStruct->USART_BaudRate)); + assert_param(IS_USART_WORD_LENGTH(USART_InitStruct->USART_WordLength)); + assert_param(IS_USART_STOPBITS(USART_InitStruct->USART_StopBits)); + assert_param(IS_USART_PARITY(USART_InitStruct->USART_Parity)); + assert_param(IS_USART_MODE(USART_InitStruct->USART_Mode)); + assert_param(IS_USART_HARDWARE_FLOW_CONTROL(USART_InitStruct->USART_HardwareFlowControl)); + /* The hardware flow control is available only for USART1, USART2 and USART3 */ + if (USART_InitStruct->USART_HardwareFlowControl != USART_HardwareFlowControl_None) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + usartxbase = (uint32_t)USARTx; + +/*---------------------------- USART CR2 Configuration -----------------------*/ + tmpreg = USARTx->CR2; + /* Clear STOP[13:12] bits */ + tmpreg &= CR2_STOP_CLEAR_Mask; + /* Configure the USART Stop Bits, Clock, CPOL, CPHA and LastBit ------------*/ + /* Set STOP[13:12] bits according to USART_StopBits value */ + tmpreg |= (uint32_t)USART_InitStruct->USART_StopBits; + + /* Write to USART CR2 */ + USARTx->CR2 = (uint16_t)tmpreg; + +/*---------------------------- USART CR1 Configuration -----------------------*/ + tmpreg = USARTx->CR1; + /* Clear M, PCE, PS, TE and RE bits */ + tmpreg &= CR1_CLEAR_Mask; + /* Configure the USART Word Length, Parity and mode ----------------------- */ + /* Set the M bits according to USART_WordLength value */ + /* Set PCE and PS bits according to USART_Parity value */ + /* Set TE and RE bits according to USART_Mode value */ + tmpreg |= (uint32_t)USART_InitStruct->USART_WordLength | USART_InitStruct->USART_Parity | + USART_InitStruct->USART_Mode; + /* Write to USART CR1 */ + USARTx->CR1 = (uint16_t)tmpreg; + +/*---------------------------- USART CR3 Configuration -----------------------*/ + tmpreg = USARTx->CR3; + /* Clear CTSE and RTSE bits */ + tmpreg &= CR3_CLEAR_Mask; + /* Configure the USART HFC -------------------------------------------------*/ + /* Set CTSE and RTSE bits according to USART_HardwareFlowControl value */ + tmpreg |= USART_InitStruct->USART_HardwareFlowControl; + /* Write to USART CR3 */ + USARTx->CR3 = (uint16_t)tmpreg; + +/*---------------------------- USART BRR Configuration -----------------------*/ + /* Configure the USART Baud Rate -------------------------------------------*/ + RCC_GetClocksFreq(&RCC_ClocksStatus); + if (usartxbase == USART1_BASE) + { + apbclock = RCC_ClocksStatus.PCLK2_Frequency; + } + else + { + apbclock = RCC_ClocksStatus.PCLK1_Frequency; + } + + /* Determine the integer part */ + if ((USARTx->CR1 & CR1_OVER8_Set) != 0) + { + /* Integer part computing in case Oversampling mode is 8 Samples */ + integerdivider = ((25 * apbclock) / (2 * (USART_InitStruct->USART_BaudRate))); + } + else /* if ((USARTx->CR1 & CR1_OVER8_Set) == 0) */ + { + /* Integer part computing in case Oversampling mode is 16 Samples */ + integerdivider = ((25 * apbclock) / (4 * (USART_InitStruct->USART_BaudRate))); + } + tmpreg = (integerdivider / 100) << 4; + + /* Determine the fractional part */ + fractionaldivider = integerdivider - (100 * (tmpreg >> 4)); + + /* Implement the fractional part in the register */ + if ((USARTx->CR1 & CR1_OVER8_Set) != 0) + { + tmpreg |= ((((fractionaldivider * 8) + 50) / 100)) & ((uint8_t)0x07); + } + else /* if ((USARTx->CR1 & CR1_OVER8_Set) == 0) */ + { + tmpreg |= ((((fractionaldivider * 16) + 50) / 100)) & ((uint8_t)0x0F); + } + + /* Write to USART BRR */ + USARTx->BRR = (uint16_t)tmpreg; +} + +/** + * @brief Fills each USART_InitStruct member with its default value. + * @param USART_InitStruct: pointer to a USART_InitTypeDef structure + * which will be initialized. + * @retval None + */ +void USART_StructInit(USART_InitTypeDef* USART_InitStruct) +{ + /* USART_InitStruct members default value */ + USART_InitStruct->USART_BaudRate = 9600; + USART_InitStruct->USART_WordLength = USART_WordLength_8b; + USART_InitStruct->USART_StopBits = USART_StopBits_1; + USART_InitStruct->USART_Parity = USART_Parity_No ; + USART_InitStruct->USART_Mode = USART_Mode_Rx | USART_Mode_Tx; + USART_InitStruct->USART_HardwareFlowControl = USART_HardwareFlowControl_None; +} + +/** + * @brief Initializes the USARTx peripheral Clock according to the + * specified parameters in the USART_ClockInitStruct . + * @param USARTx: where x can be 1, 2, 3 to select the USART peripheral. + * @param USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef + * structure that contains the configuration information for the specified + * USART peripheral. + * @note The Smart Card and Synchronous modes are not available for UART4 and UART5. + * @retval None + */ +void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct) +{ + uint32_t tmpreg = 0x00; + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + assert_param(IS_USART_CLOCK(USART_ClockInitStruct->USART_Clock)); + assert_param(IS_USART_CPOL(USART_ClockInitStruct->USART_CPOL)); + assert_param(IS_USART_CPHA(USART_ClockInitStruct->USART_CPHA)); + assert_param(IS_USART_LASTBIT(USART_ClockInitStruct->USART_LastBit)); + +/*---------------------------- USART CR2 Configuration -----------------------*/ + tmpreg = USARTx->CR2; + /* Clear CLKEN, CPOL, CPHA and LBCL bits */ + tmpreg &= CR2_CLOCK_CLEAR_Mask; + /* Configure the USART Clock, CPOL, CPHA and LastBit ------------*/ + /* Set CLKEN bit according to USART_Clock value */ + /* Set CPOL bit according to USART_CPOL value */ + /* Set CPHA bit according to USART_CPHA value */ + /* Set LBCL bit according to USART_LastBit value */ + tmpreg |= (uint32_t)USART_ClockInitStruct->USART_Clock | USART_ClockInitStruct->USART_CPOL | + USART_ClockInitStruct->USART_CPHA | USART_ClockInitStruct->USART_LastBit; + /* Write to USART CR2 */ + USARTx->CR2 = (uint16_t)tmpreg; +} + +/** + * @brief Fills each USART_ClockInitStruct member with its default value. + * @param USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef + * structure which will be initialized. + * @retval None + */ +void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct) +{ + /* USART_ClockInitStruct members default value */ + USART_ClockInitStruct->USART_Clock = USART_Clock_Disable; + USART_ClockInitStruct->USART_CPOL = USART_CPOL_Low; + USART_ClockInitStruct->USART_CPHA = USART_CPHA_1Edge; + USART_ClockInitStruct->USART_LastBit = USART_LastBit_Disable; +} + +/** + * @brief Enables or disables the specified USART peripheral. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USARTx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected USART by setting the UE bit in the CR1 register */ + USARTx->CR1 |= CR1_UE_Set; + } + else + { + /* Disable the selected USART by clearing the UE bit in the CR1 register */ + USARTx->CR1 &= CR1_UE_Reset; + } +} + +/** + * @brief Enables or disables the specified USART interrupts. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_IT: specifies the USART interrupt sources to be enabled or disabled. + * This parameter can be one of the following values: + * @arg USART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) + * @arg USART_IT_LBD: LIN Break detection interrupt + * @arg USART_IT_TXE: Transmit Data Register empty interrupt + * @arg USART_IT_TC: Transmission complete interrupt + * @arg USART_IT_RXNE: Receive Data register not empty interrupt + * @arg USART_IT_IDLE: Idle line detection interrupt + * @arg USART_IT_PE: Parity Error interrupt + * @arg USART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) + * @param NewState: new state of the specified USARTx interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState) +{ + uint32_t usartreg = 0x00, itpos = 0x00, itmask = 0x00; + uint32_t usartxbase = 0x00; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_CONFIG_IT(USART_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + /* The CTS interrupt is not available for UART4 and UART5 */ + if (USART_IT == USART_IT_CTS) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + usartxbase = (uint32_t)USARTx; + + /* Get the USART register index */ + usartreg = (((uint8_t)USART_IT) >> 0x05); + + /* Get the interrupt position */ + itpos = USART_IT & IT_Mask; + itmask = (((uint32_t)0x01) << itpos); + + if (usartreg == 0x01) /* The IT is in CR1 register */ + { + usartxbase += 0x0C; + } + else if (usartreg == 0x02) /* The IT is in CR2 register */ + { + usartxbase += 0x10; + } + else /* The IT is in CR3 register */ + { + usartxbase += 0x14; + } + if (NewState != DISABLE) + { + *(__IO uint32_t*)usartxbase |= itmask; + } + else + { + *(__IO uint32_t*)usartxbase &= ~itmask; + } +} + +/** + * @brief Enables or disables the USART’s DMA interface. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_DMAReq: specifies the DMA request. + * This parameter can be any combination of the following values: + * @arg USART_DMAReq_Tx: USART DMA transmit request + * @arg USART_DMAReq_Rx: USART DMA receive request + * @param NewState: new state of the DMA Request sources. + * This parameter can be: ENABLE or DISABLE. + * @note The DMA mode is not available for UART5 except in the STM32 + * High density value line devices(STM32F10X_HD_VL). + * @retval None + */ +void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_DMAREQ(USART_DMAReq)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the DMA transfer for selected requests by setting the DMAT and/or + DMAR bits in the USART CR3 register */ + USARTx->CR3 |= USART_DMAReq; + } + else + { + /* Disable the DMA transfer for selected requests by clearing the DMAT and/or + DMAR bits in the USART CR3 register */ + USARTx->CR3 &= (uint16_t)~USART_DMAReq; + } +} + +/** + * @brief Sets the address of the USART node. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_Address: Indicates the address of the USART node. + * @retval None + */ +void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_ADDRESS(USART_Address)); + + /* Clear the USART address */ + USARTx->CR2 &= CR2_Address_Mask; + /* Set the USART address node */ + USARTx->CR2 |= USART_Address; +} + +/** + * @brief Selects the USART WakeUp method. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_WakeUp: specifies the USART wakeup method. + * This parameter can be one of the following values: + * @arg USART_WakeUp_IdleLine: WakeUp by an idle line detection + * @arg USART_WakeUp_AddressMark: WakeUp by an address mark + * @retval None + */ +void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_WAKEUP(USART_WakeUp)); + + USARTx->CR1 &= CR1_WAKE_Mask; + USARTx->CR1 |= USART_WakeUp; +} + +/** + * @brief Determines if the USART is in mute mode or not. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USART mute mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the USART mute mode by setting the RWU bit in the CR1 register */ + USARTx->CR1 |= CR1_RWU_Set; + } + else + { + /* Disable the USART mute mode by clearing the RWU bit in the CR1 register */ + USARTx->CR1 &= CR1_RWU_Reset; + } +} + +/** + * @brief Sets the USART LIN Break detection length. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_LINBreakDetectLength: specifies the LIN break detection length. + * This parameter can be one of the following values: + * @arg USART_LINBreakDetectLength_10b: 10-bit break detection + * @arg USART_LINBreakDetectLength_11b: 11-bit break detection + * @retval None + */ +void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_LIN_BREAK_DETECT_LENGTH(USART_LINBreakDetectLength)); + + USARTx->CR2 &= CR2_LBDL_Mask; + USARTx->CR2 |= USART_LINBreakDetectLength; +} + +/** + * @brief Enables or disables the USART’s LIN mode. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USART LIN mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the LIN mode by setting the LINEN bit in the CR2 register */ + USARTx->CR2 |= CR2_LINEN_Set; + } + else + { + /* Disable the LIN mode by clearing the LINEN bit in the CR2 register */ + USARTx->CR2 &= CR2_LINEN_Reset; + } +} + +/** + * @brief Transmits single data through the USARTx peripheral. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param Data: the data to transmit. + * @retval None + */ +void USART_SendData(USART_TypeDef* USARTx, uint16_t Data) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_DATA(Data)); + + /* Transmit Data */ + USARTx->DR = (Data & (uint16_t)0x01FF); +} + +/** + * @brief Returns the most recent received data by the USARTx peripheral. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @retval The received data. + */ +uint16_t USART_ReceiveData(USART_TypeDef* USARTx) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + /* Receive Data */ + return (uint16_t)(USARTx->DR & (uint16_t)0x01FF); +} + +/** + * @brief Transmits break characters. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @retval None + */ +void USART_SendBreak(USART_TypeDef* USARTx) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + /* Send break characters */ + USARTx->CR1 |= CR1_SBK_Set; +} + +/** + * @brief Sets the specified USART guard time. + * @param USARTx: where x can be 1, 2 or 3 to select the USART peripheral. + * @param USART_GuardTime: specifies the guard time. + * @note The guard time bits are not available for UART4 and UART5. + * @retval None + */ +void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime) +{ + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + + /* Clear the USART Guard time */ + USARTx->GTPR &= GTPR_LSB_Mask; + /* Set the USART guard time */ + USARTx->GTPR |= (uint16_t)((uint16_t)USART_GuardTime << 0x08); +} + +/** + * @brief Sets the system clock prescaler. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_Prescaler: specifies the prescaler clock. + * @note The function is used for IrDA mode with UART4 and UART5. + * @retval None + */ +void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + /* Clear the USART prescaler */ + USARTx->GTPR &= GTPR_MSB_Mask; + /* Set the USART prescaler */ + USARTx->GTPR |= USART_Prescaler; +} + +/** + * @brief Enables or disables the USART’s Smart Card mode. + * @param USARTx: where x can be 1, 2 or 3 to select the USART peripheral. + * @param NewState: new state of the Smart Card mode. + * This parameter can be: ENABLE or DISABLE. + * @note The Smart Card mode is not available for UART4 and UART5. + * @retval None + */ +void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the SC mode by setting the SCEN bit in the CR3 register */ + USARTx->CR3 |= CR3_SCEN_Set; + } + else + { + /* Disable the SC mode by clearing the SCEN bit in the CR3 register */ + USARTx->CR3 &= CR3_SCEN_Reset; + } +} + +/** + * @brief Enables or disables NACK transmission. + * @param USARTx: where x can be 1, 2 or 3 to select the USART peripheral. + * @param NewState: new state of the NACK transmission. + * This parameter can be: ENABLE or DISABLE. + * @note The Smart Card mode is not available for UART4 and UART5. + * @retval None + */ +void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the NACK transmission by setting the NACK bit in the CR3 register */ + USARTx->CR3 |= CR3_NACK_Set; + } + else + { + /* Disable the NACK transmission by clearing the NACK bit in the CR3 register */ + USARTx->CR3 &= CR3_NACK_Reset; + } +} + +/** + * @brief Enables or disables the USART’s Half Duplex communication. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USART Communication. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Half-Duplex mode by setting the HDSEL bit in the CR3 register */ + USARTx->CR3 |= CR3_HDSEL_Set; + } + else + { + /* Disable the Half-Duplex mode by clearing the HDSEL bit in the CR3 register */ + USARTx->CR3 &= CR3_HDSEL_Reset; + } +} + + +/** + * @brief Enables or disables the USART's 8x oversampling mode. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USART one bit sampling method. + * This parameter can be: ENABLE or DISABLE. + * @note + * This function has to be called before calling USART_Init() + * function in order to have correct baudrate Divider value. + * @retval None + */ +void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the 8x Oversampling mode by setting the OVER8 bit in the CR1 register */ + USARTx->CR1 |= CR1_OVER8_Set; + } + else + { + /* Disable the 8x Oversampling mode by clearing the OVER8 bit in the CR1 register */ + USARTx->CR1 &= CR1_OVER8_Reset; + } +} + +/** + * @brief Enables or disables the USART's one bit sampling method. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USART one bit sampling method. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the one bit method by setting the ONEBITE bit in the CR3 register */ + USARTx->CR3 |= CR3_ONEBITE_Set; + } + else + { + /* Disable tthe one bit method by clearing the ONEBITE bit in the CR3 register */ + USARTx->CR3 &= CR3_ONEBITE_Reset; + } +} + +/** + * @brief Configures the USART's IrDA interface. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_IrDAMode: specifies the IrDA mode. + * This parameter can be one of the following values: + * @arg USART_IrDAMode_LowPower + * @arg USART_IrDAMode_Normal + * @retval None + */ +void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_IRDA_MODE(USART_IrDAMode)); + + USARTx->CR3 &= CR3_IRLP_Mask; + USARTx->CR3 |= USART_IrDAMode; +} + +/** + * @brief Enables or disables the USART's IrDA interface. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the IrDA mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the IrDA mode by setting the IREN bit in the CR3 register */ + USARTx->CR3 |= CR3_IREN_Set; + } + else + { + /* Disable the IrDA mode by clearing the IREN bit in the CR3 register */ + USARTx->CR3 &= CR3_IREN_Reset; + } +} + +/** + * @brief Checks whether the specified USART flag is set or not. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg USART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5) + * @arg USART_FLAG_LBD: LIN Break detection flag + * @arg USART_FLAG_TXE: Transmit data register empty flag + * @arg USART_FLAG_TC: Transmission Complete flag + * @arg USART_FLAG_RXNE: Receive data register not empty flag + * @arg USART_FLAG_IDLE: Idle Line detection flag + * @arg USART_FLAG_ORE: OverRun Error flag + * @arg USART_FLAG_NE: Noise Error flag + * @arg USART_FLAG_FE: Framing Error flag + * @arg USART_FLAG_PE: Parity Error flag + * @retval The new state of USART_FLAG (SET or RESET). + */ +FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_FLAG(USART_FLAG)); + /* The CTS flag is not available for UART4 and UART5 */ + if (USART_FLAG == USART_FLAG_CTS) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + if ((USARTx->SR & USART_FLAG) != (uint16_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the USARTx's pending flags. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg USART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5). + * @arg USART_FLAG_LBD: LIN Break detection flag. + * @arg USART_FLAG_TC: Transmission Complete flag. + * @arg USART_FLAG_RXNE: Receive data register not empty flag. + * + * @note + * - PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun + * error) and IDLE (Idle line detected) flags are cleared by software + * sequence: a read operation to USART_SR register (USART_GetFlagStatus()) + * followed by a read operation to USART_DR register (USART_ReceiveData()). + * - RXNE flag can be also cleared by a read to the USART_DR register + * (USART_ReceiveData()). + * - TC flag can be also cleared by software sequence: a read operation to + * USART_SR register (USART_GetFlagStatus()) followed by a write operation + * to USART_DR register (USART_SendData()). + * - TXE flag is cleared only by a write to the USART_DR register + * (USART_SendData()). + * @retval None + */ +void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_CLEAR_FLAG(USART_FLAG)); + /* The CTS flag is not available for UART4 and UART5 */ + if ((USART_FLAG & USART_FLAG_CTS) == USART_FLAG_CTS) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + USARTx->SR = (uint16_t)~USART_FLAG; +} + +/** + * @brief Checks whether the specified USART interrupt has occurred or not. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_IT: specifies the USART interrupt source to check. + * This parameter can be one of the following values: + * @arg USART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) + * @arg USART_IT_LBD: LIN Break detection interrupt + * @arg USART_IT_TXE: Tansmit Data Register empty interrupt + * @arg USART_IT_TC: Transmission complete interrupt + * @arg USART_IT_RXNE: Receive Data register not empty interrupt + * @arg USART_IT_IDLE: Idle line detection interrupt + * @arg USART_IT_ORE: OverRun Error interrupt + * @arg USART_IT_NE: Noise Error interrupt + * @arg USART_IT_FE: Framing Error interrupt + * @arg USART_IT_PE: Parity Error interrupt + * @retval The new state of USART_IT (SET or RESET). + */ +ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT) +{ + uint32_t bitpos = 0x00, itmask = 0x00, usartreg = 0x00; + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_GET_IT(USART_IT)); + /* The CTS interrupt is not available for UART4 and UART5 */ + if (USART_IT == USART_IT_CTS) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + /* Get the USART register index */ + usartreg = (((uint8_t)USART_IT) >> 0x05); + /* Get the interrupt position */ + itmask = USART_IT & IT_Mask; + itmask = (uint32_t)0x01 << itmask; + + if (usartreg == 0x01) /* The IT is in CR1 register */ + { + itmask &= USARTx->CR1; + } + else if (usartreg == 0x02) /* The IT is in CR2 register */ + { + itmask &= USARTx->CR2; + } + else /* The IT is in CR3 register */ + { + itmask &= USARTx->CR3; + } + + bitpos = USART_IT >> 0x08; + bitpos = (uint32_t)0x01 << bitpos; + bitpos &= USARTx->SR; + if ((itmask != (uint16_t)RESET)&&(bitpos != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + + return bitstatus; +} + +/** + * @brief Clears the USARTx's interrupt pending bits. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_IT: specifies the interrupt pending bit to clear. + * This parameter can be one of the following values: + * @arg USART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) + * @arg USART_IT_LBD: LIN Break detection interrupt + * @arg USART_IT_TC: Transmission complete interrupt. + * @arg USART_IT_RXNE: Receive Data register not empty interrupt. + * + * @note + * - PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun + * error) and IDLE (Idle line detected) pending bits are cleared by + * software sequence: a read operation to USART_SR register + * (USART_GetITStatus()) followed by a read operation to USART_DR register + * (USART_ReceiveData()). + * - RXNE pending bit can be also cleared by a read to the USART_DR register + * (USART_ReceiveData()). + * - TC pending bit can be also cleared by software sequence: a read + * operation to USART_SR register (USART_GetITStatus()) followed by a write + * operation to USART_DR register (USART_SendData()). + * - TXE pending bit is cleared only by a write to the USART_DR register + * (USART_SendData()). + * @retval None + */ +void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT) +{ + uint16_t bitpos = 0x00, itmask = 0x00; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_CLEAR_IT(USART_IT)); + /* The CTS interrupt is not available for UART4 and UART5 */ + if (USART_IT == USART_IT_CTS) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + bitpos = USART_IT >> 0x08; + itmask = ((uint16_t)0x01 << (uint16_t)bitpos); + USARTx->SR = (uint16_t)~itmask; +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c new file mode 100644 index 0000000..4a901e4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c @@ -0,0 +1,224 @@ +/** + ****************************************************************************** + * @file stm32f10x_wwdg.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the WWDG firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_wwdg.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup WWDG + * @brief WWDG driver modules + * @{ + */ + +/** @defgroup WWDG_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup WWDG_Private_Defines + * @{ + */ + +/* ----------- WWDG registers bit address in the alias region ----------- */ +#define WWDG_OFFSET (WWDG_BASE - PERIPH_BASE) + +/* Alias word address of EWI bit */ +#define CFR_OFFSET (WWDG_OFFSET + 0x04) +#define EWI_BitNumber 0x09 +#define CFR_EWI_BB (PERIPH_BB_BASE + (CFR_OFFSET * 32) + (EWI_BitNumber * 4)) + +/* --------------------- WWDG registers bit mask ------------------------ */ + +/* CR register bit mask */ +#define CR_WDGA_Set ((uint32_t)0x00000080) + +/* CFR register bit mask */ +#define CFR_WDGTB_Mask ((uint32_t)0xFFFFFE7F) +#define CFR_W_Mask ((uint32_t)0xFFFFFF80) +#define BIT_Mask ((uint8_t)0x7F) + +/** + * @} + */ + +/** @defgroup WWDG_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup WWDG_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup WWDG_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup WWDG_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the WWDG peripheral registers to their default reset values. + * @param None + * @retval None + */ +void WWDG_DeInit(void) +{ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, DISABLE); +} + +/** + * @brief Sets the WWDG Prescaler. + * @param WWDG_Prescaler: specifies the WWDG Prescaler. + * This parameter can be one of the following values: + * @arg WWDG_Prescaler_1: WWDG counter clock = (PCLK1/4096)/1 + * @arg WWDG_Prescaler_2: WWDG counter clock = (PCLK1/4096)/2 + * @arg WWDG_Prescaler_4: WWDG counter clock = (PCLK1/4096)/4 + * @arg WWDG_Prescaler_8: WWDG counter clock = (PCLK1/4096)/8 + * @retval None + */ +void WWDG_SetPrescaler(uint32_t WWDG_Prescaler) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_WWDG_PRESCALER(WWDG_Prescaler)); + /* Clear WDGTB[1:0] bits */ + tmpreg = WWDG->CFR & CFR_WDGTB_Mask; + /* Set WDGTB[1:0] bits according to WWDG_Prescaler value */ + tmpreg |= WWDG_Prescaler; + /* Store the new value */ + WWDG->CFR = tmpreg; +} + +/** + * @brief Sets the WWDG window value. + * @param WindowValue: specifies the window value to be compared to the downcounter. + * This parameter value must be lower than 0x80. + * @retval None + */ +void WWDG_SetWindowValue(uint8_t WindowValue) +{ + __IO uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_WWDG_WINDOW_VALUE(WindowValue)); + /* Clear W[6:0] bits */ + + tmpreg = WWDG->CFR & CFR_W_Mask; + + /* Set W[6:0] bits according to WindowValue value */ + tmpreg |= WindowValue & (uint32_t) BIT_Mask; + + /* Store the new value */ + WWDG->CFR = tmpreg; +} + +/** + * @brief Enables the WWDG Early Wakeup interrupt(EWI). + * @param None + * @retval None + */ +void WWDG_EnableIT(void) +{ + *(__IO uint32_t *) CFR_EWI_BB = (uint32_t)ENABLE; +} + +/** + * @brief Sets the WWDG counter value. + * @param Counter: specifies the watchdog counter value. + * This parameter must be a number between 0x40 and 0x7F. + * @retval None + */ +void WWDG_SetCounter(uint8_t Counter) +{ + /* Check the parameters */ + assert_param(IS_WWDG_COUNTER(Counter)); + /* Write to T[6:0] bits to configure the counter value, no need to do + a read-modify-write; writing a 0 to WDGA bit does nothing */ + WWDG->CR = Counter & BIT_Mask; +} + +/** + * @brief Enables WWDG and load the counter value. + * @param Counter: specifies the watchdog counter value. + * This parameter must be a number between 0x40 and 0x7F. + * @retval None + */ +void WWDG_Enable(uint8_t Counter) +{ + /* Check the parameters */ + assert_param(IS_WWDG_COUNTER(Counter)); + WWDG->CR = CR_WDGA_Set | Counter; +} + +/** + * @brief Checks whether the Early Wakeup interrupt flag is set or not. + * @param None + * @retval The new state of the Early Wakeup interrupt flag (SET or RESET) + */ +FlagStatus WWDG_GetFlagStatus(void) +{ + return (FlagStatus)(WWDG->SR); +} + +/** + * @brief Clears Early Wakeup interrupt flag. + * @param None + * @retval None + */ +void WWDG_ClearFlag(void) +{ + WWDG->SR = (uint32_t)RESET; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/Release_Notes.html b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/Release_Notes.html new file mode 100644 index 0000000..0361fd8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/Release_Notes.html @@ -0,0 +1,409 @@ + + + + + + + + + +Release Notes for STM32F30x Standard Peripherals Library Drivers + + + + + + +
+


+

+
+ + + + + + +
+ + + + + + +
+ +

Release +Notes for STM32F30x Standard Peripherals Library Drivers (StdPeriph_Drivers)
+

+

Copyright +© 2014 STMicroelectronics

+

+
+

 

+ + + + + + +
+

Update history

+ +

V1.1.1 /04-April-2014

+ + +

Main +Changes

+ + + + + + + + + + + +
  • stm32f30x_hrtim.c/.h: 
    • Add "HRTIM_SINGLE_CALIBRATION" define.
    • Add HRTIM Common flags definition
    • Add new function HRTIM_SlaveSetCompare(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, uint32_t CompareUnit, uint32_t Compare).
    • Update HRTIM_DLLCalibrationStart() function.
    • Update HRTIM_DMACmd(), HRTIM_GetITStatus(), HRTIM_GetFlagStatus(), HRTIM_ClearITPendingBit(), HRTIM_ClearFlag() and HRTIM_ITConfig() functions to properly manage master and slave HRTIMERS.

V1.1.0 /27-February-2014

+ + +

Main +Changes

+ + + + + + + + + + + +
  • Add support of the STM32F302x8 and STM32F334x8 devices.
  • Add High Resolution Timer(HRTIM) peripheral driver.
  • stm32f30x_adc.c
    • Update ADC_TempSensorCmd() and ADC_VbatCmd() functions to be inline with the devices specification.
    • Update ADC_DMAConfig() function description.
  • stm32f30x_dac.c/.h: update overall driver to add the support of the DAC2.
  • stm32f30x_gpio.c: 
    • Update +GPIO_Init() function to avoid unexpected transition in the GPIO +pin configuration when writing to the PUPDR register.
  • stm32f30x_rcc.c/.h: update for STM32F302x8 and STM32F334x8 devices
    • Add new function RCC_MCOConfig(uint8_t RCC_MCOSource, uint32_t RCC_MCOPrescaler).
    • Update RCC_GetClocksFreq() funtion to :
      • properly return the ADC clock frequency,
      • workarround USART1 clock limitation for the STM32F302x8 and STM32F334x8 devices,
      • support TIM15, 16, 17, HRTIM and I2C3 peripherals.
    • Update RCC_I2CCLKConfig() function to support I2C3 peripheral.
    • Update RCC_TIMCLKConfig() function to support TIM15, 16, and 17 peripherals.
    • Add RCC_HRTIM1CLKConfig() function.
  • stm32f30x_syscfg.c/.h
    • Update SYSCFG_DMAChannelRemapConfig() function to support new DMA channels remap.
    • Update SYSCFG_TriggerRemapConfig() funciton to support the new remap of DAC trigger to HRTIM.
  • stm32f30x_tim.c:
    • Update TIM_SelectOCxM() function to properly manage the output compare modes.

V1.0.1 / 23-October-2012

+ + +

Main +Changes

+ + + +
  • + + + +

    stm32f30x_adc.c/h

    • Remove +the following functions, the configuration will be done under ADC_Init function :

      • ADC_InjectedSequencerLengthConfig; +

      • ADC_InjectedChannelConfig;

      • ADC_ExternalTriggerInjectedPolarityConfig;

      • ADC_SelectExternalTriggerInjected

    • Update + comment of uint8_t ADC_TwoSamplingDelay parameter in +ADC_CommonInitTypeDef structure definition.

    • Add +a function to configure the sampling time for injected channels : void +ADC_InjectedChannelSampleTimeConfig (ADC_TypeDef* ADCx, uint8_t +ADC_InjectedChannel, uint8_t ADC_SampleTime);

+ + + + + + + + + + + + + + + + + +

+

  • stm32f30x_rtc.c

    • Update +comments : remove all reference to RTC_AF1, reformulate +the PC13 RTC_AF table to be in line with the description in Reference manual (RM00316)

  • + + + +

     stm32f30x_tim.c +

    • Update local variables declaration (must be uint32_t) to correct Tasking toochain warnings.  

  • stm32f30x_gpio.h +
    • Update GPIOSpeed_TypeDef parameters structure to be in line with description in Reference manual and add GPIO speed legacy defines.

  • Remove all references to other products (STM32F37x, STM32F0xx,...) in the comments.

V1.0.0 / 04-September-2012

+ + +

Main +Changes

+ + + +
  • First official release for STM32F30x and STM32F31x devices
+
    + +

    License

    Licensed +under MCD-ST Liberty SW License Agreement V2, (the "License"); You may not use +this package +except in compliance with the License. You may obtain a copy of the License +at:

    +
    Unless +required by applicable law or agreed to in writing, software distributed under +the License is distributed on an "AS IS" BASIS,
    WITHOUT WARRANTIES OR +CONDITIONS OF ANY KIND, either express or implied. See the License for the +specific language governing permissions and limitations under the +License.

    +
    +
    +

    For +complete documentation on STM32 Microcontrollers visit www.st.com/STM32

    +
    +

    +
    +
    +

     

    +
    + \ No newline at end of file diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_adc.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_adc.h new file mode 100644 index 0000000..ba5b70b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_adc.h @@ -0,0 +1,820 @@ +/** + ****************************************************************************** + * @file stm32f30x_adc.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the ADC firmware + * library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_ADC_H +#define __STM32F30x_ADC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup ADC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief ADC Init structure definition + */ +typedef struct +{ + + uint32_t ADC_ContinuousConvMode; /*!< Specifies whether the conversion is performed in + Continuous or Single mode. + This parameter can be set to ENABLE or DISABLE. */ + uint32_t ADC_Resolution; /*!< Configures the ADC resolution. + This parameter can be a value of @ref ADC_resolution */ + uint32_t ADC_ExternalTrigConvEvent; /*!< Defines the external trigger used to start the analog + to digital conversion of regular channels. This parameter + can be a value of @ref ADC_external_trigger_sources_for_regular_channels_conversion */ + uint32_t ADC_ExternalTrigEventEdge; /*!< Select the external trigger edge and enable the trigger of a regular group. + This parameter can be a value of + @ref ADC_external_trigger_edge_for_regular_channels_conversion */ + uint32_t ADC_DataAlign; /*!< Specifies whether the ADC data alignment is left or right. + This parameter can be a value of @ref ADC_data_align */ + uint32_t ADC_OverrunMode; /*!< Specifies the way data overrun are managed. + This parameter can be set to ENABLE or DISABLE. */ + uint32_t ADC_AutoInjMode; /*!< Enable/disable automatic injected group conversion after + regular group conversion. + This parameter can be set to ENABLE or DISABLE. */ + uint8_t ADC_NbrOfRegChannel; /*!< Specifies the number of ADC channels that will be converted + using the sequencer for regular channel group. + This parameter must range from 1 to 16. */ +}ADC_InitTypeDef; + +/** + * @} + */ +/** + * @brief ADC Init structure definition + */ +typedef struct +{ + + uint32_t ADC_ExternalTrigInjecConvEvent; /*!< Defines the external trigger used to start the analog + to digital conversion of injected channels. This parameter + can be a value of @ref ADC_external_trigger_sources_for_Injected_channels_conversion */ + uint32_t ADC_ExternalTrigInjecEventEdge; /*!< Select the external trigger edge and enable the trigger of an injected group. + This parameter can be a value of + @ref ADC_external_trigger_edge_for_Injected_channels_conversion */ + uint8_t ADC_NbrOfInjecChannel; /*!< Specifies the number of ADC channels that will be converted + using the sequencer for injected channel group. + This parameter must range from 1 to 4. */ + uint32_t ADC_InjecSequence1; + uint32_t ADC_InjecSequence2; + uint32_t ADC_InjecSequence3; + uint32_t ADC_InjecSequence4; +}ADC_InjectedInitTypeDef; + +/** + * @} + */ +typedef struct +{ + uint32_t ADC_Mode; /*!< Configures the ADC to operate in + independent or multi mode. + This parameter can be a value of @ref ADC_mode */ + uint32_t ADC_Clock; /*!< Select the clock of the ADC. The clock is common for both master + and slave ADCs. + This parameter can be a value of @ref ADC_Clock */ + uint32_t ADC_DMAAccessMode; /*!< Configures the Direct memory access mode for multi ADC mode. + This parameter can be a value of + @ref ADC_Direct_memory_access_mode_for_multi_mode */ + uint32_t ADC_DMAMode; /*!< Configures the DMA mode for ADC. + This parameter can be a value of @ref ADC_DMA_Mode_definition */ + uint8_t ADC_TwoSamplingDelay; /*!< Configures the Delay between 2 sampling phases. + This parameter can be a value between 0x0 and 0xF */ + +}ADC_CommonInitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup ADC_Exported_Constants + * @{ + */ + +#define IS_ADC_ALL_PERIPH(PERIPH) (((PERIPH) == ADC1) || \ + ((PERIPH) == ADC2) || \ + ((PERIPH) == ADC3) || \ + ((PERIPH) == ADC4)) + +#define IS_ADC_DMA_PERIPH(PERIPH) (((PERIPH) == ADC1) || \ + ((PERIPH) == ADC2) || \ + ((PERIPH) == ADC3) || \ + ((PERIPH) == ADC4)) + +/** @defgroup ADC_ContinuousConvMode + * @{ + */ +#define ADC_ContinuousConvMode_Enable ((uint32_t)0x00002000) /*!< ADC continuous conversion mode enable */ +#define ADC_ContinuousConvMode_Disable ((uint32_t)0x00000000) /*!< ADC continuous conversion mode disable */ +#define IS_ADC_CONVMODE(MODE) (((MODE) == ADC_ContinuousConvMode_Enable) || \ + ((MODE) == ADC_ContinuousConvMode_Disable)) +/** + * @} + */ +/** @defgroup ADC_OverunMode + * @{ + */ +#define ADC_OverrunMode_Enable ((uint32_t)0x00001000) /*!< ADC Overrun Mode enable */ +#define ADC_OverrunMode_Disable ((uint32_t)0x00000000) /*!< ADC Overrun Mode disable */ +#define IS_ADC_OVRUNMODE(MODE) (((MODE) == ADC_OverrunMode_Enable) || \ + ((MODE) == ADC_OverrunMode_Disable)) +/** + * @} + */ +/** @defgroup ADC_AutoInjecMode + * @{ + */ +#define ADC_AutoInjec_Enable ((uint32_t)0x02000000) /*!< ADC Auto injected Mode enable */ +#define ADC_AutoInjec_Disable ((uint32_t)0x00000000) /*!< ADC Auto injected Mode disable */ +#define IS_ADC_AUTOINJECMODE(MODE) (((MODE) == ADC_AutoInjec_Enable) || \ + ((MODE) == ADC_AutoInjec_Disable)) +/** + * @} + */ +/** @defgroup ADC_resolution + * @{ + */ +#define ADC_Resolution_12b ((uint32_t)0x00000000) /*!< ADC 12-bit resolution */ +#define ADC_Resolution_10b ((uint32_t)0x00000008) /*!< ADC 10-bit resolution */ +#define ADC_Resolution_8b ((uint32_t)0x00000010) /*!< ADC 8-bit resolution */ +#define ADC_Resolution_6b ((uint32_t)0x00000018) /*!< ADC 6-bit resolution */ +#define IS_ADC_RESOLUTION(RESOLUTION) (((RESOLUTION) == ADC_Resolution_12b) || \ + ((RESOLUTION) == ADC_Resolution_10b) || \ + ((RESOLUTION) == ADC_Resolution_8b) || \ + ((RESOLUTION) == ADC_Resolution_6b)) + +/** + * @} + */ + + +/** @defgroup ADC_external_trigger_edge_for_regular_channels_conversion + * @{ + */ +#define ADC_ExternalTrigEventEdge_None ((uint16_t)0x0000) /*!< ADC No external trigger for regular conversion */ +#define ADC_ExternalTrigEventEdge_RisingEdge ((uint16_t)0x0400) /*!< ADC external trigger rising edge for regular conversion */ +#define ADC_ExternalTrigEventEdge_FallingEdge ((uint16_t)0x0800) /*!< ADC ADC external trigger falling edge for regular conversion */ +#define ADC_ExternalTrigEventEdge_BothEdge ((uint16_t)0x0C00) /*!< ADC ADC external trigger both edges for regular conversion */ + +#define IS_EXTERNALTRIG_EDGE(EDGE) (((EDGE) == ADC_ExternalTrigEventEdge_None) || \ + ((EDGE) == ADC_ExternalTrigEventEdge_RisingEdge) || \ + ((EDGE) == ADC_ExternalTrigEventEdge_FallingEdge) || \ + ((EDGE) == ADC_ExternalTrigEventEdge_BothEdge)) + +/** + * @} + */ + +/** @defgroup ADC_external_trigger_edge_for_Injected_channels_conversion + * @{ + */ +#define ADC_ExternalTrigInjecEventEdge_None ((uint16_t)0x0000) /*!< ADC No external trigger for regular conversion */ +#define ADC_ExternalTrigInjecEventEdge_RisingEdge ((uint16_t)0x0040) /*!< ADC external trigger rising edge for injected conversion */ +#define ADC_ExternalTrigInjecEventEdge_FallingEdge ((uint16_t)0x0080) /*!< ADC external trigger falling edge for injected conversion */ +#define ADC_ExternalTrigInjecEventEdge_BothEdge ((uint16_t)0x00C0) /*!< ADC external trigger both edges for injected conversion */ + +#define IS_EXTERNALTRIGINJ_EDGE(EDGE) (((EDGE) == ADC_ExternalTrigInjecEventEdge_None) || \ + ((EDGE) == ADC_ExternalTrigInjecEventEdge_RisingEdge) || \ + ((EDGE) == ADC_ExternalTrigInjecEventEdge_FallingEdge) || \ + ((EDGE) == ADC_ExternalTrigInjecEventEdge_BothEdge)) + +/** @defgroup ADC_external_trigger_sources_for_regular_channels_conversion + * @{ + */ +#define ADC_ExternalTrigConvEvent_0 ((uint16_t)0x0000) /*!< ADC external trigger event 0 */ +#define ADC_ExternalTrigConvEvent_1 ((uint16_t)0x0040) /*!< ADC external trigger event 1 */ +#define ADC_ExternalTrigConvEvent_2 ((uint16_t)0x0080) /*!< ADC external trigger event 2 */ +#define ADC_ExternalTrigConvEvent_3 ((uint16_t)0x00C0) /*!< ADC external trigger event 3 */ +#define ADC_ExternalTrigConvEvent_4 ((uint16_t)0x0100) /*!< ADC external trigger event 4 */ +#define ADC_ExternalTrigConvEvent_5 ((uint16_t)0x0140) /*!< ADC external trigger event 5 */ +#define ADC_ExternalTrigConvEvent_6 ((uint16_t)0x0180) /*!< ADC external trigger event 6 */ +#define ADC_ExternalTrigConvEvent_7 ((uint16_t)0x01C0) /*!< ADC external trigger event 7 */ +#define ADC_ExternalTrigConvEvent_8 ((uint16_t)0x0200) /*!< ADC external trigger event 8 */ +#define ADC_ExternalTrigConvEvent_9 ((uint16_t)0x0240) /*!< ADC external trigger event 9 */ +#define ADC_ExternalTrigConvEvent_10 ((uint16_t)0x0280) /*!< ADC external trigger event 10 */ +#define ADC_ExternalTrigConvEvent_11 ((uint16_t)0x02C0) /*!< ADC external trigger event 11 */ +#define ADC_ExternalTrigConvEvent_12 ((uint16_t)0x0300) /*!< ADC external trigger event 12 */ +#define ADC_ExternalTrigConvEvent_13 ((uint16_t)0x0340) /*!< ADC external trigger event 13 */ +#define ADC_ExternalTrigConvEvent_14 ((uint16_t)0x0380) /*!< ADC external trigger event 14 */ +#define ADC_ExternalTrigConvEvent_15 ((uint16_t)0x03C0) /*!< ADC external trigger event 15 */ + +#define IS_ADC_EXT_TRIG(REGTRIG) (((REGTRIG) == ADC_ExternalTrigConvEvent_0) || \ + ((REGTRIG) == ADC_ExternalTrigConvEvent_1) || \ + ((REGTRIG) == ADC_ExternalTrigConvEvent_2) || \ + ((REGTRIG) == ADC_ExternalTrigConvEvent_3) || \ + ((REGTRIG) == ADC_ExternalTrigConvEvent_4) || \ + ((REGTRIG) == ADC_ExternalTrigConvEvent_5) || \ + ((REGTRIG) == ADC_ExternalTrigConvEvent_6) || \ + ((REGTRIG) == ADC_ExternalTrigConvEvent_7) || \ + ((REGTRIG) == ADC_ExternalTrigConvEvent_8) || \ + ((REGTRIG) == ADC_ExternalTrigConvEvent_9) || \ + ((REGTRIG) == ADC_ExternalTrigConvEvent_10) || \ + ((REGTRIG) == ADC_ExternalTrigConvEvent_11) || \ + ((REGTRIG) == ADC_ExternalTrigConvEvent_12) || \ + ((REGTRIG) == ADC_ExternalTrigConvEvent_13) || \ + ((REGTRIG) == ADC_ExternalTrigConvEvent_14) || \ + ((REGTRIG) == ADC_ExternalTrigConvEvent_15)) + +/** + * @} + */ + +/** @defgroup ADC_external_trigger_sources_for_Injected_channels_conversion + * @{ + */ + +#define ADC_ExternalTrigInjecConvEvent_0 ((uint16_t)0x0000) /*!< ADC external trigger for injected conversion event 0 */ +#define ADC_ExternalTrigInjecConvEvent_1 ((uint16_t)0x0004) /*!< ADC external trigger for injected conversion event 1 */ +#define ADC_ExternalTrigInjecConvEvent_2 ((uint16_t)0x0008) /*!< ADC external trigger for injected conversion event 2 */ +#define ADC_ExternalTrigInjecConvEvent_3 ((uint16_t)0x000C) /*!< ADC external trigger for injected conversion event 3 */ +#define ADC_ExternalTrigInjecConvEvent_4 ((uint16_t)0x0010) /*!< ADC external trigger for injected conversion event 4 */ +#define ADC_ExternalTrigInjecConvEvent_5 ((uint16_t)0x0014) /*!< ADC external trigger for injected conversion event 5 */ +#define ADC_ExternalTrigInjecConvEvent_6 ((uint16_t)0x0018) /*!< ADC external trigger for injected conversion event 6 */ +#define ADC_ExternalTrigInjecConvEvent_7 ((uint16_t)0x001C) /*!< ADC external trigger for injected conversion event 7 */ +#define ADC_ExternalTrigInjecConvEvent_8 ((uint16_t)0x0020) /*!< ADC external trigger for injected conversion event 8 */ +#define ADC_ExternalTrigInjecConvEvent_9 ((uint16_t)0x0024) /*!< ADC external trigger for injected conversion event 9 */ +#define ADC_ExternalTrigInjecConvEvent_10 ((uint16_t)0x0028) /*!< ADC external trigger for injected conversion event 10 */ +#define ADC_ExternalTrigInjecConvEvent_11 ((uint16_t)0x002C) /*!< ADC external trigger for injected conversion event 11 */ +#define ADC_ExternalTrigInjecConvEvent_12 ((uint16_t)0x0030) /*!< ADC external trigger for injected conversion event 12 */ +#define ADC_ExternalTrigInjecConvEvent_13 ((uint16_t)0x0034) /*!< ADC external trigger for injected conversion event 13 */ +#define ADC_ExternalTrigInjecConvEvent_14 ((uint16_t)0x0038) /*!< ADC external trigger for injected conversion event 14 */ +#define ADC_ExternalTrigInjecConvEvent_15 ((uint16_t)0x003C) /*!< ADC external trigger for injected conversion event 15 */ + +#define IS_ADC_EXT_INJEC_TRIG(INJTRIG) (((INJTRIG) == ADC_ExternalTrigInjecConvEvent_0) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConvEvent_1) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConvEvent_2) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConvEvent_3) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConvEvent_4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConvEvent_5) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConvEvent_6) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConvEvent_7) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConvEvent_8) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConvEvent_9) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConvEvent_10) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConvEvent_11) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConvEvent_12) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConvEvent_13) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConvEvent_14) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConvEvent_15)) +/** + * @} + */ +/** @defgroup ADC_data_align + * @{ + */ + +#define ADC_DataAlign_Right ((uint32_t)0x00000000) /*!< ADC Data alignment right */ +#define ADC_DataAlign_Left ((uint32_t)0x00000020) /*!< ADC Data alignment left */ +#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DataAlign_Right) || \ + ((ALIGN) == ADC_DataAlign_Left)) +/** + * @} + */ + +/** @defgroup ADC_channels + * @{ + */ + +#define ADC_Channel_1 ((uint8_t)0x01) /*!< ADC Channel 1 */ +#define ADC_Channel_2 ((uint8_t)0x02) /*!< ADC Channel 2 */ +#define ADC_Channel_3 ((uint8_t)0x03) /*!< ADC Channel 3 */ +#define ADC_Channel_4 ((uint8_t)0x04) /*!< ADC Channel 4 */ +#define ADC_Channel_5 ((uint8_t)0x05) /*!< ADC Channel 5 */ +#define ADC_Channel_6 ((uint8_t)0x06) /*!< ADC Channel 6 */ +#define ADC_Channel_7 ((uint8_t)0x07) /*!< ADC Channel 7 */ +#define ADC_Channel_8 ((uint8_t)0x08) /*!< ADC Channel 8 */ +#define ADC_Channel_9 ((uint8_t)0x09) /*!< ADC Channel 9 */ +#define ADC_Channel_10 ((uint8_t)0x0A) /*!< ADC Channel 10 */ +#define ADC_Channel_11 ((uint8_t)0x0B) /*!< ADC Channel 11 */ +#define ADC_Channel_12 ((uint8_t)0x0C) /*!< ADC Channel 12 */ +#define ADC_Channel_13 ((uint8_t)0x0D) /*!< ADC Channel 13 */ +#define ADC_Channel_14 ((uint8_t)0x0E) /*!< ADC Channel 14 */ +#define ADC_Channel_15 ((uint8_t)0x0F) /*!< ADC Channel 15 */ +#define ADC_Channel_16 ((uint8_t)0x10) /*!< ADC Channel 16 */ +#define ADC_Channel_17 ((uint8_t)0x11) /*!< ADC Channel 17 */ +#define ADC_Channel_18 ((uint8_t)0x12) /*!< ADC Channel 18 */ + +#define ADC_Channel_TempSensor ((uint8_t)ADC_Channel_16) +#define ADC_Channel_Vrefint ((uint8_t)ADC_Channel_18) +#define ADC_Channel_Vbat ((uint8_t)ADC_Channel_17) + +#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) == ADC_Channel_1) || \ + ((CHANNEL) == ADC_Channel_2) || \ + ((CHANNEL) == ADC_Channel_3) || \ + ((CHANNEL) == ADC_Channel_4) || \ + ((CHANNEL) == ADC_Channel_5) || \ + ((CHANNEL) == ADC_Channel_6) || \ + ((CHANNEL) == ADC_Channel_7) || \ + ((CHANNEL) == ADC_Channel_8) || \ + ((CHANNEL) == ADC_Channel_9) || \ + ((CHANNEL) == ADC_Channel_10) || \ + ((CHANNEL) == ADC_Channel_11) || \ + ((CHANNEL) == ADC_Channel_12) || \ + ((CHANNEL) == ADC_Channel_13) || \ + ((CHANNEL) == ADC_Channel_14) || \ + ((CHANNEL) == ADC_Channel_15) || \ + ((CHANNEL) == ADC_Channel_16) || \ + ((CHANNEL) == ADC_Channel_17) || \ + ((CHANNEL) == ADC_Channel_18)) +#define IS_ADC_DIFFCHANNEL(CHANNEL) (((CHANNEL) == ADC_Channel_1) || \ + ((CHANNEL) == ADC_Channel_2) || \ + ((CHANNEL) == ADC_Channel_3) || \ + ((CHANNEL) == ADC_Channel_4) || \ + ((CHANNEL) == ADC_Channel_5) || \ + ((CHANNEL) == ADC_Channel_6) || \ + ((CHANNEL) == ADC_Channel_7) || \ + ((CHANNEL) == ADC_Channel_8) || \ + ((CHANNEL) == ADC_Channel_9) || \ + ((CHANNEL) == ADC_Channel_10) || \ + ((CHANNEL) == ADC_Channel_11) || \ + ((CHANNEL) == ADC_Channel_12) || \ + ((CHANNEL) == ADC_Channel_13) || \ + ((CHANNEL) == ADC_Channel_14)) +/** + * @} + */ + +/** @defgroup ADC_mode + * @{ + */ +#define ADC_Mode_Independent ((uint32_t)0x00000000) /*!< ADC independent mode */ +#define ADC_Mode_CombRegSimulInjSimul ((uint32_t)0x00000001) /*!< ADC multi ADC mode: Combined Regular simultaneous injected simultaneous mode */ +#define ADC_Mode_CombRegSimulAltTrig ((uint32_t)0x00000002) /*!< ADC multi ADC mode: Combined Regular simultaneous Alternate trigger mode */ +#define ADC_Mode_InjSimul ((uint32_t)0x00000005) /*!< ADC multi ADC mode: Injected simultaneous mode */ +#define ADC_Mode_RegSimul ((uint32_t)0x00000006) /*!< ADC multi ADC mode: Regular simultaneous mode */ +#define ADC_Mode_Interleave ((uint32_t)0x00000007) /*!< ADC multi ADC mode: Interleave mode */ +#define ADC_Mode_AltTrig ((uint32_t)0x00000009) /*!< ADC multi ADC mode: Alternate Trigger mode */ + +#define IS_ADC_MODE(MODE) (((MODE) == ADC_Mode_Independent) || \ + ((MODE) == ADC_Mode_CombRegSimulInjSimul) || \ + ((MODE) == ADC_Mode_CombRegSimulAltTrig) || \ + ((MODE) == ADC_Mode_InjSimul) || \ + ((MODE) == ADC_Mode_RegSimul) || \ + ((MODE) == ADC_Mode_Interleave) || \ + ((MODE) == ADC_Mode_AltTrig)) + +/** + * @} + */ + +/** @defgroup ADC_Clock + * @{ + */ +#define ADC_Clock_AsynClkMode ((uint32_t)0x00000000) /*!< ADC Asynchronous clock mode */ +#define ADC_Clock_SynClkModeDiv1 ((uint32_t)0x00010000) /*!< Synchronous clock mode divided by 1 */ +#define ADC_Clock_SynClkModeDiv2 ((uint32_t)0x00020000) /*!< Synchronous clock mode divided by 2 */ +#define ADC_Clock_SynClkModeDiv4 ((uint32_t)0x00030000) /*!< Synchronous clock mode divided by 4 */ +#define IS_ADC_CLOCKMODE(CLOCK) (((CLOCK) == ADC_Clock_AsynClkMode) ||\ + ((CLOCK) == ADC_Clock_SynClkModeDiv1) ||\ + ((CLOCK) == ADC_Clock_SynClkModeDiv2)||\ + ((CLOCK) == ADC_Clock_SynClkModeDiv4)) +/** + * @} + */ +/** @defgroup ADC_Direct_memory_access_mode_for_multi_mode + * @{ + */ +#define ADC_DMAAccessMode_Disabled ((uint32_t)0x00000000) /*!< DMA mode disabled */ +#define ADC_DMAAccessMode_1 ((uint32_t)0x00008000) /*!< DMA mode enabled for 12 and 10-bit resolution (6 bit) */ +#define ADC_DMAAccessMode_2 ((uint32_t)0x0000C000) /*!< DMA mode enabled for 8 and 6-bit resolution (8bit) */ +#define IS_ADC_DMA_ACCESS_MODE(MODE) (((MODE) == ADC_DMAAccessMode_Disabled) || \ + ((MODE) == ADC_DMAAccessMode_1) || \ + ((MODE) == ADC_DMAAccessMode_2)) + +/** + * @} + */ +/** @defgroup ADC_sampling_time + * @{ + */ + +#define ADC_SampleTime_1Cycles5 ((uint8_t)0x00) /*!< ADC sampling time 1.5 cycle */ +#define ADC_SampleTime_2Cycles5 ((uint8_t)0x01) /*!< ADC sampling time 2.5 cycles */ +#define ADC_SampleTime_4Cycles5 ((uint8_t)0x02) /*!< ADC sampling time 4.5 cycles */ +#define ADC_SampleTime_7Cycles5 ((uint8_t)0x03) /*!< ADC sampling time 7.5 cycles */ +#define ADC_SampleTime_19Cycles5 ((uint8_t)0x04) /*!< ADC sampling time 19.5 cycles */ +#define ADC_SampleTime_61Cycles5 ((uint8_t)0x05) /*!< ADC sampling time 61.5 cycles */ +#define ADC_SampleTime_181Cycles5 ((uint8_t)0x06) /*!< ADC sampling time 181.5 cycles */ +#define ADC_SampleTime_601Cycles5 ((uint8_t)0x07) /*!< ADC sampling time 601.5 cycles */ +#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SampleTime_1Cycles5) || \ + ((TIME) == ADC_SampleTime_2Cycles5) || \ + ((TIME) == ADC_SampleTime_4Cycles5) || \ + ((TIME) == ADC_SampleTime_7Cycles5) || \ + ((TIME) == ADC_SampleTime_19Cycles5) || \ + ((TIME) == ADC_SampleTime_61Cycles5) || \ + ((TIME) == ADC_SampleTime_181Cycles5) || \ + ((TIME) == ADC_SampleTime_601Cycles5)) +/** + * @} + */ + +/** @defgroup ADC_injected_Channel_selection + * @{ + */ + +#define ADC_InjectedChannel_1 ADC_Channel_1 /*!< ADC Injected channel 1 */ +#define ADC_InjectedChannel_2 ADC_Channel_2 /*!< ADC Injected channel 2 */ +#define ADC_InjectedChannel_3 ADC_Channel_3 /*!< ADC Injected channel 3 */ +#define ADC_InjectedChannel_4 ADC_Channel_4 /*!< ADC Injected channel 4 */ +#define ADC_InjectedChannel_5 ADC_Channel_5 /*!< ADC Injected channel 5 */ +#define ADC_InjectedChannel_6 ADC_Channel_6 /*!< ADC Injected channel 6 */ +#define ADC_InjectedChannel_7 ADC_Channel_7 /*!< ADC Injected channel 7 */ +#define ADC_InjectedChannel_8 ADC_Channel_8 /*!< ADC Injected channel 8 */ +#define ADC_InjectedChannel_9 ADC_Channel_9 /*!< ADC Injected channel 9 */ +#define ADC_InjectedChannel_10 ADC_Channel_10 /*!< ADC Injected channel 10 */ +#define ADC_InjectedChannel_11 ADC_Channel_11 /*!< ADC Injected channel 11 */ +#define ADC_InjectedChannel_12 ADC_Channel_12 /*!< ADC Injected channel 12 */ +#define ADC_InjectedChannel_13 ADC_Channel_13 /*!< ADC Injected channel 13 */ +#define ADC_InjectedChannel_14 ADC_Channel_14 /*!< ADC Injected channel 14 */ +#define ADC_InjectedChannel_15 ADC_Channel_15 /*!< ADC Injected channel 15 */ +#define ADC_InjectedChannel_16 ADC_Channel_16 /*!< ADC Injected channel 16 */ +#define ADC_InjectedChannel_17 ADC_Channel_17 /*!< ADC Injected channel 17 */ +#define ADC_InjectedChannel_18 ADC_Channel_18 /*!< ADC Injected channel 18 */ + +#define IS_ADC_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) == ADC_InjectedChannel_1) || \ + ((CHANNEL) == ADC_InjectedChannel_2) || \ + ((CHANNEL) == ADC_InjectedChannel_3) || \ + ((CHANNEL) == ADC_InjectedChannel_4) ||\ + ((CHANNEL) == ADC_InjectedChannel_5) ||\ + ((CHANNEL) == ADC_InjectedChannel_6) ||\ + ((CHANNEL) == ADC_InjectedChannel_7) ||\ + ((CHANNEL) == ADC_InjectedChannel_8) ||\ + ((CHANNEL) == ADC_InjectedChannel_9) ||\ + ((CHANNEL) == ADC_InjectedChannel_10) ||\ + ((CHANNEL) == ADC_InjectedChannel_11) ||\ + ((CHANNEL) == ADC_InjectedChannel_12) ||\ + ((CHANNEL) == ADC_InjectedChannel_13) ||\ + ((CHANNEL) == ADC_InjectedChannel_14) ||\ + ((CHANNEL) == ADC_InjectedChannel_15) ||\ + ((CHANNEL) == ADC_InjectedChannel_16) ||\ + ((CHANNEL) == ADC_InjectedChannel_17) ||\ + ((CHANNEL) == ADC_InjectedChannel_18)) +/** + * @} + */ + +/** @defgroup ADC_injected_Sequence_selection + * @{ + */ + +#define ADC_InjectedSequence_1 ADC_Channel_1 /*!< ADC Injected sequence 1 */ +#define ADC_InjectedSequence_2 ADC_Channel_2 /*!< ADC Injected sequence 2 */ +#define ADC_InjectedSequence_3 ADC_Channel_3 /*!< ADC Injected sequence 3 */ +#define ADC_InjectedSequence_4 ADC_Channel_4 /*!< ADC Injected sequence 4 */ +#define IS_ADC_INJECTED_SEQUENCE(SEQUENCE) (((SEQUENCE) == ADC_InjectedSequence_1) || \ + ((SEQUENCE) == ADC_InjectedSequence_2) || \ + ((SEQUENCE) == ADC_InjectedSequence_3) || \ + ((SEQUENCE) == ADC_InjectedSequence_4)) +/** + * @} + */ + +/** @defgroup ADC_analog_watchdog_selection + * @{ + */ + +#define ADC_AnalogWatchdog_SingleRegEnable ((uint32_t)0x00C00000) /*!< ADC Analog watchdog single regular mode */ +#define ADC_AnalogWatchdog_SingleInjecEnable ((uint32_t)0x01400000) /*!< ADC Analog watchdog single injected mode */ +#define ADC_AnalogWatchdog_SingleRegOrInjecEnable ((uint32_t)0x01C00000) /*!< ADC Analog watchdog single regular or injected mode */ +#define ADC_AnalogWatchdog_AllRegEnable ((uint32_t)0x00800000) /*!< ADC Analog watchdog all regular mode */ +#define ADC_AnalogWatchdog_AllInjecEnable ((uint32_t)0x01000000) /*!< ADC Analog watchdog all injected mode */ +#define ADC_AnalogWatchdog_AllRegAllInjecEnable ((uint32_t)0x01800000) /*!< ADC Analog watchdog all regular and all injected mode */ +#define ADC_AnalogWatchdog_None ((uint32_t)0x00000000) /*!< ADC Analog watchdog off */ + +#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_AnalogWatchdog_SingleRegEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_SingleInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_SingleRegOrInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_AllRegEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_AllInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_AllRegAllInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_None)) +/** + * @} + */ + +/** @defgroup ADC_Calibration_Mode_definition + * @{ + */ +#define ADC_CalibrationMode_Single ((uint32_t)0x00000000) /*!< ADC Calibration for single ended channel */ +#define ADC_CalibrationMode_Differential ((uint32_t)0x40000000) /*!< ADC Calibration for differential channel */ + +#define IS_ADC_CALIBRATION_MODE(MODE) (((MODE) == ADC_CalibrationMode_Single) ||((MODE) == ADC_CalibrationMode_Differential)) + +/** + * @} + */ + +/** @defgroup ADC_DMA_Mode_definition + * @{ + */ +#define ADC_DMAMode_OneShot ((uint32_t)0x00000000) /*!< ADC DMA Oneshot mode */ +#define ADC_DMAMode_Circular ((uint32_t)0x00000002) /*!< ADC DMA circular mode */ + +#define IS_ADC_DMA_MODE(MODE) (((MODE) == ADC_DMAMode_OneShot) || ((MODE) == ADC_DMAMode_Circular)) +/** + * @} + */ + +/** @defgroup ADC_interrupts_definition + * @{ + */ + +#define ADC_IT_RDY ((uint16_t)0x0001) /*!< ADC Ready (ADRDY) interrupt source */ +#define ADC_IT_EOSMP ((uint16_t)0x0002) /*!< ADC End of Sampling interrupt source */ +#define ADC_IT_EOC ((uint16_t)0x0004) /*!< ADC End of Regular Conversion interrupt source */ +#define ADC_IT_EOS ((uint16_t)0x0008) /*!< ADC End of Regular sequence of Conversions interrupt source */ +#define ADC_IT_OVR ((uint16_t)0x0010) /*!< ADC overrun interrupt source */ +#define ADC_IT_JEOC ((uint16_t)0x0020) /*!< ADC End of Injected Conversion interrupt source */ +#define ADC_IT_JEOS ((uint16_t)0x0040) /*!< ADC End of Injected sequence of Conversions interrupt source */ +#define ADC_IT_AWD1 ((uint16_t)0x0080) /*!< ADC Analog watchdog 1 interrupt source */ +#define ADC_IT_AWD2 ((uint16_t)0x0100) /*!< ADC Analog watchdog 2 interrupt source */ +#define ADC_IT_AWD3 ((uint16_t)0x0200) /*!< ADC Analog watchdog 3 interrupt source */ +#define ADC_IT_JQOVF ((uint16_t)0x0400) /*!< ADC Injected Context Queue Overflow interrupt source */ + + +#define IS_ADC_IT(IT) ((((IT) & (uint16_t)0xF800) == 0x0000) && ((IT) != 0x0000)) + +#define IS_ADC_GET_IT(IT) (((IT) == ADC_IT_RDY) || ((IT) == ADC_IT_EOSMP) || \ + ((IT) == ADC_IT_EOC) || ((IT) == ADC_IT_EOS) || \ + ((IT) == ADC_IT_OVR) || ((IT) == ADC_IT_EOS) || \ + ((IT) == ADC_IT_JEOS) || ((IT) == ADC_IT_AWD1) || \ + ((IT) == ADC_IT_AWD2) || ((IT) == ADC_IT_AWD3) || \ + ((IT) == ADC_IT_JQOVF)) +/** + * @} + */ + +/** @defgroup ADC_flags_definition + * @{ + */ + +#define ADC_FLAG_RDY ((uint16_t)0x0001) /*!< ADC Ready (ADRDY) flag */ +#define ADC_FLAG_EOSMP ((uint16_t)0x0002) /*!< ADC End of Sampling flag */ +#define ADC_FLAG_EOC ((uint16_t)0x0004) /*!< ADC End of Regular Conversion flag */ +#define ADC_FLAG_EOS ((uint16_t)0x0008) /*!< ADC End of Regular sequence of Conversions flag */ +#define ADC_FLAG_OVR ((uint16_t)0x0010) /*!< ADC overrun flag */ +#define ADC_FLAG_JEOC ((uint16_t)0x0020) /*!< ADC End of Injected Conversion flag */ +#define ADC_FLAG_JEOS ((uint16_t)0x0040) /*!< ADC End of Injected sequence of Conversions flag */ +#define ADC_FLAG_AWD1 ((uint16_t)0x0080) /*!< ADC Analog watchdog 1 flag */ +#define ADC_FLAG_AWD2 ((uint16_t)0x0100) /*!< ADC Analog watchdog 2 flag */ +#define ADC_FLAG_AWD3 ((uint16_t)0x0200) /*!< ADC Analog watchdog 3 flag */ +#define ADC_FLAG_JQOVF ((uint16_t)0x0400) /*!< ADC Injected Context Queue Overflow flag */ + +#define IS_ADC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xF800) == 0x0000) && ((FLAG) != 0x0000)) +#define IS_ADC_GET_FLAG(FLAG) (((FLAG) == ADC_FLAG_RDY) || ((FLAG) == ADC_FLAG_EOSMP) || \ + ((FLAG) == ADC_FLAG_EOC) || ((FLAG) == ADC_FLAG_EOS) || \ + ((FLAG) == ADC_FLAG_OVR) || ((FLAG) == ADC_FLAG_JEOC) || \ + ((FLAG) == ADC_FLAG_JEOS) || ((FLAG) == ADC_FLAG_AWD1) || \ + ((FLAG) == ADC_FLAG_AWD2) || ((FLAG) == ADC_FLAG_AWD3) || \ + ((FLAG) == ADC_FLAG_JQOVF)) +/** + * @} + */ + +/** @defgroup ADC_Common_flags_definition + * @{ + */ + +#define ADC_FLAG_MSTRDY ((uint32_t)0x00000001) /*!< ADC Master Ready (ADRDY) flag */ +#define ADC_FLAG_MSTEOSMP ((uint32_t)0x00000002) /*!< ADC Master End of Sampling flag */ +#define ADC_FLAG_MSTEOC ((uint32_t)0x00000004) /*!< ADC Master End of Regular Conversion flag */ +#define ADC_FLAG_MSTEOS ((uint32_t)0x00000008) /*!< ADC Master End of Regular sequence of Conversions flag */ +#define ADC_FLAG_MSTOVR ((uint32_t)0x00000010) /*!< ADC Master overrun flag */ +#define ADC_FLAG_MSTJEOC ((uint32_t)0x00000020) /*!< ADC Master End of Injected Conversion flag */ +#define ADC_FLAG_MSTJEOS ((uint32_t)0x00000040) /*!< ADC Master End of Injected sequence of Conversions flag */ +#define ADC_FLAG_MSTAWD1 ((uint32_t)0x00000080) /*!< ADC Master Analog watchdog 1 flag */ +#define ADC_FLAG_MSTAWD2 ((uint32_t)0x00000100) /*!< ADC Master Analog watchdog 2 flag */ +#define ADC_FLAG_MSTAWD3 ((uint32_t)0x00000200) /*!< ADC Master Analog watchdog 3 flag */ +#define ADC_FLAG_MSTJQOVF ((uint32_t)0x00000400) /*!< ADC Master Injected Context Queue Overflow flag */ + +#define ADC_FLAG_SLVRDY ((uint32_t)0x00010000) /*!< ADC Slave Ready (ADRDY) flag */ +#define ADC_FLAG_SLVEOSMP ((uint32_t)0x00020000) /*!< ADC Slave End of Sampling flag */ +#define ADC_FLAG_SLVEOC ((uint32_t)0x00040000) /*!< ADC Slave End of Regular Conversion flag */ +#define ADC_FLAG_SLVEOS ((uint32_t)0x00080000) /*!< ADC Slave End of Regular sequence of Conversions flag */ +#define ADC_FLAG_SLVOVR ((uint32_t)0x00100000) /*!< ADC Slave overrun flag */ +#define ADC_FLAG_SLVJEOC ((uint32_t)0x00200000) /*!< ADC Slave End of Injected Conversion flag */ +#define ADC_FLAG_SLVJEOS ((uint32_t)0x00400000) /*!< ADC Slave End of Injected sequence of Conversions flag */ +#define ADC_FLAG_SLVAWD1 ((uint32_t)0x00800000) /*!< ADC Slave Analog watchdog 1 flag */ +#define ADC_FLAG_SLVAWD2 ((uint32_t)0x01000000) /*!< ADC Slave Analog watchdog 2 flag */ +#define ADC_FLAG_SLVAWD3 ((uint32_t)0x02000000) /*!< ADC Slave Analog watchdog 3 flag */ +#define ADC_FLAG_SLVJQOVF ((uint32_t)0x04000000) /*!< ADC Slave Injected Context Queue Overflow flag */ + +#define IS_ADC_CLEAR_COMMONFLAG(FLAG) ((((FLAG) & (uint32_t)0xF800F800) == 0x0000) && ((FLAG) != 0x00000000)) +#define IS_ADC_GET_COMMONFLAG(FLAG) (((FLAG) == ADC_FLAG_MSTRDY) || ((FLAG) == ADC_FLAG_MSTEOSMP) || \ + ((FLAG) == ADC_FLAG_MSTEOC) || ((FLAG) == ADC_FLAG_MSTEOS) || \ + ((FLAG) == ADC_FLAG_MSTOVR) || ((FLAG) == ADC_FLAG_MSTEOS) || \ + ((FLAG) == ADC_FLAG_MSTJEOS) || ((FLAG) == ADC_FLAG_MSTAWD1) || \ + ((FLAG) == ADC_FLAG_MSTAWD2) || ((FLAG) == ADC_FLAG_MSTAWD3) || \ + ((FLAG) == ADC_FLAG_MSTJQOVF) || \ + ((FLAG) == ADC_FLAG_SLVRDY) || ((FLAG) == ADC_FLAG_SLVEOSMP) || \ + ((FLAG) == ADC_FLAG_SLVEOC) || ((FLAG) == ADC_FLAG_SLVEOS) || \ + ((FLAG) == ADC_FLAG_SLVOVR) || ((FLAG) == ADC_FLAG_SLVEOS) || \ + ((FLAG) == ADC_FLAG_SLVJEOS) || ((FLAG) == ADC_FLAG_SLVAWD1) || \ + ((FLAG) == ADC_FLAG_SLVAWD2) || ((FLAG) == ADC_FLAG_SLVAWD3) || \ + ((FLAG) == ADC_FLAG_SLVJQOVF)) +/** + * @} + */ + +/** @defgroup ADC_thresholds + * @{ + */ + +#define IS_ADC_THRESHOLD(THRESHOLD) ((THRESHOLD) <= 0xFFF) + +/** + * @} + */ + +/** @defgroup ADC_injected_offset + * @{ + */ + +#define IS_ADC_OFFSET(OFFSET) ((OFFSET) <= 0xFFF) + +/** + * @} + */ + +/** @defgroup ADC_injected_length + * @{ + */ + +#define IS_ADC_INJECTED_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x4)) + +/** + * @} + */ + + +/** @defgroup ADC_regular_length + * @{ + */ + +#define IS_ADC_REGULAR_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x10)) +/** + * @} + */ + +/** @defgroup ADC_regular_discontinuous_mode_number + * @{ + */ + +#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER) (((NUMBER) >= 0x1) && ((NUMBER) <= 0x8)) + +/** + * @} + */ + +/** @defgroup ADC_two_sampling_delay_number + * @{ + */ +#define IS_ADC_TWOSAMPLING_DELAY(DELAY) (((DELAY) <= 0xF)) + +/** + * @} + */ +/** + * @} + */ + + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +/* Function used to set the ADC configuration to the default reset state *****/ +void ADC_DeInit(ADC_TypeDef* ADCx); + +/* Initialization and Configuration functions *********************************/ +void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct); +void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct); +void ADC_InjectedInit(ADC_TypeDef* ADCx, ADC_InjectedInitTypeDef* ADC_InjectedInitStruct); +void ADC_InjectedStructInit(ADC_InjectedInitTypeDef* ADC_InjectedInitStruct); +void ADC_CommonInit(ADC_TypeDef* ADCx, ADC_CommonInitTypeDef* ADC_CommonInitStruct); +void ADC_CommonStructInit(ADC_CommonInitTypeDef* ADC_CommonInitStruct); + +void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_StartCalibration(ADC_TypeDef* ADCx); +uint32_t ADC_GetCalibrationValue(ADC_TypeDef* ADCx); +void ADC_SetCalibrationValue(ADC_TypeDef* ADCx, uint32_t ADC_Calibration); +void ADC_SelectCalibrationMode(ADC_TypeDef* ADCx, uint32_t ADC_CalibrationMode); +FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx); +void ADC_DisableCmd(ADC_TypeDef* ADCx); +FlagStatus ADC_GetDisableCmdStatus(ADC_TypeDef* ADCx); +void ADC_VoltageRegulatorCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_SelectDifferentialMode(ADC_TypeDef* ADCx, uint8_t ADC_Channel, FunctionalState NewState); +void ADC_SelectQueueOfContextMode(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_AutoDelayCmd(ADC_TypeDef* ADCx, FunctionalState NewState); + +/* Analog Watchdog configuration functions ************************************/ +void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog); +void ADC_AnalogWatchdog1ThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold, uint16_t LowThreshold); +void ADC_AnalogWatchdog2ThresholdsConfig(ADC_TypeDef* ADCx, uint8_t HighThreshold, uint8_t LowThreshold); +void ADC_AnalogWatchdog3ThresholdsConfig(ADC_TypeDef* ADCx, uint8_t HighThreshold, uint8_t LowThreshold); +void ADC_AnalogWatchdog1SingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel); +void ADC_AnalogWatchdog2SingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel); +void ADC_AnalogWatchdog3SingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel); + +/* Temperature Sensor, Vrefint and Vbat management function */ +void ADC_TempSensorCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_VrefintCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_VbatCmd(ADC_TypeDef* ADCx, FunctionalState NewState); + +/* Channels Configuration functions ***********************************/ +void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime); +void ADC_RegularChannelSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t SequencerLength); +void ADC_ExternalTriggerConfig(ADC_TypeDef* ADCx, uint16_t ADC_ExternalTrigConvEvent, uint16_t ADC_ExternalTrigEventEdge); + +void ADC_StartConversion(ADC_TypeDef* ADCx); +FlagStatus ADC_GetStartConversionStatus(ADC_TypeDef* ADCx); +void ADC_StopConversion(ADC_TypeDef* ADCx); +void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number); +void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx); +uint32_t ADC_GetDualModeConversionValue(ADC_TypeDef* ADCx); + +void ADC_SetChannelOffset1(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint16_t Offset); +void ADC_SetChannelOffset2(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint16_t Offset); +void ADC_SetChannelOffset3(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint16_t Offset); +void ADC_SetChannelOffset4(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint16_t Offset); + +void ADC_ChannelOffset1Cmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_ChannelOffset2Cmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_ChannelOffset3Cmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_ChannelOffset4Cmd(ADC_TypeDef* ADCx, FunctionalState NewState); + +/* Regular Channels DMA Configuration functions *******************************/ +void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_DMAConfig(ADC_TypeDef* ADCx, uint32_t ADC_DMAMode); + +/* Injected channels Configuration functions **********************************/ +void ADC_InjectedChannelSampleTimeConfig(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint8_t ADC_SampleTime); +void ADC_StartInjectedConversion(ADC_TypeDef* ADCx); +FlagStatus ADC_GetStartInjectedConversionStatus(ADC_TypeDef* ADCx); +void ADC_StopInjectedConversion(ADC_TypeDef* ADCx); +void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel); + +/* ADC Dual Modes Configuration functions *************************************/ +FlagStatus ADC_GetCommonFlagStatus(ADC_TypeDef* ADCx, uint32_t ADC_FLAG); +void ADC_ClearCommonFlag(ADC_TypeDef* ADCx, uint32_t ADC_FLAG); + +/* Interrupts and flags management functions **********************************/ +void ADC_ITConfig(ADC_TypeDef* ADCx, uint32_t ADC_IT, FunctionalState NewState); +FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint32_t ADC_FLAG); +void ADC_ClearFlag(ADC_TypeDef* ADCx, uint32_t ADC_FLAG); +ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint32_t ADC_IT); +void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint32_t ADC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F30x_ADC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_can.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_can.h new file mode 100644 index 0000000..2303f9a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_can.h @@ -0,0 +1,643 @@ +/** + ****************************************************************************** + * @file stm32f30x_can.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the CAN firmware + * library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_CAN_H +#define __STM32F30x_CAN_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup CAN + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +#define IS_CAN_ALL_PERIPH(PERIPH) (((PERIPH) == CAN1)) + +/** + * @brief CAN init structure definition + */ +typedef struct +{ + uint16_t CAN_Prescaler; /*!< Specifies the length of a time quantum. + It ranges from 1 to 1024. */ + + uint8_t CAN_Mode; /*!< Specifies the CAN operating mode. + This parameter can be a value of @ref CAN_operating_mode */ + + uint8_t CAN_SJW; /*!< Specifies the maximum number of time quanta + the CAN hardware is allowed to lengthen or + shorten a bit to perform resynchronization. + This parameter can be a value of @ref CAN_synchronisation_jump_width */ + + uint8_t CAN_BS1; /*!< Specifies the number of time quanta in Bit + Segment 1. This parameter can be a value of + @ref CAN_time_quantum_in_bit_segment_1 */ + + uint8_t CAN_BS2; /*!< Specifies the number of time quanta in Bit Segment 2. + This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_2 */ + + FunctionalState CAN_TTCM; /*!< Enable or disable the time triggered communication mode. + This parameter can be set either to ENABLE or DISABLE. */ + + FunctionalState CAN_ABOM; /*!< Enable or disable the automatic bus-off management. + This parameter can be set either to ENABLE or DISABLE. */ + + FunctionalState CAN_AWUM; /*!< Enable or disable the automatic wake-up mode. + This parameter can be set either to ENABLE or DISABLE. */ + + FunctionalState CAN_NART; /*!< Enable or disable the non-automatic retransmission mode. + This parameter can be set either to ENABLE or DISABLE. */ + + FunctionalState CAN_RFLM; /*!< Enable or disable the Receive FIFO Locked mode. + This parameter can be set either to ENABLE or DISABLE. */ + + FunctionalState CAN_TXFP; /*!< Enable or disable the transmit FIFO priority. + This parameter can be set either to ENABLE or DISABLE. */ +} CAN_InitTypeDef; + +/** + * @brief CAN filter init structure definition + */ +typedef struct +{ + uint16_t CAN_FilterIdHigh; /*!< Specifies the filter identification number (MSBs for a 32-bit + configuration, first one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterIdLow; /*!< Specifies the filter identification number (LSBs for a 32-bit + configuration, second one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterMaskIdHigh; /*!< Specifies the filter mask number or identification number, + according to the mode (MSBs for a 32-bit configuration, + first one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterMaskIdLow; /*!< Specifies the filter mask number or identification number, + according to the mode (LSBs for a 32-bit configuration, + second one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterFIFOAssignment; /*!< Specifies the FIFO (0 or 1) which will be assigned to the filter. + This parameter can be a value of @ref CAN_filter_FIFO */ + + uint8_t CAN_FilterNumber; /*!< Specifies the filter which will be initialized. It ranges from 0 to 13. */ + + uint8_t CAN_FilterMode; /*!< Specifies the filter mode to be initialized. + This parameter can be a value of @ref CAN_filter_mode */ + + uint8_t CAN_FilterScale; /*!< Specifies the filter scale. + This parameter can be a value of @ref CAN_filter_scale */ + + FunctionalState CAN_FilterActivation; /*!< Enable or disable the filter. + This parameter can be set either to ENABLE or DISABLE. */ +} CAN_FilterInitTypeDef; + +/** + * @brief CAN Tx message structure definition + */ +typedef struct +{ + uint32_t StdId; /*!< Specifies the standard identifier. + This parameter can be a value between 0 to 0x7FF. */ + + uint32_t ExtId; /*!< Specifies the extended identifier. + This parameter can be a value between 0 to 0x1FFFFFFF. */ + + uint8_t IDE; /*!< Specifies the type of identifier for the message that + will be transmitted. This parameter can be a value + of @ref CAN_identifier_type */ + + uint8_t RTR; /*!< Specifies the type of frame for the message that will + be transmitted. This parameter can be a value of + @ref CAN_remote_transmission_request */ + + uint8_t DLC; /*!< Specifies the length of the frame that will be + transmitted. This parameter can be a value between + 0 to 8 */ + + uint8_t Data[8]; /*!< Contains the data to be transmitted. It ranges from 0 + to 0xFF. */ +} CanTxMsg; + +/** + * @brief CAN Rx message structure definition + */ +typedef struct +{ + uint32_t StdId; /*!< Specifies the standard identifier. + This parameter can be a value between 0 to 0x7FF. */ + + uint32_t ExtId; /*!< Specifies the extended identifier. + This parameter can be a value between 0 to 0x1FFFFFFF. */ + + uint8_t IDE; /*!< Specifies the type of identifier for the message that + will be received. This parameter can be a value of + @ref CAN_identifier_type */ + + uint8_t RTR; /*!< Specifies the type of frame for the received message. + This parameter can be a value of + @ref CAN_remote_transmission_request */ + + uint8_t DLC; /*!< Specifies the length of the frame that will be received. + This parameter can be a value between 0 to 8 */ + + uint8_t Data[8]; /*!< Contains the data to be received. It ranges from 0 to + 0xFF. */ + + uint8_t FMI; /*!< Specifies the index of the filter the message stored in + the mailbox passes through. This parameter can be a + value between 0 to 0xFF */ +} CanRxMsg; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup CAN_Exported_Constants + * @{ + */ + +/** @defgroup CAN_InitStatus + * @{ + */ + +#define CAN_InitStatus_Failed ((uint8_t)0x00) /*!< CAN initialization failed */ +#define CAN_InitStatus_Success ((uint8_t)0x01) /*!< CAN initialization OK */ + + +/* Legacy defines */ +#define CANINITFAILED CAN_InitStatus_Failed +#define CANINITOK CAN_InitStatus_Success +/** + * @} + */ + +/** @defgroup CAN_operating_mode + * @{ + */ + +#define CAN_Mode_Normal ((uint8_t)0x00) /*!< normal mode */ +#define CAN_Mode_LoopBack ((uint8_t)0x01) /*!< loopback mode */ +#define CAN_Mode_Silent ((uint8_t)0x02) /*!< silent mode */ +#define CAN_Mode_Silent_LoopBack ((uint8_t)0x03) /*!< loopback combined with silent mode */ + +#define IS_CAN_MODE(MODE) (((MODE) == CAN_Mode_Normal) || \ + ((MODE) == CAN_Mode_LoopBack)|| \ + ((MODE) == CAN_Mode_Silent) || \ + ((MODE) == CAN_Mode_Silent_LoopBack)) +/** + * @} + */ + + + /** + * @defgroup CAN_operating_mode + * @{ + */ +#define CAN_OperatingMode_Initialization ((uint8_t)0x00) /*!< Initialization mode */ +#define CAN_OperatingMode_Normal ((uint8_t)0x01) /*!< Normal mode */ +#define CAN_OperatingMode_Sleep ((uint8_t)0x02) /*!< sleep mode */ + + +#define IS_CAN_OPERATING_MODE(MODE) (((MODE) == CAN_OperatingMode_Initialization) ||\ + ((MODE) == CAN_OperatingMode_Normal)|| \ + ((MODE) == CAN_OperatingMode_Sleep)) +/** + * @} + */ + +/** + * @defgroup CAN_operating_mode_status + * @{ + */ + +#define CAN_ModeStatus_Failed ((uint8_t)0x00) /*!< CAN entering the specific mode failed */ +#define CAN_ModeStatus_Success ((uint8_t)!CAN_ModeStatus_Failed) /*!< CAN entering the specific mode Succeed */ +/** + * @} + */ + +/** @defgroup CAN_synchronisation_jump_width + * @{ + */ +#define CAN_SJW_1tq ((uint8_t)0x00) /*!< 1 time quantum */ +#define CAN_SJW_2tq ((uint8_t)0x01) /*!< 2 time quantum */ +#define CAN_SJW_3tq ((uint8_t)0x02) /*!< 3 time quantum */ +#define CAN_SJW_4tq ((uint8_t)0x03) /*!< 4 time quantum */ + +#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1tq) || ((SJW) == CAN_SJW_2tq)|| \ + ((SJW) == CAN_SJW_3tq) || ((SJW) == CAN_SJW_4tq)) +/** + * @} + */ + +/** @defgroup CAN_time_quantum_in_bit_segment_1 + * @{ + */ +#define CAN_BS1_1tq ((uint8_t)0x00) /*!< 1 time quantum */ +#define CAN_BS1_2tq ((uint8_t)0x01) /*!< 2 time quantum */ +#define CAN_BS1_3tq ((uint8_t)0x02) /*!< 3 time quantum */ +#define CAN_BS1_4tq ((uint8_t)0x03) /*!< 4 time quantum */ +#define CAN_BS1_5tq ((uint8_t)0x04) /*!< 5 time quantum */ +#define CAN_BS1_6tq ((uint8_t)0x05) /*!< 6 time quantum */ +#define CAN_BS1_7tq ((uint8_t)0x06) /*!< 7 time quantum */ +#define CAN_BS1_8tq ((uint8_t)0x07) /*!< 8 time quantum */ +#define CAN_BS1_9tq ((uint8_t)0x08) /*!< 9 time quantum */ +#define CAN_BS1_10tq ((uint8_t)0x09) /*!< 10 time quantum */ +#define CAN_BS1_11tq ((uint8_t)0x0A) /*!< 11 time quantum */ +#define CAN_BS1_12tq ((uint8_t)0x0B) /*!< 12 time quantum */ +#define CAN_BS1_13tq ((uint8_t)0x0C) /*!< 13 time quantum */ +#define CAN_BS1_14tq ((uint8_t)0x0D) /*!< 14 time quantum */ +#define CAN_BS1_15tq ((uint8_t)0x0E) /*!< 15 time quantum */ +#define CAN_BS1_16tq ((uint8_t)0x0F) /*!< 16 time quantum */ + +#define IS_CAN_BS1(BS1) ((BS1) <= CAN_BS1_16tq) +/** + * @} + */ + +/** @defgroup CAN_time_quantum_in_bit_segment_2 + * @{ + */ +#define CAN_BS2_1tq ((uint8_t)0x00) /*!< 1 time quantum */ +#define CAN_BS2_2tq ((uint8_t)0x01) /*!< 2 time quantum */ +#define CAN_BS2_3tq ((uint8_t)0x02) /*!< 3 time quantum */ +#define CAN_BS2_4tq ((uint8_t)0x03) /*!< 4 time quantum */ +#define CAN_BS2_5tq ((uint8_t)0x04) /*!< 5 time quantum */ +#define CAN_BS2_6tq ((uint8_t)0x05) /*!< 6 time quantum */ +#define CAN_BS2_7tq ((uint8_t)0x06) /*!< 7 time quantum */ +#define CAN_BS2_8tq ((uint8_t)0x07) /*!< 8 time quantum */ + +#define IS_CAN_BS2(BS2) ((BS2) <= CAN_BS2_8tq) +/** + * @} + */ + +/** @defgroup CAN_clock_prescaler + * @{ + */ +#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1) && ((PRESCALER) <= 1024)) +/** + * @} + */ + +/** @defgroup CAN_filter_number + * @{ + */ +#define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 27) +/** + * @} + */ + +/** @defgroup CAN_filter_mode + * @{ + */ +#define CAN_FilterMode_IdMask ((uint8_t)0x00) /*!< identifier/mask mode */ +#define CAN_FilterMode_IdList ((uint8_t)0x01) /*!< identifier list mode */ + +#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FilterMode_IdMask) || \ + ((MODE) == CAN_FilterMode_IdList)) +/** + * @} + */ + +/** @defgroup CAN_filter_scale + * @{ + */ +#define CAN_FilterScale_16bit ((uint8_t)0x00) /*!< Two 16-bit filters */ +#define CAN_FilterScale_32bit ((uint8_t)0x01) /*!< One 32-bit filter */ + +#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FilterScale_16bit) || \ + ((SCALE) == CAN_FilterScale_32bit)) +/** + * @} + */ + +/** @defgroup CAN_filter_FIFO + * @{ + */ +#define CAN_Filter_FIFO0 ((uint8_t)0x00) /*!< Filter FIFO 0 assignment for filter x */ +#define CAN_Filter_FIFO1 ((uint8_t)0x01) /*!< Filter FIFO 1 assignment for filter x */ +#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FilterFIFO0) || \ + ((FIFO) == CAN_FilterFIFO1)) + +/* Legacy defines */ +#define CAN_FilterFIFO0 CAN_Filter_FIFO0 +#define CAN_FilterFIFO1 CAN_Filter_FIFO1 +/** + * @} + */ + +/** @defgroup CAN_Start_bank_filter_for_slave_CAN + * @{ + */ +#define IS_CAN_BANKNUMBER(BANKNUMBER) (((BANKNUMBER) >= 1) && ((BANKNUMBER) <= 27)) +/** + * @} + */ + +/** @defgroup CAN_Tx + * @{ + */ +#define IS_CAN_TRANSMITMAILBOX(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= ((uint8_t)0x02)) +#define IS_CAN_STDID(STDID) ((STDID) <= ((uint32_t)0x7FF)) +#define IS_CAN_EXTID(EXTID) ((EXTID) <= ((uint32_t)0x1FFFFFFF)) +#define IS_CAN_DLC(DLC) ((DLC) <= ((uint8_t)0x08)) +/** + * @} + */ + +/** @defgroup CAN_identifier_type + * @{ + */ +#define CAN_Id_Standard ((uint32_t)0x00000000) /*!< Standard Id */ +#define CAN_Id_Extended ((uint32_t)0x00000004) /*!< Extended Id */ +#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_Id_Standard) || \ + ((IDTYPE) == CAN_Id_Extended)) + +/* Legacy defines */ +#define CAN_ID_STD CAN_Id_Standard +#define CAN_ID_EXT CAN_Id_Extended +/** + * @} + */ + +/** @defgroup CAN_remote_transmission_request + * @{ + */ +#define CAN_RTR_Data ((uint32_t)0x00000000) /*!< Data frame */ +#define CAN_RTR_Remote ((uint32_t)0x00000002) /*!< Remote frame */ +#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_Data) || ((RTR) == CAN_RTR_Remote)) + +/* Legacy defines */ +#define CAN_RTR_DATA CAN_RTR_Data +#define CAN_RTR_REMOTE CAN_RTR_Remote +/** + * @} + */ + +/** @defgroup CAN_transmit_constants + * @{ + */ +#define CAN_TxStatus_Failed ((uint8_t)0x00)/*!< CAN transmission failed */ +#define CAN_TxStatus_Ok ((uint8_t)0x01) /*!< CAN transmission succeeded */ +#define CAN_TxStatus_Pending ((uint8_t)0x02) /*!< CAN transmission pending */ +#define CAN_TxStatus_NoMailBox ((uint8_t)0x04) /*!< CAN cell did not provide + an empty mailbox */ +/* Legacy defines */ +#define CANTXFAILED CAN_TxStatus_Failed +#define CANTXOK CAN_TxStatus_Ok +#define CANTXPENDING CAN_TxStatus_Pending +#define CAN_NO_MB CAN_TxStatus_NoMailBox +/** + * @} + */ + +/** @defgroup CAN_receive_FIFO_number_constants + * @{ + */ +#define CAN_FIFO0 ((uint8_t)0x00) /*!< CAN FIFO 0 used to receive */ +#define CAN_FIFO1 ((uint8_t)0x01) /*!< CAN FIFO 1 used to receive */ + +#define IS_CAN_FIFO(FIFO) (((FIFO) == CAN_FIFO0) || ((FIFO) == CAN_FIFO1)) +/** + * @} + */ + +/** @defgroup CAN_sleep_constants + * @{ + */ +#define CAN_Sleep_Failed ((uint8_t)0x00) /*!< CAN did not enter the sleep mode */ +#define CAN_Sleep_Ok ((uint8_t)0x01) /*!< CAN entered the sleep mode */ + +/* Legacy defines */ +#define CANSLEEPFAILED CAN_Sleep_Failed +#define CANSLEEPOK CAN_Sleep_Ok +/** + * @} + */ + +/** @defgroup CAN_wake_up_constants + * @{ + */ +#define CAN_WakeUp_Failed ((uint8_t)0x00) /*!< CAN did not leave the sleep mode */ +#define CAN_WakeUp_Ok ((uint8_t)0x01) /*!< CAN leaved the sleep mode */ + +/* Legacy defines */ +#define CANWAKEUPFAILED CAN_WakeUp_Failed +#define CANWAKEUPOK CAN_WakeUp_Ok +/** + * @} + */ + +/** + * @defgroup CAN_Error_Code_constants + * @{ + */ +#define CAN_ErrorCode_NoErr ((uint8_t)0x00) /*!< No Error */ +#define CAN_ErrorCode_StuffErr ((uint8_t)0x10) /*!< Stuff Error */ +#define CAN_ErrorCode_FormErr ((uint8_t)0x20) /*!< Form Error */ +#define CAN_ErrorCode_ACKErr ((uint8_t)0x30) /*!< Acknowledgment Error */ +#define CAN_ErrorCode_BitRecessiveErr ((uint8_t)0x40) /*!< Bit Recessive Error */ +#define CAN_ErrorCode_BitDominantErr ((uint8_t)0x50) /*!< Bit Dominant Error */ +#define CAN_ErrorCode_CRCErr ((uint8_t)0x60) /*!< CRC Error */ +#define CAN_ErrorCode_SoftwareSetErr ((uint8_t)0x70) /*!< Software Set Error */ +/** + * @} + */ + +/** @defgroup CAN_flags + * @{ + */ +/* If the flag is 0x3XXXXXXX, it means that it can be used with CAN_GetFlagStatus() + and CAN_ClearFlag() functions. */ +/* If the flag is 0x1XXXXXXX, it means that it can only be used with + CAN_GetFlagStatus() function. */ + +/* Transmit Flags */ +#define CAN_FLAG_RQCP0 ((uint32_t)0x38000001) /*!< Request MailBox0 Flag */ +#define CAN_FLAG_RQCP1 ((uint32_t)0x38000100) /*!< Request MailBox1 Flag */ +#define CAN_FLAG_RQCP2 ((uint32_t)0x38010000) /*!< Request MailBox2 Flag */ + +/* Receive Flags */ +#define CAN_FLAG_FMP0 ((uint32_t)0x12000003) /*!< FIFO 0 Message Pending Flag */ +#define CAN_FLAG_FF0 ((uint32_t)0x32000008) /*!< FIFO 0 Full Flag */ +#define CAN_FLAG_FOV0 ((uint32_t)0x32000010) /*!< FIFO 0 Overrun Flag */ +#define CAN_FLAG_FMP1 ((uint32_t)0x14000003) /*!< FIFO 1 Message Pending Flag */ +#define CAN_FLAG_FF1 ((uint32_t)0x34000008) /*!< FIFO 1 Full Flag */ +#define CAN_FLAG_FOV1 ((uint32_t)0x34000010) /*!< FIFO 1 Overrun Flag */ + +/* Operating Mode Flags */ +#define CAN_FLAG_WKU ((uint32_t)0x31000008) /*!< Wake up Flag */ +#define CAN_FLAG_SLAK ((uint32_t)0x31000012) /*!< Sleep acknowledge Flag */ +/* @note When SLAK interrupt is disabled (SLKIE=0), no polling on SLAKI is possible. + In this case the SLAK bit can be polled.*/ + +/* Error Flags */ +#define CAN_FLAG_EWG ((uint32_t)0x10F00001) /*!< Error Warning Flag */ +#define CAN_FLAG_EPV ((uint32_t)0x10F00002) /*!< Error Passive Flag */ +#define CAN_FLAG_BOF ((uint32_t)0x10F00004) /*!< Bus-Off Flag */ +#define CAN_FLAG_LEC ((uint32_t)0x30F00070) /*!< Last error code Flag */ + +#define IS_CAN_GET_FLAG(FLAG) (((FLAG) == CAN_FLAG_LEC) || ((FLAG) == CAN_FLAG_BOF) || \ + ((FLAG) == CAN_FLAG_EPV) || ((FLAG) == CAN_FLAG_EWG) || \ + ((FLAG) == CAN_FLAG_WKU) || ((FLAG) == CAN_FLAG_FOV0) || \ + ((FLAG) == CAN_FLAG_FF0) || ((FLAG) == CAN_FLAG_FMP0) || \ + ((FLAG) == CAN_FLAG_FOV1) || ((FLAG) == CAN_FLAG_FF1) || \ + ((FLAG) == CAN_FLAG_FMP1) || ((FLAG) == CAN_FLAG_RQCP2) || \ + ((FLAG) == CAN_FLAG_RQCP1)|| ((FLAG) == CAN_FLAG_RQCP0) || \ + ((FLAG) == CAN_FLAG_SLAK )) + +#define IS_CAN_CLEAR_FLAG(FLAG)(((FLAG) == CAN_FLAG_LEC) || ((FLAG) == CAN_FLAG_RQCP2) || \ + ((FLAG) == CAN_FLAG_RQCP1) || ((FLAG) == CAN_FLAG_RQCP0) || \ + ((FLAG) == CAN_FLAG_FF0) || ((FLAG) == CAN_FLAG_FOV0) ||\ + ((FLAG) == CAN_FLAG_FF1) || ((FLAG) == CAN_FLAG_FOV1) || \ + ((FLAG) == CAN_FLAG_WKU) || ((FLAG) == CAN_FLAG_SLAK)) +/** + * @} + */ + + +/** @defgroup CAN_interrupts + * @{ + */ +#define CAN_IT_TME ((uint32_t)0x00000001) /*!< Transmit mailbox empty Interrupt*/ + +/* Receive Interrupts */ +#define CAN_IT_FMP0 ((uint32_t)0x00000002) /*!< FIFO 0 message pending Interrupt*/ +#define CAN_IT_FF0 ((uint32_t)0x00000004) /*!< FIFO 0 full Interrupt*/ +#define CAN_IT_FOV0 ((uint32_t)0x00000008) /*!< FIFO 0 overrun Interrupt*/ +#define CAN_IT_FMP1 ((uint32_t)0x00000010) /*!< FIFO 1 message pending Interrupt*/ +#define CAN_IT_FF1 ((uint32_t)0x00000020) /*!< FIFO 1 full Interrupt*/ +#define CAN_IT_FOV1 ((uint32_t)0x00000040) /*!< FIFO 1 overrun Interrupt*/ + +/* Operating Mode Interrupts */ +#define CAN_IT_WKU ((uint32_t)0x00010000) /*!< Wake-up Interrupt*/ +#define CAN_IT_SLK ((uint32_t)0x00020000) /*!< Sleep acknowledge Interrupt*/ + +/* Error Interrupts */ +#define CAN_IT_EWG ((uint32_t)0x00000100) /*!< Error warning Interrupt*/ +#define CAN_IT_EPV ((uint32_t)0x00000200) /*!< Error passive Interrupt*/ +#define CAN_IT_BOF ((uint32_t)0x00000400) /*!< Bus-off Interrupt*/ +#define CAN_IT_LEC ((uint32_t)0x00000800) /*!< Last error code Interrupt*/ +#define CAN_IT_ERR ((uint32_t)0x00008000) /*!< Error Interrupt*/ + +/* Flags named as Interrupts : kept only for FW compatibility */ +#define CAN_IT_RQCP0 CAN_IT_TME +#define CAN_IT_RQCP1 CAN_IT_TME +#define CAN_IT_RQCP2 CAN_IT_TME + + +#define IS_CAN_IT(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FMP0) ||\ + ((IT) == CAN_IT_FF0) || ((IT) == CAN_IT_FOV0) ||\ + ((IT) == CAN_IT_FMP1) || ((IT) == CAN_IT_FF1) ||\ + ((IT) == CAN_IT_FOV1) || ((IT) == CAN_IT_EWG) ||\ + ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\ + ((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\ + ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK)) + +#define IS_CAN_CLEAR_IT(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FF0) ||\ + ((IT) == CAN_IT_FOV0)|| ((IT) == CAN_IT_FF1) ||\ + ((IT) == CAN_IT_FOV1)|| ((IT) == CAN_IT_EWG) ||\ + ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\ + ((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\ + ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the CAN configuration to the default reset state *****/ +void CAN_DeInit(CAN_TypeDef* CANx); + +/* Initialization and Configuration functions *********************************/ +uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct); +void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct); +void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct); +void CAN_SlaveStartBank(uint8_t CAN_BankNumber); +void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState); +void CAN_TTComModeCmd(CAN_TypeDef* CANx, FunctionalState NewState); + +/* CAN Frames Transmission functions ******************************************/ +uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage); +uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox); +void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox); + +/* CAN Frames Reception functions *********************************************/ +void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage); +void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber); +uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber); + +/* Operation modes functions **************************************************/ +uint8_t CAN_OperatingModeRequest(CAN_TypeDef* CANx, uint8_t CAN_OperatingMode); +uint8_t CAN_Sleep(CAN_TypeDef* CANx); +uint8_t CAN_WakeUp(CAN_TypeDef* CANx); + +/* CAN Bus Error management functions *****************************************/ +uint8_t CAN_GetLastErrorCode(CAN_TypeDef* CANx); +uint8_t CAN_GetReceiveErrorCounter(CAN_TypeDef* CANx); +uint8_t CAN_GetLSBTransmitErrorCounter(CAN_TypeDef* CANx); + +/* Interrupts and flags management functions **********************************/ +void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState); +FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG); +void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG); +ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT); +void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F30x_CAN_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_comp.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_comp.h new file mode 100644 index 0000000..ce41a21 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_comp.h @@ -0,0 +1,426 @@ +/** + ****************************************************************************** + * @file stm32f30x_comp.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the COMP firmware + * library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_COMP_H +#define __STM32F30x_COMP_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup COMP + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief COMP Init structure definition + */ + +typedef struct +{ + + uint32_t COMP_InvertingInput; /*!< Selects the inverting input of the comparator. + This parameter can be a value of @ref COMP_InvertingInput */ + + uint32_t COMP_NonInvertingInput; /*!< Selects the non inverting input of the comparator. + This parameter can be a value of @ref COMP_NonInvertingInput */ + + uint32_t COMP_Output; /*!< Selects the output redirection of the comparator. + This parameter can be a value of @ref COMP_Output */ + + uint32_t COMP_BlankingSrce; /*!< Selects the output blanking source of the comparator. + This parameter can be a value of @ref COMP_BlankingSrce */ + + uint32_t COMP_OutputPol; /*!< Selects the output polarity of the comparator. + This parameter can be a value of @ref COMP_OutputPoloarity */ + + uint32_t COMP_Hysteresis; /*!< Selects the hysteresis voltage of the comparator. + This parameter can be a value of @ref COMP_Hysteresis */ + + uint32_t COMP_Mode; /*!< Selects the operating mode of the comparator + and allows to adjust the speed/consumption. + This parameter can be a value of @ref COMP_Mode */ +}COMP_InitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup COMP_Exported_Constants + * @{ + */ + +/** @defgroup COMP_Selection + * @{ + */ + +#define COMP_Selection_COMP1 ((uint32_t)0x00000000) /*!< COMP1 Selection */ +#define COMP_Selection_COMP2 ((uint32_t)0x00000004) /*!< COMP2 Selection */ +#define COMP_Selection_COMP3 ((uint32_t)0x00000008) /*!< COMP3 Selection */ +#define COMP_Selection_COMP4 ((uint32_t)0x0000000C) /*!< COMP4 Selection */ +#define COMP_Selection_COMP5 ((uint32_t)0x00000010) /*!< COMP5 Selection */ +#define COMP_Selection_COMP6 ((uint32_t)0x00000014) /*!< COMP6 Selection */ +#define COMP_Selection_COMP7 ((uint32_t)0x00000018) /*!< COMP7 Selection */ + +#define IS_COMP_ALL_PERIPH(PERIPH) (((PERIPH) == COMP_Selection_COMP1) || \ + ((PERIPH) == COMP_Selection_COMP2) || \ + ((PERIPH) == COMP_Selection_COMP3) || \ + ((PERIPH) == COMP_Selection_COMP4) || \ + ((PERIPH) == COMP_Selection_COMP5) || \ + ((PERIPH) == COMP_Selection_COMP6) || \ + ((PERIPH) == COMP_Selection_COMP7)) + +/** + * @} + */ + +/** @defgroup COMP_InvertingInput + * @{ + */ + +#define COMP_InvertingInput_1_4VREFINT ((uint32_t)0x00000000) /*!< 1/4 VREFINT connected to comparator inverting input */ +#define COMP_InvertingInput_1_2VREFINT COMP_CSR_COMPxINSEL_0 /*!< 1/2 VREFINT connected to comparator inverting input */ +#define COMP_InvertingInput_3_4VREFINT COMP_CSR_COMPxINSEL_1 /*!< 3/4 VREFINT connected to comparator inverting input */ +#define COMP_InvertingInput_VREFINT ((uint32_t)0x00000030) /*!< VREFINT connected to comparator inverting input */ +#define COMP_InvertingInput_DAC1OUT1 COMP_CSR_COMPxINSEL_2 /*!< DAC1_OUT1 (PA4) connected to comparator inverting input */ +#define COMP_InvertingInput_DAC1OUT2 ((uint32_t)0x00000050) /*!< DAC1_OUT2 (PA5) connected to comparator inverting input */ + +#define COMP_InvertingInput_IO1 ((uint32_t)0x00000060) /*!< I/O1 (PA0 for COMP1, PA2 for COMP2, PD15 for COMP3, + PE8 for COMP4, PD13 for COMP5, PD10 for COMP6, + PC0 for COMP7) connected to comparator inverting input */ + +#define COMP_InvertingInput_IO2 COMP_CSR_COMPxINSEL /*!< I/O2 (PB12 for COMP3, PB2 for COMP4, PB10 for COMP5, + PB15 for COMP6) connected to comparator inverting input */ + +#define COMP_InvertingInput_DAC2OUT1 COMP_CSR_COMPxINSEL_3 /*!< DAC2_OUT1 (PA6) connected to comparator inverting input */ + +#define IS_COMP_INVERTING_INPUT(INPUT) (((INPUT) == COMP_InvertingInput_1_4VREFINT) || \ + ((INPUT) == COMP_InvertingInput_1_2VREFINT) || \ + ((INPUT) == COMP_InvertingInput_3_4VREFINT) || \ + ((INPUT) == COMP_InvertingInput_VREFINT) || \ + ((INPUT) == COMP_InvertingInput_DAC1OUT1) || \ + ((INPUT) == COMP_InvertingInput_DAC1OUT2) || \ + ((INPUT) == COMP_InvertingInput_IO1) || \ + ((INPUT) == COMP_InvertingInput_IO2) || \ + ((INPUT) == COMP_InvertingInput_DAC2OUT1)) +/** + * @} + */ + +/** @defgroup COMP_NonInvertingInput + * @{ + */ + +#define COMP_NonInvertingInput_IO1 ((uint32_t)0x00000000) /*!< I/O1 (PA1 for COMP1, PA7 for COMP2, PB14 for COMP3, + PB0 for COMP4, PD12 for COMP5, PD11 for COMP6, + PA0 for COMP7) connected to comparator non inverting input */ + +#define COMP_NonInvertingInput_IO2 COMP_CSR_COMPxNONINSEL /*!< I/O2 (PA3 for COMP2, PD14 for COMP3, PE7 for COMP4, PB13 for COMP5, + PB11 for COMP6, PC1 for COMP7) connected to comparator non inverting input */ + +#define IS_COMP_NONINVERTING_INPUT(INPUT) (((INPUT) == COMP_NonInvertingInput_IO1) || \ + ((INPUT) == COMP_NonInvertingInput_IO2)) +/** + * @} + */ + +/** @defgroup COMP_Output + * @{ + */ + +#define COMP_Output_None ((uint32_t)0x00000000) /*!< COMP output isn't connected to other peripherals */ + +/* Output Redirection common for all comparators COMP1...COMP7 */ +#define COMP_Output_TIM1BKIN COMP_CSR_COMPxOUTSEL_0 /*!< COMP output connected to TIM1 Break Input (BKIN) */ +#define COMP_Output_TIM1BKIN2 ((uint32_t)0x00000800) /*!< COMP output connected to TIM1 Break Input 2 (BKIN2) */ +#define COMP_Output_TIM8BKIN ((uint32_t)0x00000C00) /*!< COMP output connected to TIM8 Break Input (BKIN) */ +#define COMP_Output_TIM8BKIN2 ((uint32_t)0x00001000) /*!< COMP output connected to TIM8 Break Input 2 (BKIN2) */ +#define COMP_Output_TIM1BKIN2_TIM8BKIN2 ((uint32_t)0x00001400) /*!< COMP output connected to TIM1 Break Input 2 and TIM8 Break Input 2 */ + +/* Output Redirection common for COMP1 and COMP2 */ +#define COMP_Output_TIM1OCREFCLR ((uint32_t)0x00001800) /*!< COMP output connected to TIM1 OCREF Clear */ +#define COMP_Output_TIM1IC1 ((uint32_t)0x00001C00) /*!< COMP output connected to TIM1 Input Capture 1 */ +#define COMP_Output_TIM2IC4 ((uint32_t)0x00002000) /*!< COMP output connected to TIM2 Input Capture 4 */ +#define COMP_Output_TIM2OCREFCLR ((uint32_t)0x00002400) /*!< COMP output connected to TIM2 OCREF Clear */ +#define COMP_Output_TIM3IC1 ((uint32_t)0x00002800) /*!< COMP output connected to TIM3 Input Capture 1 */ +#define COMP_Output_TIM3OCREFCLR ((uint32_t)0x00002C00) /*!< COMP output connected to TIM3 OCREF Clear */ + +/* Output Redirection specific to COMP2 */ +#define COMP_Output_HRTIM1_FLT6 ((uint32_t)0x00003000) /*!< COMP output connected to HRTIM1 FLT6 */ +#define COMP_Output_HRTIM1_EE1_2 ((uint32_t)0x00003400) /*!< COMP output connected to HRTIM1 EE1_2*/ +#define COMP_Output_HRTIM1_EE6_2 ((uint32_t)0x00003800) /*!< COMP output connected to HRTIM1 EE6_2 */ + +/* Output Redirection specific to COMP3 */ +#define COMP_Output_TIM4IC1 ((uint32_t)0x00001C00) /*!< COMP output connected to TIM4 Input Capture 1 */ +#define COMP_Output_TIM3IC2 ((uint32_t)0x00002000) /*!< COMP output connected to TIM3 Input Capture 2 */ +#define COMP_Output_TIM15IC1 ((uint32_t)0x00002800) /*!< COMP output connected to TIM15 Input Capture 1 */ +#define COMP_Output_TIM15BKIN ((uint32_t)0x00002C00) /*!< COMP output connected to TIM15 Break Input (BKIN) */ + +/* Output Redirection specific to COMP4 */ +#define COMP_Output_TIM3IC3 ((uint32_t)0x00001800) /*!< COMP output connected to TIM3 Input Capture 3 */ +#define COMP_Output_TIM8OCREFCLR ((uint32_t)0x00001C00) /*!< COMP output connected to TIM8 OCREF Clear */ +#define COMP_Output_TIM15IC2 ((uint32_t)0x00002000) /*!< COMP output connected to TIM15 Input Capture 2 */ +#define COMP_Output_TIM4IC2 ((uint32_t)0x00002400) /*!< COMP output connected to TIM4 Input Capture 2 */ +#define COMP_Output_TIM15OCREFCLR ((uint32_t)0x00002800) /*!< COMP output connected to TIM15 OCREF Clear */ + +#define COMP_Output_HRTIM1_FLT7 ((uint32_t)0x00003000) /*!< COMP output connected to HRTIM1 FLT7 */ +#define COMP_Output_HRTIM1_EE2_2 ((uint32_t)0x00003400) /*!< COMP output connected to HRTIM1 EE2_2*/ +#define COMP_Output_HRTIM1_EE7_2 ((uint32_t)0x00003800) /*!< COMP output connected to HRTIM1 EE7_2 */ + +/* Output Redirection specific to COMP5 */ +#define COMP_Output_TIM2IC1 ((uint32_t)0x00001800) /*!< COMP output connected to TIM2 Input Capture 1 */ +#define COMP_Output_TIM17IC1 ((uint32_t)0x00002000) /*!< COMP output connected to TIM17 Input Capture 1 */ +#define COMP_Output_TIM4IC3 ((uint32_t)0x00002400) /*!< COMP output connected to TIM4 Input Capture 3 */ +#define COMP_Output_TIM16BKIN ((uint32_t)0x00002800) /*!< COMP output connected to TIM16 Break Input (BKIN) */ + +/* Output Redirection specific to COMP6 */ +#define COMP_Output_TIM2IC2 ((uint32_t)0x00001800) /*!< COMP output connected to TIM2 Input Capture 2 */ +#define COMP_Output_COMP6TIM2OCREFCLR ((uint32_t)0x00002000) /*!< COMP output connected to TIM2 OCREF Clear */ +#define COMP_Output_TIM16OCREFCLR ((uint32_t)0x00002400) /*!< COMP output connected to TIM16 OCREF Clear */ +#define COMP_Output_TIM16IC1 ((uint32_t)0x00002800) /*!< COMP output connected to TIM16 Input Capture 1 */ +#define COMP_Output_TIM4IC4 ((uint32_t)0x00002C00) /*!< COMP output connected to TIM4 Input Capture 4 */ + +#define COMP_Output_HRTIM1_FLT8 ((uint32_t)0x00003000) /*!< COMP output connected to HRTIM1 FLT8 */ +#define COMP_Output_HRTIM1_EE3_2 ((uint32_t)0x00003400) /*!< COMP output connected to HRTIM1 EE3_2*/ +#define COMP_Output_HRTIM1_EE8_2 ((uint32_t)0x00003800) /*!< COMP output connected to HRTIM1 EE8_2 */ + +/* Output Redirection specific to COMP7 */ +#define COMP_Output_TIM2IC3 ((uint32_t)0x00002000) /*!< COMP output connected to TIM2 Input Capture 3 */ +#define COMP_Output_TIM1IC2 ((uint32_t)0x00002400) /*!< COMP output connected to TIM1 Input Capture 2 */ +#define COMP_Output_TIM17OCREFCLR ((uint32_t)0x00002800) /*!< COMP output connected to TIM16 OCREF Clear */ +#define COMP_Output_TIM17BKIN ((uint32_t)0x00002C00) /*!< COMP output connected to TIM16 Break Input (BKIN) */ + +#define IS_COMP_OUTPUT(OUTPUT) (((OUTPUT) == COMP_Output_None) || \ + ((OUTPUT) == COMP_Output_TIM1BKIN) || \ + ((OUTPUT) == COMP_Output_TIM1IC1) || \ + ((OUTPUT) == COMP_Output_TIM1OCREFCLR) || \ + ((OUTPUT) == COMP_Output_TIM2IC4) || \ + ((OUTPUT) == COMP_Output_TIM2OCREFCLR) || \ + ((OUTPUT) == COMP_Output_COMP6TIM2OCREFCLR) || \ + ((OUTPUT) == COMP_Output_TIM3IC1) || \ + ((OUTPUT) == COMP_Output_TIM3OCREFCLR) || \ + ((OUTPUT) == COMP_Output_TIM8BKIN) || \ + ((OUTPUT) == COMP_Output_TIM1BKIN2) || \ + ((OUTPUT) == COMP_Output_TIM8BKIN2) || \ + ((OUTPUT) == COMP_Output_TIM2OCREFCLR) || \ + ((OUTPUT) == COMP_Output_TIM1BKIN2_TIM8BKIN2) || \ + ((OUTPUT) == COMP_Output_TIM3IC2) || \ + ((OUTPUT) == COMP_Output_TIM4IC1) || \ + ((OUTPUT) == COMP_Output_TIM15IC1) || \ + ((OUTPUT) == COMP_Output_TIM15BKIN) || \ + ((OUTPUT) == COMP_Output_TIM8OCREFCLR) || \ + ((OUTPUT) == COMP_Output_TIM3IC3) || \ + ((OUTPUT) == COMP_Output_TIM4IC1) || \ + ((OUTPUT) == COMP_Output_TIM15IC1) || \ + ((OUTPUT) == COMP_Output_TIM2IC1) || \ + ((OUTPUT) == COMP_Output_TIM4IC3) || \ + ((OUTPUT) == COMP_Output_TIM16BKIN) || \ + ((OUTPUT) == COMP_Output_TIM17IC1) || \ + ((OUTPUT) == COMP_Output_TIM2IC2) || \ + ((OUTPUT) == COMP_Output_TIM16IC1) || \ + ((OUTPUT) == COMP_Output_TIM4IC4) || \ + ((OUTPUT) == COMP_Output_TIM16OCREFCLR) || \ + ((OUTPUT) == COMP_Output_TIM2IC3) || \ + ((OUTPUT) == COMP_Output_TIM1IC2) || \ + ((OUTPUT) == COMP_Output_TIM17BKIN) || \ + ((OUTPUT) == COMP_Output_TIM17OCREFCLR) || \ + ((OUTPUT) == COMP_Output_HRTIM1_FLT6) || \ + ((OUTPUT) == COMP_Output_HRTIM1_EE1_2) || \ + ((OUTPUT) == COMP_Output_HRTIM1_EE6_2) || \ + ((OUTPUT) == COMP_Output_HRTIM1_FLT7) || \ + ((OUTPUT) == COMP_Output_HRTIM1_EE2_2) || \ + ((OUTPUT) == COMP_Output_HRTIM1_EE7_2) || \ + ((OUTPUT) == COMP_Output_HRTIM1_FLT8) || \ + ((OUTPUT) == COMP_Output_HRTIM1_EE3_2) || \ + ((OUTPUT) == COMP_Output_HRTIM1_EE8_2)) + +/** + * @} + */ + +/** @defgroup COMP_BlankingSrce + * @{ + */ + +/* No blanking source can be selected for all comparators */ +#define COMP_BlankingSrce_None ((uint32_t)0x00000000) /*!< No blanking source */ + +/* Blanking source common for COMP1, COMP2, COMP3 and COMP7 */ +#define COMP_BlankingSrce_TIM1OC5 COMP_CSR_COMPxBLANKING_0 /*!< TIM1 OC5 selected as blanking source for compartor */ + +/* Blanking source common for COMP1 and COMP2 */ +#define COMP_BlankingSrce_TIM2OC3 COMP_CSR_COMPxBLANKING_1 /*!< TIM2 OC5 selected as blanking source for compartor */ + +/* Blanking source common for COMP1, COMP2 and COMP5 */ +#define COMP_BlankingSrce_TIM3OC3 ((uint32_t)0x000C0000) /*!< TIM2 OC3 selected as blanking source for compartor */ + +/* Blanking source common for COMP3 and COMP6 */ +#define COMP_BlankingSrce_TIM2OC4 ((uint32_t)0x000C0000) /*!< TIM2 OC4 selected as blanking source for compartor */ + +/* Blanking source common for COMP4, COMP5, COMP6 and COMP7 */ +#define COMP_BlankingSrce_TIM8OC5 COMP_CSR_COMPxBLANKING_1 /*!< TIM8 OC5 selected as blanking source for compartor */ + +/* Blanking source for COMP4 */ +#define COMP_BlankingSrce_TIM3OC4 COMP_CSR_COMPxBLANKING_0 /*!< TIM3 OC4 selected as blanking source for compartor */ +#define COMP_BlankingSrce_TIM15OC1 ((uint32_t)0x000C0000) /*!< TIM15 OC1 selected as blanking source for compartor */ + +/* Blanking source common for COMP6 and COMP7 */ +#define COMP_BlankingSrce_TIM15OC2 COMP_CSR_COMPxBLANKING_2 /*!< TIM15 OC2 selected as blanking source for compartor */ + +#define IS_COMP_BLANKING_SOURCE(SOURCE) (((SOURCE) == COMP_BlankingSrce_None) || \ + ((SOURCE) == COMP_BlankingSrce_TIM1OC5) || \ + ((SOURCE) == COMP_BlankingSrce_TIM2OC3) || \ + ((SOURCE) == COMP_BlankingSrce_TIM3OC3) || \ + ((SOURCE) == COMP_BlankingSrce_TIM2OC4) || \ + ((SOURCE) == COMP_BlankingSrce_TIM8OC5) || \ + ((SOURCE) == COMP_BlankingSrce_TIM3OC4) || \ + ((SOURCE) == COMP_BlankingSrce_TIM15OC1) || \ + ((SOURCE) == COMP_BlankingSrce_TIM15OC2)) +/** + * @} + */ + +/** @defgroup COMP_OutputPoloarity + * @{ + */ +#define COMP_OutputPol_NonInverted ((uint32_t)0x00000000) /*!< COMP output on GPIO isn't inverted */ +#define COMP_OutputPol_Inverted COMP_CSR_COMPxPOL /*!< COMP output on GPIO is inverted */ + +#define IS_COMP_OUTPUT_POL(POL) (((POL) == COMP_OutputPol_NonInverted) || \ + ((POL) == COMP_OutputPol_Inverted)) + +/** + * @} + */ + +/** @defgroup COMP_Hysteresis + * @{ + */ +/* Please refer to the electrical characteristics in the device datasheet for + the hysteresis level */ +#define COMP_Hysteresis_No 0x00000000 /*!< No hysteresis */ +#define COMP_Hysteresis_Low COMP_CSR_COMPxHYST_0 /*!< Hysteresis level low */ +#define COMP_Hysteresis_Medium COMP_CSR_COMPxHYST_1 /*!< Hysteresis level medium */ +#define COMP_Hysteresis_High COMP_CSR_COMPxHYST /*!< Hysteresis level high */ + +#define IS_COMP_HYSTERESIS(HYSTERESIS) (((HYSTERESIS) == COMP_Hysteresis_No) || \ + ((HYSTERESIS) == COMP_Hysteresis_Low) || \ + ((HYSTERESIS) == COMP_Hysteresis_Medium) || \ + ((HYSTERESIS) == COMP_Hysteresis_High)) +/** + * @} + */ + +/** @defgroup COMP_Mode + * @{ + */ +/* Please refer to the electrical characteristics in the device datasheet for + the power consumption values */ +#define COMP_Mode_HighSpeed 0x00000000 /*!< High Speed */ +#define COMP_Mode_MediumSpeed COMP_CSR_COMPxMODE_0 /*!< Medium Speed */ +#define COMP_Mode_LowPower COMP_CSR_COMPxMODE_1 /*!< Low power mode */ +#define COMP_Mode_UltraLowPower COMP_CSR_COMPxMODE /*!< Ultra-low power mode */ + +#define IS_COMP_MODE(MODE) (((MODE) == COMP_Mode_UltraLowPower) || \ + ((MODE) == COMP_Mode_LowPower) || \ + ((MODE) == COMP_Mode_MediumSpeed) || \ + ((MODE) == COMP_Mode_HighSpeed)) +/** + * @} + */ + +/** @defgroup COMP_OutputLevel + * @{ + */ +/* When output polarity is not inverted, comparator output is high when + the non-inverting input is at a higher voltage than the inverting input */ +#define COMP_OutputLevel_High COMP_CSR_COMPxOUT +/* When output polarity is not inverted, comparator output is low when + the non-inverting input is at a lower voltage than the inverting input*/ +#define COMP_OutputLevel_Low ((uint32_t)0x00000000) + +/** + * @} + */ + +/** @defgroup COMP_WindowMode + * @{ + */ +#define IS_COMP_WINDOW(WINDOW) (((WINDOW) == COMP_Selection_COMP2) || \ + ((WINDOW) == COMP_Selection_COMP4) || \ + ((WINDOW) == COMP_Selection_COMP6)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +/* Function used to set the COMP configuration to the default reset state ****/ +void COMP_DeInit(uint32_t COMP_Selection); + +/* Initialization and Configuration functions *********************************/ +void COMP_Init(uint32_t COMP_Selection, COMP_InitTypeDef* COMP_InitStruct); +void COMP_StructInit(COMP_InitTypeDef* COMP_InitStruct); +void COMP_Cmd(uint32_t COMP_Selection, FunctionalState NewState); +void COMP_SwitchCmd(uint32_t COMP_Selection, FunctionalState NewState); +uint32_t COMP_GetOutputLevel(uint32_t COMP_Selection); + +/* Window mode control function ***********************************************/ +void COMP_WindowCmd(uint32_t COMP_Selection, FunctionalState NewState); + +/* COMP configuration locking function ****************************************/ +void COMP_LockConfig(uint32_t COMP_Selection); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F30x_COMP_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_crc.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_crc.h new file mode 100644 index 0000000..1b4d4b6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_crc.h @@ -0,0 +1,121 @@ +/** + ****************************************************************************** + * @file stm32f30x_crc.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the CRC firmware + * library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_CRC_H +#define __STM32F30x_CRC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/*!< Includes ----------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup CRC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup CRC_ReverseInputData + * @{ + */ +#define CRC_ReverseInputData_No ((uint32_t)0x00000000) /*!< No reverse operation of Input Data */ +#define CRC_ReverseInputData_8bits CRC_CR_REV_IN_0 /*!< Reverse operation of Input Data on 8 bits */ +#define CRC_ReverseInputData_16bits CRC_CR_REV_IN_1 /*!< Reverse operation of Input Data on 16 bits */ +#define CRC_ReverseInputData_32bits CRC_CR_REV_IN /*!< Reverse operation of Input Data on 32 bits */ + +#define IS_CRC_REVERSE_INPUT_DATA(DATA) (((DATA) == CRC_ReverseInputData_No) || \ + ((DATA) == CRC_ReverseInputData_8bits) || \ + ((DATA) == CRC_ReverseInputData_16bits) || \ + ((DATA) == CRC_ReverseInputData_32bits)) + +/** + * @} + */ + +/** @defgroup CRC_PolynomialSize + * @{ + */ +#define CRC_PolSize_7 CRC_CR_POLSIZE /*!< 7-bit polynomial for CRC calculation */ +#define CRC_PolSize_8 CRC_CR_POLSIZE_1 /*!< 8-bit polynomial for CRC calculation */ +#define CRC_PolSize_16 CRC_CR_POLSIZE_0 /*!< 16-bit polynomial for CRC calculation */ +#define CRC_PolSize_32 ((uint32_t)0x00000000)/*!< 32-bit polynomial for CRC calculation */ + +#define IS_CRC_POL_SIZE(SIZE) (((SIZE) == CRC_PolSize_7) || \ + ((SIZE) == CRC_PolSize_8) || \ + ((SIZE) == CRC_PolSize_16) || \ + ((SIZE) == CRC_PolSize_32)) + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +/* Configuration of the CRC computation unit **********************************/ +void CRC_DeInit(void); +void CRC_ResetDR(void); +void CRC_PolynomialSizeSelect(uint32_t CRC_PolSize); +void CRC_ReverseInputDataSelect(uint32_t CRC_ReverseInputData); +void CRC_ReverseOutputDataCmd(FunctionalState NewState); +void CRC_SetInitRegister(uint32_t CRC_InitValue); +void CRC_SetPolynomial(uint32_t CRC_Pol); + +/* CRC computation ************************************************************/ +uint32_t CRC_CalcCRC(uint32_t CRC_Data); +uint32_t CRC_CalcCRC16bits(uint16_t CRC_Data); +uint32_t CRC_CalcCRC8bits(uint8_t CRC_Data); +uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength); +uint32_t CRC_GetCRC(void); + +/* Independent register (IDR) access (write/read) *****************************/ +void CRC_SetIDRegister(uint8_t CRC_IDValue); +uint8_t CRC_GetIDRegister(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F30x_CRC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_dac.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_dac.h new file mode 100644 index 0000000..ce8ddef --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_dac.h @@ -0,0 +1,322 @@ +/** + ****************************************************************************** + * @file stm32f30x_dac.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the DAC firmware + * library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_DAC_H +#define __STM32F30x_DAC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DAC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +#define DAC_CR_DMAUDRIE ((uint32_t)0x00002000) /*!< DAC channel DMA underrun interrupt enable */ + +/** + * @brief DAC Init structure definition + */ + +typedef struct +{ + uint32_t DAC_Trigger; /*!< Specifies the external trigger for the selected DAC channel. + This parameter can be a value of @ref DAC_trigger_selection */ + + uint32_t DAC_WaveGeneration; /*!< Specifies whether DAC channel noise waves or triangle waves + are generated, or whether no wave is generated. + This parameter can be a value of @ref DAC_wave_generation */ + + uint32_t DAC_LFSRUnmask_TriangleAmplitude; /*!< Specifies the LFSR mask for noise wave generation or + the maximum amplitude triangle generation for the DAC channel. + This parameter can be a value of @ref DAC_lfsrunmask_triangleamplitude */ + + uint32_t DAC_Buffer_Switch; /*!< Specifies whether the DAC channel output buffer is enabled or disabled or + the DAC channel output switch is enabled or disabled. + This parameter can be a value of @ref DAC_buffer_switch */ +}DAC_InitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup DAC_Exported_Constants + * @{ + */ + +#define IS_DAC_ALL_PERIPH(PERIPH) (((PERIPH) == DAC1) || \ + ((PERIPH) == DAC2)) + +#define IS_DAC_LIST1_PERIPH(PERIPH) (((PERIPH) == DAC1)) + +/** @defgroup DAC_trigger_selection + * @{ + */ + +#define DAC_Trigger_None ((uint32_t)0x00000000) /*!< Conversion is automatic once the DAC1_DHRxxxx register + has been loaded, and not by external trigger */ +#define DAC_Trigger_T6_TRGO ((uint32_t)0x00000004) /*!< TIM6 TRGO selected as external conversion trigger for DAC1/2 channel1/2 */ +#define DAC_Trigger_T3_TRGO ((uint32_t)0x0000000C) /*!< TIM3 TRGO selected as external conversion trigger for DAC1/2 channel1/2 */ +#define DAC_Trigger_T8_TRGO ((uint32_t)0x0000000C) /*!< TIM8 TRGO selected as external conversion trigger for DAC1 channel1/2 */ +#define DAC_Trigger_T7_TRGO ((uint32_t)0x00000014) /*!< TIM7 TRGO selected as external conversion trigger for DAC1/2 channel1/2 */ +#define DAC_Trigger_T15_TRGO ((uint32_t)0x0000001C) /*!< TIM15 TRGO selected as external conversion trigger for DAC1/2 channel1/2 */ +#define DAC_Trigger_HRTIM1_DACTRG1 ((uint32_t)0x0000001C) /*!< HRTIM1 DACTRG1 selected as external conversion trigger for DAC1 channel1/2 */ +#define DAC_Trigger_T2_TRGO ((uint32_t)0x00000024) /*!< TIM2 TRGO selected as external conversion trigger for DAC1/2 channel1/2 */ +#define DAC_Trigger_T4_TRGO ((uint32_t)0x0000002C) /*!< TIM4 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_HRTIM1_DACTRG2 ((uint32_t)0x0000002C) /*!< HRTIM1 DACTRG2 selected as external conversion trigger for DAC1 channel1/2 */ +#define DAC_Trigger_HRTIM1_DACTRG3 ((uint32_t)0x0000002C) /*!< HRTIM1 DACTRG3 selected as external conversion trigger for DAC2 channel1 */ +#define DAC_Trigger_Ext_IT9 ((uint32_t)0x00000034) /*!< EXTI Line9 event selected as external conversion trigger for DAC1/2 channel1/2 */ +#define DAC_Trigger_Software ((uint32_t)0x0000003C) /*!< Conversion started by software trigger for DAC1/2 channel1/2 */ + +#define IS_DAC_TRIGGER(TRIGGER) (((TRIGGER) == DAC_Trigger_None) || \ + ((TRIGGER) == DAC_Trigger_T6_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T3_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T8_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T7_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T15_TRGO) || \ + ((TRIGGER) == DAC_Trigger_HRTIM1_DACTRG1)|| \ + ((TRIGGER) == DAC_Trigger_T2_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T4_TRGO) || \ + ((TRIGGER) == DAC_Trigger_HRTIM1_DACTRG2)|| \ + ((TRIGGER) == DAC_Trigger_HRTIM1_DACTRG3)|| \ + ((TRIGGER) == DAC_Trigger_Ext_IT9) || \ + ((TRIGGER) == DAC_Trigger_Software)) + +/** + * @} + */ + +/** @defgroup DAC_wave_generation + * @{ + */ + +#define DAC_WaveGeneration_None ((uint32_t)0x00000000) +#define DAC_WaveGeneration_Noise ((uint32_t)0x00000040) +#define DAC_WaveGeneration_Triangle ((uint32_t)0x00000080) + +#define IS_DAC_GENERATE_WAVE(WAVE) (((WAVE) == DAC_WaveGeneration_None) || \ + ((WAVE) == DAC_WaveGeneration_Noise) || \ + ((WAVE) == DAC_WaveGeneration_Triangle)) +/** + * @} + */ + +/** @defgroup DAC_lfsrunmask_triangleamplitude + * @{ + */ + +#define DAC_LFSRUnmask_Bit0 ((uint32_t)0x00000000) /*!< Unmask DAC channel LFSR bit0 for noise wave generation */ +#define DAC_LFSRUnmask_Bits1_0 ((uint32_t)0x00000100) /*!< Unmask DAC channel LFSR bit[1:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits2_0 ((uint32_t)0x00000200) /*!< Unmask DAC channel LFSR bit[2:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits3_0 ((uint32_t)0x00000300) /*!< Unmask DAC channel LFSR bit[3:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits4_0 ((uint32_t)0x00000400) /*!< Unmask DAC channel LFSR bit[4:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits5_0 ((uint32_t)0x00000500) /*!< Unmask DAC channel LFSR bit[5:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits6_0 ((uint32_t)0x00000600) /*!< Unmask DAC channel LFSR bit[6:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits7_0 ((uint32_t)0x00000700) /*!< Unmask DAC channel LFSR bit[7:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits8_0 ((uint32_t)0x00000800) /*!< Unmask DAC channel LFSR bit[8:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits9_0 ((uint32_t)0x00000900) /*!< Unmask DAC channel LFSR bit[9:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits10_0 ((uint32_t)0x00000A00) /*!< Unmask DAC channel LFSR bit[10:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits11_0 ((uint32_t)0x00000B00) /*!< Unmask DAC channel LFSR bit[11:0] for noise wave generation */ +#define DAC_TriangleAmplitude_1 ((uint32_t)0x00000000) /*!< Select max triangle amplitude of 1 */ +#define DAC_TriangleAmplitude_3 ((uint32_t)0x00000100) /*!< Select max triangle amplitude of 3 */ +#define DAC_TriangleAmplitude_7 ((uint32_t)0x00000200) /*!< Select max triangle amplitude of 7 */ +#define DAC_TriangleAmplitude_15 ((uint32_t)0x00000300) /*!< Select max triangle amplitude of 15 */ +#define DAC_TriangleAmplitude_31 ((uint32_t)0x00000400) /*!< Select max triangle amplitude of 31 */ +#define DAC_TriangleAmplitude_63 ((uint32_t)0x00000500) /*!< Select max triangle amplitude of 63 */ +#define DAC_TriangleAmplitude_127 ((uint32_t)0x00000600) /*!< Select max triangle amplitude of 127 */ +#define DAC_TriangleAmplitude_255 ((uint32_t)0x00000700) /*!< Select max triangle amplitude of 255 */ +#define DAC_TriangleAmplitude_511 ((uint32_t)0x00000800) /*!< Select max triangle amplitude of 511 */ +#define DAC_TriangleAmplitude_1023 ((uint32_t)0x00000900) /*!< Select max triangle amplitude of 1023 */ +#define DAC_TriangleAmplitude_2047 ((uint32_t)0x00000A00) /*!< Select max triangle amplitude of 2047 */ +#define DAC_TriangleAmplitude_4095 ((uint32_t)0x00000B00) /*!< Select max triangle amplitude of 4095 */ + +#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE) (((VALUE) == DAC_LFSRUnmask_Bit0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits1_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits2_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits3_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits4_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits5_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits6_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits7_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits8_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits9_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits10_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits11_0) || \ + ((VALUE) == DAC_TriangleAmplitude_1) || \ + ((VALUE) == DAC_TriangleAmplitude_3) || \ + ((VALUE) == DAC_TriangleAmplitude_7) || \ + ((VALUE) == DAC_TriangleAmplitude_15) || \ + ((VALUE) == DAC_TriangleAmplitude_31) || \ + ((VALUE) == DAC_TriangleAmplitude_63) || \ + ((VALUE) == DAC_TriangleAmplitude_127) || \ + ((VALUE) == DAC_TriangleAmplitude_255) || \ + ((VALUE) == DAC_TriangleAmplitude_511) || \ + ((VALUE) == DAC_TriangleAmplitude_1023) || \ + ((VALUE) == DAC_TriangleAmplitude_2047) || \ + ((VALUE) == DAC_TriangleAmplitude_4095)) +/** + * @} + */ + +/** @defgroup DAC_buffer_switch + * @{ + */ + +#define DAC_BufferSwitch_Disable ((uint32_t)0x00000000) +#define DAC_BufferSwitch_Enable ((uint32_t)0x00000002) + +#define IS_DAC_BUFFER_SWITCH_STATE(STATE) (((STATE) == DAC_BufferSwitch_Enable) || \ + ((STATE) == DAC_BufferSwitch_Disable)) +/** + * @} + */ + +/** @defgroup DAC_Channel_selection + * @{ + */ +#define DAC_Channel_1 ((uint32_t)0x00000000) +#define DAC_Channel_2 ((uint32_t)0x00000010) + +#define IS_DAC_CHANNEL(CHANNEL) (((CHANNEL) == DAC_Channel_1) || \ + ((CHANNEL) == DAC_Channel_2)) +/** + * @} + */ + +/** @defgroup DAC_data_alignement + * @{ + */ + +#define DAC_Align_12b_R ((uint32_t)0x00000000) +#define DAC_Align_12b_L ((uint32_t)0x00000004) +#define DAC_Align_8b_R ((uint32_t)0x00000008) + +#define IS_DAC_ALIGN(ALIGN) (((ALIGN) == DAC_Align_12b_R) || \ + ((ALIGN) == DAC_Align_12b_L) || \ + ((ALIGN) == DAC_Align_8b_R)) +/** + * @} + */ + +/** @defgroup DAC_wave_generation + * @{ + */ + +#define DAC_Wave_Noise ((uint32_t)0x00000040) +#define DAC_Wave_Triangle ((uint32_t)0x00000080) + +#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_Wave_Noise) || \ + ((WAVE) == DAC_Wave_Triangle)) +/** + * @} + */ + +/** @defgroup DAC_data + * @{ + */ + +#define IS_DAC_DATA(DATA) ((DATA) <= 0xFFF0) +/** + * @} + */ + +/** @defgroup DAC_interrupts_definition + * @{ + */ +#define DAC_IT_DMAUDR ((uint32_t)0x00002000) +#define IS_DAC_IT(IT) (((IT) == DAC_IT_DMAUDR)) + +/** + * @} + */ + +/** @defgroup DAC_flags_definition + * @{ + */ + +#define DAC_FLAG_DMAUDR ((uint32_t)0x00002000) +#define IS_DAC_FLAG(FLAG) (((FLAG) == DAC_FLAG_DMAUDR)) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Function used to set the DAC configuration to the default reset state *****/ +void DAC_DeInit(DAC_TypeDef* DACx); + +/* DAC channels configuration: trigger, output buffer, data format functions */ +void DAC_Init(DAC_TypeDef* DACx, uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct); +void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct); +void DAC_Cmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, FunctionalState NewState); +void DAC_SoftwareTriggerCmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, FunctionalState NewState); +void DAC_DualSoftwareTriggerCmd(DAC_TypeDef* DACx, FunctionalState NewState); +void DAC_WaveGenerationCmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState); +void DAC_SetChannel1Data(DAC_TypeDef* DACx, uint32_t DAC_Align, uint16_t Data); +void DAC_SetChannel2Data(DAC_TypeDef* DACx, uint32_t DAC_Align, uint16_t Data); +void DAC_SetDualChannelData(DAC_TypeDef* DACx, uint32_t DAC_Align, uint16_t Data2, uint16_t Data1); +uint16_t DAC_GetDataOutputValue(DAC_TypeDef* DACx, uint32_t DAC_Channel); + +/* DMA management functions ***************************************************/ +void DAC_DMACmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, FunctionalState NewState); + +/* Interrupts and flags management functions **********************************/ +void DAC_ITConfig(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState); +FlagStatus DAC_GetFlagStatus(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_FLAG); +void DAC_ClearFlag(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_FLAG); +ITStatus DAC_GetITStatus(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_IT); +void DAC_ClearITPendingBit(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F30x_DAC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_dbgmcu.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_dbgmcu.h new file mode 100644 index 0000000..f518236 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_dbgmcu.h @@ -0,0 +1,108 @@ +/** + ****************************************************************************** + * @file stm32f30x_dbgmcu.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the DBGMCU firmware library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_DBGMCU_H +#define __STM32F30x_DBGMCU_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DBGMCU + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup DBGMCU_Exported_Constants + * @{ + */ +#define DBGMCU_SLEEP ((uint32_t)0x00000001) +#define DBGMCU_STOP ((uint32_t)0x00000002) +#define DBGMCU_STANDBY ((uint32_t)0x00000004) +#define IS_DBGMCU_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFFF8) == 0x00) && ((PERIPH) != 0x00)) + +#define DBGMCU_TIM2_STOP ((uint32_t)0x00000001) +#define DBGMCU_TIM3_STOP ((uint32_t)0x00000002) +#define DBGMCU_TIM4_STOP ((uint32_t)0x00000004) +#define DBGMCU_TIM6_STOP ((uint32_t)0x00000010) +#define DBGMCU_TIM7_STOP ((uint32_t)0x00000020) +#define DBGMCU_RTC_STOP ((uint32_t)0x00000400) +#define DBGMCU_WWDG_STOP ((uint32_t)0x00000800) +#define DBGMCU_IWDG_STOP ((uint32_t)0x00001000) +#define DBGMCU_I2C1_SMBUS_TIMEOUT ((uint32_t)0x00200000) +#define DBGMCU_I2C2_SMBUS_TIMEOUT ((uint32_t)0x00400000) +#define DBGMCU_CAN1_STOP ((uint32_t)0x02000000) + +#define IS_DBGMCU_APB1PERIPH(PERIPH) ((((PERIPH) & 0xFD9FE3C8) == 0x00) && ((PERIPH) != 0x00)) + +#define DBGMCU_TIM1_STOP ((uint32_t)0x00000001) +#define DBGMCU_TIM8_STOP ((uint32_t)0x00000002) +#define DBGMCU_TIM15_STOP ((uint32_t)0x00000004) +#define DBGMCU_TIM16_STOP ((uint32_t)0x00000008) +#define DBGMCU_TIM17_STOP ((uint32_t)0x00000010) +#define IS_DBGMCU_APB2PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFFE0) == 0x00) && ((PERIPH) != 0x00)) + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ +/* Device and Revision ID management functions ********************************/ +uint32_t DBGMCU_GetREVID(void); +uint32_t DBGMCU_GetDEVID(void); + +/* Peripherals Configuration functions ****************************************/ +void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState); +void DBGMCU_APB1PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState); +void DBGMCU_APB2PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F30x_DBGMCU_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_dma.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_dma.h new file mode 100644 index 0000000..b63d0ab --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_dma.h @@ -0,0 +1,436 @@ +/** + ****************************************************************************** + * @file stm32f30x_dma.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the DMA firmware + * library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_DMA_H +#define __STM32F30x_DMA_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DMA + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief DMA Init structures definition + */ +typedef struct +{ + uint32_t DMA_PeripheralBaseAddr; /*!< Specifies the peripheral base address for DMAy Channelx. */ + + uint32_t DMA_MemoryBaseAddr; /*!< Specifies the memory base address for DMAy Channelx. */ + + uint32_t DMA_DIR; /*!< Specifies if the peripheral is the source or destination. + This parameter can be a value of @ref DMA_data_transfer_direction */ + + uint16_t DMA_BufferSize; /*!< Specifies the buffer size, in data unit, of the specified Channel. + The data unit is equal to the configuration set in DMA_PeripheralDataSize + or DMA_MemoryDataSize members depending in the transfer direction. */ + + uint32_t DMA_PeripheralInc; /*!< Specifies whether the Peripheral address register is incremented or not. + This parameter can be a value of @ref DMA_peripheral_incremented_mode */ + + uint32_t DMA_MemoryInc; /*!< Specifies whether the memory address register is incremented or not. + This parameter can be a value of @ref DMA_memory_incremented_mode */ + + uint32_t DMA_PeripheralDataSize; /*!< Specifies the Peripheral data width. + This parameter can be a value of @ref DMA_peripheral_data_size */ + + uint32_t DMA_MemoryDataSize; /*!< Specifies the Memory data width. + This parameter can be a value of @ref DMA_memory_data_size */ + + uint32_t DMA_Mode; /*!< Specifies the operation mode of the DMAy Channelx. + This parameter can be a value of @ref DMA_circular_normal_mode + @note: The circular buffer mode cannot be used if the memory-to-memory + data transfer is configured on the selected Channel */ + + uint32_t DMA_Priority; /*!< Specifies the software priority for the DMAy Channelx. + This parameter can be a value of @ref DMA_priority_level */ + + uint32_t DMA_M2M; /*!< Specifies if the DMAy Channelx will be used in memory-to-memory transfer. + This parameter can be a value of @ref DMA_memory_to_memory */ +}DMA_InitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup DMA_Exported_Constants + * @{ + */ + +#define IS_DMA_ALL_PERIPH(PERIPH) (((PERIPH) == DMA1_Channel1) || \ + ((PERIPH) == DMA1_Channel2) || \ + ((PERIPH) == DMA1_Channel3) || \ + ((PERIPH) == DMA1_Channel4) || \ + ((PERIPH) == DMA1_Channel5) || \ + ((PERIPH) == DMA1_Channel6) || \ + ((PERIPH) == DMA1_Channel7) || \ + ((PERIPH) == DMA2_Channel1) || \ + ((PERIPH) == DMA2_Channel2) || \ + ((PERIPH) == DMA2_Channel3) || \ + ((PERIPH) == DMA2_Channel4) || \ + ((PERIPH) == DMA2_Channel5)) + +/** @defgroup DMA_data_transfer_direction + * @{ + */ + +#define DMA_DIR_PeripheralSRC ((uint32_t)0x00000000) +#define DMA_DIR_PeripheralDST DMA_CCR_DIR + +#define IS_DMA_DIR(DIR) (((DIR) == DMA_DIR_PeripheralSRC) || \ + ((DIR) == DMA_DIR_PeripheralDST)) +/** + * @} + */ + + +/** @defgroup DMA_peripheral_incremented_mode + * @{ + */ + +#define DMA_PeripheralInc_Disable ((uint32_t)0x00000000) +#define DMA_PeripheralInc_Enable DMA_CCR_PINC + +#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PeripheralInc_Disable) || \ + ((STATE) == DMA_PeripheralInc_Enable)) +/** + * @} + */ + +/** @defgroup DMA_memory_incremented_mode + * @{ + */ + +#define DMA_MemoryInc_Disable ((uint32_t)0x00000000) +#define DMA_MemoryInc_Enable DMA_CCR_MINC + +#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MemoryInc_Disable) || \ + ((STATE) == DMA_MemoryInc_Enable)) +/** + * @} + */ + +/** @defgroup DMA_peripheral_data_size + * @{ + */ + +#define DMA_PeripheralDataSize_Byte ((uint32_t)0x00000000) +#define DMA_PeripheralDataSize_HalfWord DMA_CCR_PSIZE_0 +#define DMA_PeripheralDataSize_Word DMA_CCR_PSIZE_1 + +#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PeripheralDataSize_Byte) || \ + ((SIZE) == DMA_PeripheralDataSize_HalfWord) || \ + ((SIZE) == DMA_PeripheralDataSize_Word)) +/** + * @} + */ + +/** @defgroup DMA_memory_data_size + * @{ + */ + +#define DMA_MemoryDataSize_Byte ((uint32_t)0x00000000) +#define DMA_MemoryDataSize_HalfWord DMA_CCR_MSIZE_0 +#define DMA_MemoryDataSize_Word DMA_CCR_MSIZE_1 + +#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MemoryDataSize_Byte) || \ + ((SIZE) == DMA_MemoryDataSize_HalfWord) || \ + ((SIZE) == DMA_MemoryDataSize_Word)) +/** + * @} + */ + +/** @defgroup DMA_circular_normal_mode + * @{ + */ + +#define DMA_Mode_Normal ((uint32_t)0x00000000) +#define DMA_Mode_Circular DMA_CCR_CIRC + +#define IS_DMA_MODE(MODE) (((MODE) == DMA_Mode_Normal) || ((MODE) == DMA_Mode_Circular)) +/** + * @} + */ + +/** @defgroup DMA_priority_level + * @{ + */ + +#define DMA_Priority_VeryHigh DMA_CCR_PL +#define DMA_Priority_High DMA_CCR_PL_1 +#define DMA_Priority_Medium DMA_CCR_PL_0 +#define DMA_Priority_Low ((uint32_t)0x00000000) + +#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_Priority_VeryHigh) || \ + ((PRIORITY) == DMA_Priority_High) || \ + ((PRIORITY) == DMA_Priority_Medium) || \ + ((PRIORITY) == DMA_Priority_Low)) +/** + * @} + */ + +/** @defgroup DMA_memory_to_memory + * @{ + */ + +#define DMA_M2M_Disable ((uint32_t)0x00000000) +#define DMA_M2M_Enable DMA_CCR_MEM2MEM + +#define IS_DMA_M2M_STATE(STATE) (((STATE) == DMA_M2M_Disable) || ((STATE) == DMA_M2M_Enable)) + +/** + * @} + */ + +/** @defgroup DMA_interrupts_definition + * @{ + */ + +#define DMA_IT_TC ((uint32_t)0x00000002) +#define DMA_IT_HT ((uint32_t)0x00000004) +#define DMA_IT_TE ((uint32_t)0x00000008) +#define IS_DMA_CONFIG_IT(IT) ((((IT) & 0xFFFFFFF1) == 0x00) && ((IT) != 0x00)) + +#define DMA1_IT_GL1 ((uint32_t)0x00000001) +#define DMA1_IT_TC1 ((uint32_t)0x00000002) +#define DMA1_IT_HT1 ((uint32_t)0x00000004) +#define DMA1_IT_TE1 ((uint32_t)0x00000008) +#define DMA1_IT_GL2 ((uint32_t)0x00000010) +#define DMA1_IT_TC2 ((uint32_t)0x00000020) +#define DMA1_IT_HT2 ((uint32_t)0x00000040) +#define DMA1_IT_TE2 ((uint32_t)0x00000080) +#define DMA1_IT_GL3 ((uint32_t)0x00000100) +#define DMA1_IT_TC3 ((uint32_t)0x00000200) +#define DMA1_IT_HT3 ((uint32_t)0x00000400) +#define DMA1_IT_TE3 ((uint32_t)0x00000800) +#define DMA1_IT_GL4 ((uint32_t)0x00001000) +#define DMA1_IT_TC4 ((uint32_t)0x00002000) +#define DMA1_IT_HT4 ((uint32_t)0x00004000) +#define DMA1_IT_TE4 ((uint32_t)0x00008000) +#define DMA1_IT_GL5 ((uint32_t)0x00010000) +#define DMA1_IT_TC5 ((uint32_t)0x00020000) +#define DMA1_IT_HT5 ((uint32_t)0x00040000) +#define DMA1_IT_TE5 ((uint32_t)0x00080000) +#define DMA1_IT_GL6 ((uint32_t)0x00100000) +#define DMA1_IT_TC6 ((uint32_t)0x00200000) +#define DMA1_IT_HT6 ((uint32_t)0x00400000) +#define DMA1_IT_TE6 ((uint32_t)0x00800000) +#define DMA1_IT_GL7 ((uint32_t)0x01000000) +#define DMA1_IT_TC7 ((uint32_t)0x02000000) +#define DMA1_IT_HT7 ((uint32_t)0x04000000) +#define DMA1_IT_TE7 ((uint32_t)0x08000000) + +#define DMA2_IT_GL1 ((uint32_t)0x10000001) +#define DMA2_IT_TC1 ((uint32_t)0x10000002) +#define DMA2_IT_HT1 ((uint32_t)0x10000004) +#define DMA2_IT_TE1 ((uint32_t)0x10000008) +#define DMA2_IT_GL2 ((uint32_t)0x10000010) +#define DMA2_IT_TC2 ((uint32_t)0x10000020) +#define DMA2_IT_HT2 ((uint32_t)0x10000040) +#define DMA2_IT_TE2 ((uint32_t)0x10000080) +#define DMA2_IT_GL3 ((uint32_t)0x10000100) +#define DMA2_IT_TC3 ((uint32_t)0x10000200) +#define DMA2_IT_HT3 ((uint32_t)0x10000400) +#define DMA2_IT_TE3 ((uint32_t)0x10000800) +#define DMA2_IT_GL4 ((uint32_t)0x10001000) +#define DMA2_IT_TC4 ((uint32_t)0x10002000) +#define DMA2_IT_HT4 ((uint32_t)0x10004000) +#define DMA2_IT_TE4 ((uint32_t)0x10008000) +#define DMA2_IT_GL5 ((uint32_t)0x10010000) +#define DMA2_IT_TC5 ((uint32_t)0x10020000) +#define DMA2_IT_HT5 ((uint32_t)0x10040000) +#define DMA2_IT_TE5 ((uint32_t)0x10080000) + +#define IS_DMA_CLEAR_IT(IT) (((((IT) & 0xF0000000) == 0x00) || (((IT) & 0xEFF00000) == 0x00)) && ((IT) != 0x00)) + +#define IS_DMA_GET_IT(IT) (((IT) == DMA1_IT_GL1) || ((IT) == DMA1_IT_TC1) || \ + ((IT) == DMA1_IT_HT1) || ((IT) == DMA1_IT_TE1) || \ + ((IT) == DMA1_IT_GL2) || ((IT) == DMA1_IT_TC2) || \ + ((IT) == DMA1_IT_HT2) || ((IT) == DMA1_IT_TE2) || \ + ((IT) == DMA1_IT_GL3) || ((IT) == DMA1_IT_TC3) || \ + ((IT) == DMA1_IT_HT3) || ((IT) == DMA1_IT_TE3) || \ + ((IT) == DMA1_IT_GL4) || ((IT) == DMA1_IT_TC4) || \ + ((IT) == DMA1_IT_HT4) || ((IT) == DMA1_IT_TE4) || \ + ((IT) == DMA1_IT_GL5) || ((IT) == DMA1_IT_TC5) || \ + ((IT) == DMA1_IT_HT5) || ((IT) == DMA1_IT_TE5) || \ + ((IT) == DMA1_IT_GL6) || ((IT) == DMA1_IT_TC6) || \ + ((IT) == DMA1_IT_HT6) || ((IT) == DMA1_IT_TE6) || \ + ((IT) == DMA1_IT_GL7) || ((IT) == DMA1_IT_TC7) || \ + ((IT) == DMA1_IT_HT7) || ((IT) == DMA1_IT_TE7) || \ + ((IT) == DMA2_IT_GL1) || ((IT) == DMA2_IT_TC1) || \ + ((IT) == DMA2_IT_HT1) || ((IT) == DMA2_IT_TE1) || \ + ((IT) == DMA2_IT_GL2) || ((IT) == DMA2_IT_TC2) || \ + ((IT) == DMA2_IT_HT2) || ((IT) == DMA2_IT_TE2) || \ + ((IT) == DMA2_IT_GL3) || ((IT) == DMA2_IT_TC3) || \ + ((IT) == DMA2_IT_HT3) || ((IT) == DMA2_IT_TE3) || \ + ((IT) == DMA2_IT_GL4) || ((IT) == DMA2_IT_TC4) || \ + ((IT) == DMA2_IT_HT4) || ((IT) == DMA2_IT_TE4) || \ + ((IT) == DMA2_IT_GL5) || ((IT) == DMA2_IT_TC5) || \ + ((IT) == DMA2_IT_HT5) || ((IT) == DMA2_IT_TE5)) + +/** + * @} + */ + +/** @defgroup DMA_flags_definition + * @{ + */ + +#define DMA1_FLAG_GL1 ((uint32_t)0x00000001) +#define DMA1_FLAG_TC1 ((uint32_t)0x00000002) +#define DMA1_FLAG_HT1 ((uint32_t)0x00000004) +#define DMA1_FLAG_TE1 ((uint32_t)0x00000008) +#define DMA1_FLAG_GL2 ((uint32_t)0x00000010) +#define DMA1_FLAG_TC2 ((uint32_t)0x00000020) +#define DMA1_FLAG_HT2 ((uint32_t)0x00000040) +#define DMA1_FLAG_TE2 ((uint32_t)0x00000080) +#define DMA1_FLAG_GL3 ((uint32_t)0x00000100) +#define DMA1_FLAG_TC3 ((uint32_t)0x00000200) +#define DMA1_FLAG_HT3 ((uint32_t)0x00000400) +#define DMA1_FLAG_TE3 ((uint32_t)0x00000800) +#define DMA1_FLAG_GL4 ((uint32_t)0x00001000) +#define DMA1_FLAG_TC4 ((uint32_t)0x00002000) +#define DMA1_FLAG_HT4 ((uint32_t)0x00004000) +#define DMA1_FLAG_TE4 ((uint32_t)0x00008000) +#define DMA1_FLAG_GL5 ((uint32_t)0x00010000) +#define DMA1_FLAG_TC5 ((uint32_t)0x00020000) +#define DMA1_FLAG_HT5 ((uint32_t)0x00040000) +#define DMA1_FLAG_TE5 ((uint32_t)0x00080000) +#define DMA1_FLAG_GL6 ((uint32_t)0x00100000) +#define DMA1_FLAG_TC6 ((uint32_t)0x00200000) +#define DMA1_FLAG_HT6 ((uint32_t)0x00400000) +#define DMA1_FLAG_TE6 ((uint32_t)0x00800000) +#define DMA1_FLAG_GL7 ((uint32_t)0x01000000) +#define DMA1_FLAG_TC7 ((uint32_t)0x02000000) +#define DMA1_FLAG_HT7 ((uint32_t)0x04000000) +#define DMA1_FLAG_TE7 ((uint32_t)0x08000000) + +#define DMA2_FLAG_GL1 ((uint32_t)0x10000001) +#define DMA2_FLAG_TC1 ((uint32_t)0x10000002) +#define DMA2_FLAG_HT1 ((uint32_t)0x10000004) +#define DMA2_FLAG_TE1 ((uint32_t)0x10000008) +#define DMA2_FLAG_GL2 ((uint32_t)0x10000010) +#define DMA2_FLAG_TC2 ((uint32_t)0x10000020) +#define DMA2_FLAG_HT2 ((uint32_t)0x10000040) +#define DMA2_FLAG_TE2 ((uint32_t)0x10000080) +#define DMA2_FLAG_GL3 ((uint32_t)0x10000100) +#define DMA2_FLAG_TC3 ((uint32_t)0x10000200) +#define DMA2_FLAG_HT3 ((uint32_t)0x10000400) +#define DMA2_FLAG_TE3 ((uint32_t)0x10000800) +#define DMA2_FLAG_GL4 ((uint32_t)0x10001000) +#define DMA2_FLAG_TC4 ((uint32_t)0x10002000) +#define DMA2_FLAG_HT4 ((uint32_t)0x10004000) +#define DMA2_FLAG_TE4 ((uint32_t)0x10008000) +#define DMA2_FLAG_GL5 ((uint32_t)0x10010000) +#define DMA2_FLAG_TC5 ((uint32_t)0x10020000) +#define DMA2_FLAG_HT5 ((uint32_t)0x10040000) +#define DMA2_FLAG_TE5 ((uint32_t)0x10080000) + +#define IS_DMA_CLEAR_FLAG(FLAG) (((((FLAG) & 0xF0000000) == 0x00) || (((FLAG) & 0xEFF00000) == 0x00)) && ((FLAG) != 0x00)) + +#define IS_DMA_GET_FLAG(FLAG) (((FLAG) == DMA1_FLAG_GL1) || ((FLAG) == DMA1_FLAG_TC1) || \ + ((FLAG) == DMA1_FLAG_HT1) || ((FLAG) == DMA1_FLAG_TE1) || \ + ((FLAG) == DMA1_FLAG_GL2) || ((FLAG) == DMA1_FLAG_TC2) || \ + ((FLAG) == DMA1_FLAG_HT2) || ((FLAG) == DMA1_FLAG_TE2) || \ + ((FLAG) == DMA1_FLAG_GL3) || ((FLAG) == DMA1_FLAG_TC3) || \ + ((FLAG) == DMA1_FLAG_HT3) || ((FLAG) == DMA1_FLAG_TE3) || \ + ((FLAG) == DMA1_FLAG_GL4) || ((FLAG) == DMA1_FLAG_TC4) || \ + ((FLAG) == DMA1_FLAG_HT4) || ((FLAG) == DMA1_FLAG_TE4) || \ + ((FLAG) == DMA1_FLAG_GL5) || ((FLAG) == DMA1_FLAG_TC5) || \ + ((FLAG) == DMA1_FLAG_HT5) || ((FLAG) == DMA1_FLAG_TE5) || \ + ((FLAG) == DMA1_FLAG_GL6) || ((FLAG) == DMA1_FLAG_TC6) || \ + ((FLAG) == DMA1_FLAG_HT6) || ((FLAG) == DMA1_FLAG_TE6) || \ + ((FLAG) == DMA1_FLAG_GL7) || ((FLAG) == DMA1_FLAG_TC7) || \ + ((FLAG) == DMA1_FLAG_HT7) || ((FLAG) == DMA1_FLAG_TE7) || \ + ((FLAG) == DMA2_FLAG_GL1) || ((FLAG) == DMA2_FLAG_TC1) || \ + ((FLAG) == DMA2_FLAG_HT1) || ((FLAG) == DMA2_FLAG_TE1) || \ + ((FLAG) == DMA2_FLAG_GL2) || ((FLAG) == DMA2_FLAG_TC2) || \ + ((FLAG) == DMA2_FLAG_HT2) || ((FLAG) == DMA2_FLAG_TE2) || \ + ((FLAG) == DMA2_FLAG_GL3) || ((FLAG) == DMA2_FLAG_TC3) || \ + ((FLAG) == DMA2_FLAG_HT3) || ((FLAG) == DMA2_FLAG_TE3) || \ + ((FLAG) == DMA2_FLAG_GL4) || ((FLAG) == DMA2_FLAG_TC4) || \ + ((FLAG) == DMA2_FLAG_HT4) || ((FLAG) == DMA2_FLAG_TE4) || \ + ((FLAG) == DMA2_FLAG_GL5) || ((FLAG) == DMA2_FLAG_TC5) || \ + ((FLAG) == DMA2_FLAG_HT5) || ((FLAG) == DMA2_FLAG_TE5)) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +/* Function used to set the DMA configuration to the default reset state ******/ +void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx); + +/* Initialization and Configuration functions *********************************/ +void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct); +void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct); +void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState); + +/* Data Counter functions******************************************************/ +void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber); +uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx); + +/* Interrupts and flags management functions **********************************/ +void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState); +FlagStatus DMA_GetFlagStatus(uint32_t DMAy_FLAG); +void DMA_ClearFlag(uint32_t DMAy_FLAG); +ITStatus DMA_GetITStatus(uint32_t DMAy_IT); +void DMA_ClearITPendingBit(uint32_t DMAy_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F30x_DMA_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_exti.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_exti.h new file mode 100644 index 0000000..ed1f0c2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_exti.h @@ -0,0 +1,234 @@ +/** + ****************************************************************************** + * @file stm32f30x_exti.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the EXTI + * firmware library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_EXTI_H +#define __STM32F30x_EXTI_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup EXTI + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief EXTI mode enumeration + */ + +typedef enum +{ + EXTI_Mode_Interrupt = 0x00, + EXTI_Mode_Event = 0x04 +}EXTIMode_TypeDef; + +#define IS_EXTI_MODE(MODE) (((MODE) == EXTI_Mode_Interrupt) || ((MODE) == EXTI_Mode_Event)) + +/** + * @brief EXTI Trigger enumeration + */ + +typedef enum +{ + EXTI_Trigger_Rising = 0x08, + EXTI_Trigger_Falling = 0x0C, + EXTI_Trigger_Rising_Falling = 0x10 +}EXTITrigger_TypeDef; + +#define IS_EXTI_TRIGGER(TRIGGER) (((TRIGGER) == EXTI_Trigger_Rising) || \ + ((TRIGGER) == EXTI_Trigger_Falling) || \ + ((TRIGGER) == EXTI_Trigger_Rising_Falling)) +/** + * @brief EXTI Init Structure definition + */ + +typedef struct +{ + uint32_t EXTI_Line; /*!< Specifies the EXTI lines to be enabled or disabled. + This parameter can be any combination of @ref EXTI_Lines */ + + EXTIMode_TypeDef EXTI_Mode; /*!< Specifies the mode for the EXTI lines. + This parameter can be a value of @ref EXTIMode_TypeDef */ + + EXTITrigger_TypeDef EXTI_Trigger; /*!< Specifies the trigger signal active edge for the EXTI lines. + This parameter can be a value of @ref EXTITrigger_TypeDef */ + + FunctionalState EXTI_LineCmd; /*!< Specifies the new state of the selected EXTI lines. + This parameter can be set either to ENABLE or DISABLE */ +}EXTI_InitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup EXTI_Exported_Constants + * @{ + */ +/** @defgroup EXTI_Lines + * @{ + */ + +#define EXTI_Line0 ((uint32_t)0x00) /*!< External interrupt line 0 */ +#define EXTI_Line1 ((uint32_t)0x01) /*!< External interrupt line 1 */ +#define EXTI_Line2 ((uint32_t)0x02) /*!< External interrupt line 2 */ +#define EXTI_Line3 ((uint32_t)0x03) /*!< External interrupt line 3 */ +#define EXTI_Line4 ((uint32_t)0x04) /*!< External interrupt line 4 */ +#define EXTI_Line5 ((uint32_t)0x05) /*!< External interrupt line 5 */ +#define EXTI_Line6 ((uint32_t)0x06) /*!< External interrupt line 6 */ +#define EXTI_Line7 ((uint32_t)0x07) /*!< External interrupt line 7 */ +#define EXTI_Line8 ((uint32_t)0x08) /*!< External interrupt line 8 */ +#define EXTI_Line9 ((uint32_t)0x09) /*!< External interrupt line 9 */ +#define EXTI_Line10 ((uint32_t)0x0A) /*!< External interrupt line 10 */ +#define EXTI_Line11 ((uint32_t)0x0B) /*!< External interrupt line 11 */ +#define EXTI_Line12 ((uint32_t)0x0C) /*!< External interrupt line 12 */ +#define EXTI_Line13 ((uint32_t)0x0D) /*!< External interrupt line 13 */ +#define EXTI_Line14 ((uint32_t)0x0E) /*!< External interrupt line 14 */ +#define EXTI_Line15 ((uint32_t)0x0F) /*!< External interrupt line 15 */ +#define EXTI_Line16 ((uint32_t)0x10) /*!< External interrupt line 16 + Connected to the PVD Output */ +#define EXTI_Line17 ((uint32_t)0x11) /*!< Internal interrupt line 17 + Connected to the RTC Alarm + event */ +#define EXTI_Line18 ((uint32_t)0x12) /*!< Internal interrupt line 18 + Connected to the USB Device + Wakeup from suspend event */ +#define EXTI_Line19 ((uint32_t)0x13) /*!< Internal interrupt line 19 + Connected to the RTC Tamper + and Time Stamp events */ +#define EXTI_Line20 ((uint32_t)0x14) /*!< Internal interrupt line 20 + Connected to the RTC wakeup + event */ +#define EXTI_Line21 ((uint32_t)0x15) /*!< Internal interrupt line 21 + Connected to the Comparator 1 + event */ +#define EXTI_Line22 ((uint32_t)0x16) /*!< Internal interrupt line 22 + Connected to the Comparator 2 + event */ +#define EXTI_Line23 ((uint32_t)0x17) /*!< Internal interrupt line 23 + Connected to the I2C1 wakeup + event */ +#define EXTI_Line24 ((uint32_t)0x18) /*!< Internal interrupt line 24 + Connected to the I2C2 wakeup + event */ +#define EXTI_Line25 ((uint32_t)0x19) /*!< Internal interrupt line 25 + Connected to the USART1 wakeup + event */ +#define EXTI_Line26 ((uint32_t)0x1A) /*!< Internal interrupt line 26 + Connected to the USART2 wakeup + event */ +#define EXTI_Line27 ((uint32_t)0x1B) /*!< Internal interrupt line 27 + reserved */ +#define EXTI_Line28 ((uint32_t)0x1C) /*!< Internal interrupt line 28 + Connected to the USART3 wakeup + event */ +#define EXTI_Line29 ((uint32_t)0x1D) /*!< Internal interrupt line 29 + Connected to the Comparator 3 + event */ +#define EXTI_Line30 ((uint32_t)0x1E) /*!< Internal interrupt line 30 + Connected to the Comparator 4 + event */ +#define EXTI_Line31 ((uint32_t)0x1F) /*!< Internal interrupt line 31 + Connected to the Comparator 5 + event */ +#define EXTI_Line32 ((uint32_t)0x20) /*!< Internal interrupt line 32 + Connected to the Comparator 6 + event */ +#define EXTI_Line33 ((uint32_t)0x21) /*!< Internal interrupt line 33 + Connected to the Comparator 7 + event */ +#define EXTI_Line34 ((uint32_t)0x22) /*!< Internal interrupt line 34 + Connected to the USART4 wakeup + event */ +#define EXTI_Line35 ((uint32_t)0x23) /*!< Internal interrupt line 35 + Connected to the USART5 wakeup + event */ + +#define IS_EXTI_LINE_ALL(LINE) ((LINE) <= 0x23) +#define IS_EXTI_LINE_EXT(LINE) (((LINE) <= 0x16) || (((LINE) == EXTI_Line29) || ((LINE) == EXTI_Line30) || \ + ((LINE) == EXTI_Line31) || ((LINE) == EXTI_Line32) || ((LINE) == EXTI_Line33))) + +#define IS_GET_EXTI_LINE(LINE) (((LINE) == EXTI_Line0) || ((LINE) == EXTI_Line1) || \ + ((LINE) == EXTI_Line2) || ((LINE) == EXTI_Line3) || \ + ((LINE) == EXTI_Line4) || ((LINE) == EXTI_Line5) || \ + ((LINE) == EXTI_Line6) || ((LINE) == EXTI_Line7) || \ + ((LINE) == EXTI_Line8) || ((LINE) == EXTI_Line9) || \ + ((LINE) == EXTI_Line10) || ((LINE) == EXTI_Line11) || \ + ((LINE) == EXTI_Line12) || ((LINE) == EXTI_Line13) || \ + ((LINE) == EXTI_Line14) || ((LINE) == EXTI_Line15) || \ + ((LINE) == EXTI_Line16) || ((LINE) == EXTI_Line17) || \ + ((LINE) == EXTI_Line18) || ((LINE) == EXTI_Line19) || \ + ((LINE) == EXTI_Line20) || ((LINE) == EXTI_Line21) || \ + ((LINE) == EXTI_Line22) || ((LINE) == EXTI_Line29) || \ + ((LINE) == EXTI_Line30) || ((LINE) == EXTI_Line31) || \ + ((LINE) == EXTI_Line32) || ((LINE) == EXTI_Line33)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +/* Function used to set the EXTI configuration to the default reset state *****/ +void EXTI_DeInit(void); + +/* Initialization and Configuration functions *********************************/ +void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct); +void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct); +void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line); + +/* Interrupts and flags management functions **********************************/ +FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line); +void EXTI_ClearFlag(uint32_t EXTI_Line); +ITStatus EXTI_GetITStatus(uint32_t EXTI_Line); +void EXTI_ClearITPendingBit(uint32_t EXTI_Line); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F30x_EXTI_H */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_flash.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_flash.h new file mode 100644 index 0000000..af988f0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_flash.h @@ -0,0 +1,329 @@ +/** + ****************************************************************************** + * @file stm32f30x_flash.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the FLASH + * firmware library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_FLASH_H +#define __STM32F30x_FLASH_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup FLASH + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/** + * @brief FLASH Status + */ +typedef enum +{ + FLASH_BUSY = 1, + FLASH_ERROR_WRP, + FLASH_ERROR_PROGRAM, + FLASH_COMPLETE, + FLASH_TIMEOUT +}FLASH_Status; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup FLASH_Exported_Constants + * @{ + */ + +/** @defgroup Flash_Latency + * @{ + */ +#define FLASH_Latency_0 ((uint8_t)0x0000) /*!< FLASH Zero Latency cycle */ +#define FLASH_Latency_1 FLASH_ACR_LATENCY_0 /*!< FLASH One Latency cycle */ +#define FLASH_Latency_2 FLASH_ACR_LATENCY_1 /*!< FLASH Two Latency cycles */ + +#define IS_FLASH_LATENCY(LATENCY) (((LATENCY) == FLASH_Latency_0) || \ + ((LATENCY) == FLASH_Latency_1) || \ + ((LATENCY) == FLASH_Latency_2)) +/** + * @} + */ + +/** @defgroup FLASH_Interrupts + * @{ + */ + +#define FLASH_IT_EOP FLASH_CR_EOPIE /*!< End of programming interrupt source */ +#define FLASH_IT_ERR FLASH_CR_ERRIE /*!< Error interrupt source */ +#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0xFFFFEBFF) == 0x00000000) && (((IT) != 0x00000000))) +/** + * @} + */ +/** @defgroup FLASH_Address + * @{ + */ + +#define IS_FLASH_PROGRAM_ADDRESS(ADDRESS) (((ADDRESS) >= 0x08000000) && ((ADDRESS) <= 0x0803FFFF)) + +/** + * @} + */ + +/** @defgroup FLASH_OB_DATA_ADDRESS + * @{ + */ +#define IS_OB_DATA_ADDRESS(ADDRESS) (((ADDRESS) == 0x1FFFF804) || ((ADDRESS) == 0x1FFFF806)) + +/** + * @} + */ + +/** @defgroup Option_Bytes_Write_Protection + * @{ + */ + +#define OB_WRP_Pages0to1 ((uint32_t)0x00000001) /* Write protection of page 0 to 1 */ +#define OB_WRP_Pages2to3 ((uint32_t)0x00000002) /* Write protection of page 2 to 3 */ +#define OB_WRP_Pages4to5 ((uint32_t)0x00000004) /* Write protection of page 4 to 5 */ +#define OB_WRP_Pages6to7 ((uint32_t)0x00000008) /* Write protection of page 6 to 7 */ +#define OB_WRP_Pages8to9 ((uint32_t)0x00000010) /* Write protection of page 8 to 9 */ +#define OB_WRP_Pages10to11 ((uint32_t)0x00000020) /* Write protection of page 10 to 11 */ +#define OB_WRP_Pages12to13 ((uint32_t)0x00000040) /* Write protection of page 12 to 13 */ +#define OB_WRP_Pages14to15 ((uint32_t)0x00000080) /* Write protection of page 14 to 15 */ +#define OB_WRP_Pages16to17 ((uint32_t)0x00000100) /* Write protection of page 16 to 17 */ +#define OB_WRP_Pages18to19 ((uint32_t)0x00000200) /* Write protection of page 18 to 19 */ +#define OB_WRP_Pages20to21 ((uint32_t)0x00000400) /* Write protection of page 20 to 21 */ +#define OB_WRP_Pages22to23 ((uint32_t)0x00000800) /* Write protection of page 22 to 23 */ +#define OB_WRP_Pages24to25 ((uint32_t)0x00001000) /* Write protection of page 24 to 25 */ +#define OB_WRP_Pages26to27 ((uint32_t)0x00002000) /* Write protection of page 26 to 27 */ +#define OB_WRP_Pages28to29 ((uint32_t)0x00004000) /* Write protection of page 28 to 29 */ +#define OB_WRP_Pages30to31 ((uint32_t)0x00008000) /* Write protection of page 30 to 31 */ +#define OB_WRP_Pages32to33 ((uint32_t)0x00010000) /* Write protection of page 32 to 33 */ +#define OB_WRP_Pages34to35 ((uint32_t)0x00020000) /* Write protection of page 34 to 35 */ +#define OB_WRP_Pages36to37 ((uint32_t)0x00040000) /* Write protection of page 36 to 37 */ +#define OB_WRP_Pages38to39 ((uint32_t)0x00080000) /* Write protection of page 38 to 39 */ +#define OB_WRP_Pages40to41 ((uint32_t)0x00100000) /* Write protection of page 40 to 41 */ +#define OB_WRP_Pages42to43 ((uint32_t)0x00200000) /* Write protection of page 42 to 43 */ +#define OB_WRP_Pages44to45 ((uint32_t)0x00400000) /* Write protection of page 44 to 45 */ +#define OB_WRP_Pages46to47 ((uint32_t)0x00800000) /* Write protection of page 46 to 47 */ +#define OB_WRP_Pages48to49 ((uint32_t)0x01000000) /* Write protection of page 48 to 49 */ +#define OB_WRP_Pages50to51 ((uint32_t)0x02000000) /* Write protection of page 50 to 51 */ +#define OB_WRP_Pages52to53 ((uint32_t)0x04000000) /* Write protection of page 52 to 53 */ +#define OB_WRP_Pages54to55 ((uint32_t)0x08000000) /* Write protection of page 54 to 55 */ +#define OB_WRP_Pages56to57 ((uint32_t)0x10000000) /* Write protection of page 56 to 57 */ +#define OB_WRP_Pages58to59 ((uint32_t)0x20000000) /* Write protection of page 58 to 59 */ +#define OB_WRP_Pages60to61 ((uint32_t)0x40000000) /* Write protection of page 60 to 61 */ +#define OB_WRP_Pages62to127 ((uint32_t)0x80000000) /* Write protection of page 62 to 127 */ + +#define OB_WRP_AllPages ((uint32_t)0xFFFFFFFF) /*!< Write protection of all Sectors */ + +#define IS_OB_WRP(PAGE) (((PAGE) != 0x0000000)) + +/** + * @} + */ + +/** @defgroup Option_Bytes_Read_Protection + * @{ + */ + +/** + * @brief Read Protection Level + */ +#define OB_RDP_Level_0 ((uint8_t)0xAA) +#define OB_RDP_Level_1 ((uint8_t)0xBB) +/*#define OB_RDP_Level_2 ((uint8_t)0xCC)*/ /* Warning: When enabling read protection level 2 + it's no more possible to go back to level 1 or 0 */ + +#define IS_OB_RDP(LEVEL) (((LEVEL) == OB_RDP_Level_0)||\ + ((LEVEL) == OB_RDP_Level_1))/*||\ + ((LEVEL) == OB_RDP_Level_2))*/ +/** + * @} + */ + +/** @defgroup Option_Bytes_IWatchdog + * @{ + */ + +#define OB_IWDG_SW ((uint8_t)0x01) /*!< Software IWDG selected */ +#define OB_IWDG_HW ((uint8_t)0x00) /*!< Hardware IWDG selected */ +#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW)) + +/** + * @} + */ + +/** @defgroup Option_Bytes_nRST_STOP + * @{ + */ + +#define OB_STOP_NoRST ((uint8_t)0x02) /*!< No reset generated when entering in STOP */ +#define OB_STOP_RST ((uint8_t)0x00) /*!< Reset generated when entering in STOP */ +#define IS_OB_STOP_SOURCE(SOURCE) (((SOURCE) == OB_STOP_NoRST) || ((SOURCE) == OB_STOP_RST)) + +/** + * @} + */ + +/** @defgroup Option_Bytes_nRST_STDBY + * @{ + */ + +#define OB_STDBY_NoRST ((uint8_t)0x04) /*!< No reset generated when entering in STANDBY */ +#define OB_STDBY_RST ((uint8_t)0x00) /*!< Reset generated when entering in STANDBY */ +#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NoRST) || ((SOURCE) == OB_STDBY_RST)) + +/** + * @} + */ +/** @defgroup Option_Bytes_BOOT1 + * @{ + */ + +#define OB_BOOT1_RESET ((uint8_t)0x00) /*!< BOOT1 Reset */ +#define OB_BOOT1_SET ((uint8_t)0x10) /*!< BOOT1 Set */ +#define IS_OB_BOOT1(BOOT1) (((BOOT1) == OB_BOOT1_RESET) || ((BOOT1) == OB_BOOT1_SET)) + +/** + * @} + */ +/** @defgroup Option_Bytes_VDDA_Analog_Monitoring + * @{ + */ + +#define OB_VDDA_ANALOG_ON ((uint8_t)0x20) /*!< Analog monitoring on VDDA Power source ON */ +#define OB_VDDA_ANALOG_OFF ((uint8_t)0x00) /*!< Analog monitoring on VDDA Power source OFF */ + +#define IS_OB_VDDA_ANALOG(ANALOG) (((ANALOG) == OB_VDDA_ANALOG_ON) || ((ANALOG) == OB_VDDA_ANALOG_OFF)) + +/** + * @} + */ + +/** @defgroup FLASH_Option_Bytes_SRAM_Parity_Enable + * @{ + */ + +#define OB_SRAM_PARITY_SET ((uint8_t)0x00) /*!< SRAM parity enable Set */ +#define OB_SRAM_PARITY_RESET ((uint8_t)0x40) /*!< SRAM parity enable reset */ + +#define IS_OB_SRAM_PARITY(PARITY) (((PARITY) == OB_SRAM_PARITY_SET) || ((PARITY) == OB_SRAM_PARITY_RESET)) + +/** + * @} + */ + +/** @defgroup FLASH_Flags + * @{ + */ + +#define FLASH_FLAG_BSY FLASH_SR_BSY /*!< FLASH Busy flag */ +#define FLASH_FLAG_PGERR FLASH_SR_PGERR /*!< FLASH Programming error flag */ +#define FLASH_FLAG_WRPERR FLASH_SR_WRPERR /*!< FLASH Write protected error flag */ +#define FLASH_FLAG_EOP FLASH_SR_EOP /*!< FLASH End of Programming flag */ + +#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFCB) == 0x00000000) && ((FLAG) != 0x00000000)) + +#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_PGERR) || \ + ((FLAG) == FLASH_FLAG_WRPERR) || ((FLAG) == FLASH_FLAG_EOP)) +/** + * @} + */ +/** @defgroup Timeout_definition + * @{ + */ +#define FLASH_ER_PRG_TIMEOUT ((uint32_t)0x000B0000) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* FLASH Interface configuration functions ************************************/ +void FLASH_SetLatency(uint32_t FLASH_Latency); +void FLASH_HalfCycleAccessCmd(FunctionalState NewState); +void FLASH_PrefetchBufferCmd(FunctionalState NewState); + +/* FLASH Memory Programming functions *****************************************/ +void FLASH_Unlock(void); +void FLASH_Lock(void); +FLASH_Status FLASH_ErasePage(uint32_t Page_Address); +FLASH_Status FLASH_EraseAllPages(void); +FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data); +FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data); + +/* Option Bytes Programming functions *****************************************/ +void FLASH_OB_Unlock(void); +void FLASH_OB_Lock(void); +void FLASH_OB_Launch(void); +FLASH_Status FLASH_OB_Erase(void); +FLASH_Status FLASH_OB_EnableWRP(uint32_t OB_WRP); +FLASH_Status FLASH_OB_RDPConfig(uint8_t OB_RDP); +FLASH_Status FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY); +FLASH_Status FLASH_OB_BOOTConfig(uint8_t OB_BOOT1); +FLASH_Status FLASH_OB_VDDAConfig(uint8_t OB_VDDA_ANALOG); +FLASH_Status FLASH_OB_SRAMParityConfig(uint8_t OB_SRAM_Parity); +FLASH_Status FLASH_OB_WriteUser(uint8_t OB_USER); +FLASH_Status FLASH_ProgramOptionByteData(uint32_t Address, uint8_t Data); +uint8_t FLASH_OB_GetUser(void); +uint32_t FLASH_OB_GetWRP(void); +FlagStatus FLASH_OB_GetRDP(void); + +/* Interrupts and flags management functions **********************************/ +void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState); +FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG); +void FLASH_ClearFlag(uint32_t FLASH_FLAG); +FLASH_Status FLASH_GetStatus(void); +FLASH_Status FLASH_WaitForLastOperation(uint32_t Timeout); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F30x_FLASH_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_gpio.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_gpio.h new file mode 100644 index 0000000..64e998d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_gpio.h @@ -0,0 +1,400 @@ +/** + ****************************************************************************** + * @file stm32f30x_gpio.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the GPIO + * firmware library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_GPIO_H +#define __STM32F30x_GPIO_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup GPIO + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +#define IS_GPIO_ALL_PERIPH(PERIPH) (((PERIPH) == GPIOA) || \ + ((PERIPH) == GPIOB) || \ + ((PERIPH) == GPIOC) || \ + ((PERIPH) == GPIOD) || \ + ((PERIPH) == GPIOE) || \ + ((PERIPH) == GPIOF)) + +#define IS_GPIO_LIST_PERIPH(PERIPH) (((PERIPH) == GPIOA) || \ + ((PERIPH) == GPIOB) || \ + ((PERIPH) == GPIOD)) +/** @defgroup Configuration_Mode_enumeration + * @{ + */ +typedef enum +{ + GPIO_Mode_IN = 0x00, /*!< GPIO Input Mode */ + GPIO_Mode_OUT = 0x01, /*!< GPIO Output Mode */ + GPIO_Mode_AF = 0x02, /*!< GPIO Alternate function Mode */ + GPIO_Mode_AN = 0x03 /*!< GPIO Analog In/Out Mode */ +}GPIOMode_TypeDef; + +#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_Mode_IN)|| ((MODE) == GPIO_Mode_OUT) || \ + ((MODE) == GPIO_Mode_AF)|| ((MODE) == GPIO_Mode_AN)) +/** + * @} + */ + +/** @defgroup Output_type_enumeration + * @{ + */ +typedef enum +{ + GPIO_OType_PP = 0x00, + GPIO_OType_OD = 0x01 +}GPIOOType_TypeDef; + +#define IS_GPIO_OTYPE(OTYPE) (((OTYPE) == GPIO_OType_PP) || ((OTYPE) == GPIO_OType_OD)) + +/** + * @} + */ + +/** @defgroup Output_Maximum_frequency_enumeration + * @{ + */ +typedef enum +{ + GPIO_Speed_Level_1 = 0x01, /*!< Fast Speed */ + GPIO_Speed_Level_2 = 0x02, /*!< Meduim Speed */ + GPIO_Speed_Level_3 = 0x03 /*!< High Speed */ +}GPIOSpeed_TypeDef; + +#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_Speed_Level_1) || ((SPEED) == GPIO_Speed_Level_2) || \ + ((SPEED) == GPIO_Speed_Level_3)) +/** + * @} + */ + +/** @defgroup Configuration_Pull-Up_Pull-Down_enumeration + * @{ + */ +typedef enum +{ + GPIO_PuPd_NOPULL = 0x00, + GPIO_PuPd_UP = 0x01, + GPIO_PuPd_DOWN = 0x02 +}GPIOPuPd_TypeDef; + +#define IS_GPIO_PUPD(PUPD) (((PUPD) == GPIO_PuPd_NOPULL) || ((PUPD) == GPIO_PuPd_UP) || \ + ((PUPD) == GPIO_PuPd_DOWN)) +/** + * @} + */ + +/** @defgroup Bit_SET_and_Bit_RESET_enumeration + * @{ + */ +typedef enum +{ + Bit_RESET = 0, + Bit_SET +}BitAction; + +#define IS_GPIO_BIT_ACTION(ACTION) (((ACTION) == Bit_RESET) || ((ACTION) == Bit_SET)) +/** + * @} + */ + +/** + * @brief GPIO Init structure definition + */ +typedef struct +{ + uint32_t GPIO_Pin; /*!< Specifies the GPIO pins to be configured. + This parameter can be any value of @ref GPIO_pins_define */ + + GPIOMode_TypeDef GPIO_Mode; /*!< Specifies the operating mode for the selected pins. + This parameter can be a value of @ref GPIOMode_TypeDef */ + + GPIOSpeed_TypeDef GPIO_Speed; /*!< Specifies the speed for the selected pins. + This parameter can be a value of @ref GPIOSpeed_TypeDef */ + + GPIOOType_TypeDef GPIO_OType; /*!< Specifies the operating output type for the selected pins. + This parameter can be a value of @ref GPIOOType_TypeDef */ + + GPIOPuPd_TypeDef GPIO_PuPd; /*!< Specifies the operating Pull-up/Pull down for the selected pins. + This parameter can be a value of @ref GPIOPuPd_TypeDef */ +}GPIO_InitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup GPIO_Exported_Constants + * @{ + */ + +/** @defgroup GPIO_pins_define + * @{ + */ +#define GPIO_Pin_0 ((uint16_t)0x0001) /*!< Pin 0 selected */ +#define GPIO_Pin_1 ((uint16_t)0x0002) /*!< Pin 1 selected */ +#define GPIO_Pin_2 ((uint16_t)0x0004) /*!< Pin 2 selected */ +#define GPIO_Pin_3 ((uint16_t)0x0008) /*!< Pin 3 selected */ +#define GPIO_Pin_4 ((uint16_t)0x0010) /*!< Pin 4 selected */ +#define GPIO_Pin_5 ((uint16_t)0x0020) /*!< Pin 5 selected */ +#define GPIO_Pin_6 ((uint16_t)0x0040) /*!< Pin 6 selected */ +#define GPIO_Pin_7 ((uint16_t)0x0080) /*!< Pin 7 selected */ +#define GPIO_Pin_8 ((uint16_t)0x0100) /*!< Pin 8 selected */ +#define GPIO_Pin_9 ((uint16_t)0x0200) /*!< Pin 9 selected */ +#define GPIO_Pin_10 ((uint16_t)0x0400) /*!< Pin 10 selected */ +#define GPIO_Pin_11 ((uint16_t)0x0800) /*!< Pin 11 selected */ +#define GPIO_Pin_12 ((uint16_t)0x1000) /*!< Pin 12 selected */ +#define GPIO_Pin_13 ((uint16_t)0x2000) /*!< Pin 13 selected */ +#define GPIO_Pin_14 ((uint16_t)0x4000) /*!< Pin 14 selected */ +#define GPIO_Pin_15 ((uint16_t)0x8000) /*!< Pin 15 selected */ +#define GPIO_Pin_All ((uint16_t)0xFFFF) /*!< All pins selected */ + +#define IS_GPIO_PIN(PIN) ((PIN) != (uint16_t)0x00) + +#define IS_GET_GPIO_PIN(PIN) (((PIN) == GPIO_Pin_0) || \ + ((PIN) == GPIO_Pin_1) || \ + ((PIN) == GPIO_Pin_2) || \ + ((PIN) == GPIO_Pin_3) || \ + ((PIN) == GPIO_Pin_4) || \ + ((PIN) == GPIO_Pin_5) || \ + ((PIN) == GPIO_Pin_6) || \ + ((PIN) == GPIO_Pin_7) || \ + ((PIN) == GPIO_Pin_8) || \ + ((PIN) == GPIO_Pin_9) || \ + ((PIN) == GPIO_Pin_10) || \ + ((PIN) == GPIO_Pin_11) || \ + ((PIN) == GPIO_Pin_12) || \ + ((PIN) == GPIO_Pin_13) || \ + ((PIN) == GPIO_Pin_14) || \ + ((PIN) == GPIO_Pin_15)) + +/** + * @} + */ + +/** @defgroup GPIO_Pin_sources + * @{ + */ +#define GPIO_PinSource0 ((uint8_t)0x00) +#define GPIO_PinSource1 ((uint8_t)0x01) +#define GPIO_PinSource2 ((uint8_t)0x02) +#define GPIO_PinSource3 ((uint8_t)0x03) +#define GPIO_PinSource4 ((uint8_t)0x04) +#define GPIO_PinSource5 ((uint8_t)0x05) +#define GPIO_PinSource6 ((uint8_t)0x06) +#define GPIO_PinSource7 ((uint8_t)0x07) +#define GPIO_PinSource8 ((uint8_t)0x08) +#define GPIO_PinSource9 ((uint8_t)0x09) +#define GPIO_PinSource10 ((uint8_t)0x0A) +#define GPIO_PinSource11 ((uint8_t)0x0B) +#define GPIO_PinSource12 ((uint8_t)0x0C) +#define GPIO_PinSource13 ((uint8_t)0x0D) +#define GPIO_PinSource14 ((uint8_t)0x0E) +#define GPIO_PinSource15 ((uint8_t)0x0F) + +#define IS_GPIO_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == GPIO_PinSource0) || \ + ((PINSOURCE) == GPIO_PinSource1) || \ + ((PINSOURCE) == GPIO_PinSource2) || \ + ((PINSOURCE) == GPIO_PinSource3) || \ + ((PINSOURCE) == GPIO_PinSource4) || \ + ((PINSOURCE) == GPIO_PinSource5) || \ + ((PINSOURCE) == GPIO_PinSource6) || \ + ((PINSOURCE) == GPIO_PinSource7) || \ + ((PINSOURCE) == GPIO_PinSource8) || \ + ((PINSOURCE) == GPIO_PinSource9) || \ + ((PINSOURCE) == GPIO_PinSource10) || \ + ((PINSOURCE) == GPIO_PinSource11) || \ + ((PINSOURCE) == GPIO_PinSource12) || \ + ((PINSOURCE) == GPIO_PinSource13) || \ + ((PINSOURCE) == GPIO_PinSource14) || \ + ((PINSOURCE) == GPIO_PinSource15)) +/** + * @} + */ + +/** @defgroup GPIO_Alternate_function_selection_define + * @{ + */ + +/** + * @brief AF 0 selection + */ +#define GPIO_AF_0 ((uint8_t)0x00) /* JTCK-SWCLK, JTDI, JTDO/TRACESW0, JTMS-SWDAT, + MCO, NJTRST, TRACED, TRACECK */ +/** + * @brief AF 1 selection + */ +#define GPIO_AF_1 ((uint8_t)0x01) /* OUT, TIM2, TIM15, TIM16, TIM17 */ + +/** + * @brief AF 2 selection + */ +#define GPIO_AF_2 ((uint8_t)0x02) /* COMP1_OUT, TIM1, TIM2, TIM3, TIM4, TIM8, TIM15, TIM16 */ + +/** + * @brief AF 3 selection + */ +#define GPIO_AF_3 ((uint8_t)0x03) /* COMP7_OUT, TIM8, TIM15, Touch, HRTIM1 */ + +/** + * @brief AF 4 selection + */ +#define GPIO_AF_4 ((uint8_t)0x04) /* I2C1, I2C2, TIM1, TIM8, TIM16, TIM17 */ + +/** + * @brief AF 5 selection + */ +#define GPIO_AF_5 ((uint8_t)0x05) /* IR_OUT, I2S2, I2S3, SPI1, SPI2, TIM8, USART4, USART5 */ + +/** + * @brief AF 6 selection + */ +#define GPIO_AF_6 ((uint8_t)0x06) /* IR_OUT, I2S2, I2S3, SPI2, SPI3, TIM1, TIM8 */ + +/** + * @brief AF 7 selection + */ +#define GPIO_AF_7 ((uint8_t)0x07) /* AOP2_OUT, CAN, COMP3_OUT, COMP5_OUT, COMP6_OUT, + USART1, USART2, USART3 */ + +/** + * @brief AF 8 selection + */ +#define GPIO_AF_8 ((uint8_t)0x08) /* COMP1_OUT, COMP2_OUT, COMP3_OUT, COMP4_OUT, + COMP5_OUT, COMP6_OUT */ + +/** + * @brief AF 9 selection + */ +#define GPIO_AF_9 ((uint8_t)0x09) /* AOP4_OUT, CAN, TIM1, TIM8, TIM15 */ + +/** + * @brief AF 10 selection + */ +#define GPIO_AF_10 ((uint8_t)0x0A) /* AOP1_OUT, AOP3_OUT, TIM2, TIM3, TIM4, TIM8, TIM17 */ + +/** + * @brief AF 11 selection + */ +#define GPIO_AF_11 ((uint8_t)0x0B) /* TIM1, TIM8 */ + +/** + * @brief AF 12 selection + */ +#define GPIO_AF_12 ((uint8_t)0x0C) /* TIM1, HRTIM1 */ + +/** + * @brief AF 13 selection + */ +#define GPIO_AF_13 ((uint8_t)0x0D) /* HRTIM1, AOP2_OUT */ + +/** + * @brief AF 14 selection + */ +#define GPIO_AF_14 ((uint8_t)0x0E) /* USBDM, USBDP */ + +/** + * @brief AF 15 selection + */ +#define GPIO_AF_15 ((uint8_t)0x0F) /* OUT */ + +#define IS_GPIO_AF(AF) (((AF) == GPIO_AF_0)||((AF) == GPIO_AF_1)||\ + ((AF) == GPIO_AF_2)||((AF) == GPIO_AF_3)||\ + ((AF) == GPIO_AF_4)||((AF) == GPIO_AF_5)||\ + ((AF) == GPIO_AF_6)||((AF) == GPIO_AF_7)||\ + ((AF) == GPIO_AF_8)||((AF) == GPIO_AF_9)||\ + ((AF) == GPIO_AF_10)||((AF) == GPIO_AF_11)||\ + ((AF) == GPIO_AF_12)||((AF) == GPIO_AF_13)||\ + ((AF) == GPIO_AF_14)||((AF) == GPIO_AF_15)) + +/** + * @} + */ + +/** @defgroup GPIO_Speed_Legacy + * @{ + */ + +#define GPIO_Speed_10MHz GPIO_Speed_Level_1 /*!< Fast Speed:10MHz */ +#define GPIO_Speed_2MHz GPIO_Speed_Level_2 /*!< Medium Speed:2MHz */ +#define GPIO_Speed_50MHz GPIO_Speed_Level_3 /*!< High Speed:50MHz */ + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +/* Function used to set the GPIO configuration to the default reset state *****/ +void GPIO_DeInit(GPIO_TypeDef* GPIOx); + +/* Initialization and Configuration functions *********************************/ +void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct); +void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct); +void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); + +/* GPIO Read and Write functions **********************************************/ +uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx); +uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx); +void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal); +void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal); + +/* GPIO Alternate functions configuration functions ***************************/ +void GPIO_PinAFConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F30x_GPIO_H */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_hrtim.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_hrtim.h new file mode 100644 index 0000000..39dea38 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_hrtim.h @@ -0,0 +1,2746 @@ +/** + ****************************************************************************** + * @file stm32f30x_hrtim.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the HRTIM firmware + * library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_HRTIM_H +#define __STM32F30x_HRTIM_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup ADC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief HRTIM Configuration Structure definition - Time base related parameters + */ +typedef struct +{ + uint32_t Period; /*!< Specifies the timer period + The period value must be above 3 periods of the fHRTIM clock. + Maximum value is = 0xFFDF */ + uint32_t RepetitionCounter; /*!< Specifies the timer repetition period + This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. */ + uint32_t PrescalerRatio; /*!< Specifies the timer clock prescaler ratio. + This parameter can be any value of @ref HRTIM_PrescalerRatio */ + uint32_t Mode; /*!< Specifies the counter operating mode + This parameter can be any value of @ref HRTIM_Mode */ +} HRTIM_BaseInitTypeDef; +/** + * @brief Waveform mode initialization parameters definition + */ +typedef struct { + uint32_t HalfModeEnable; /*!< Specifies whether or not half mode is enabled + This parameter can be a combination of @ref HRTIM_HalfModeEnable */ + uint32_t StartOnSync; /*!< Specifies whether or not timer is reset by a rising edge on the synchronization input (when enabled) + This parameter can be a combination of @ref HRTIM_StartOnSyncInputEvent */ + uint32_t ResetOnSync; /*!< Specifies whether or not timer is reset by a rising edge on the synchronization input (when enabled) + This parameter can be a combination of @ref HRTIM_ResetOnSyncInputEvent */ + uint32_t DACSynchro; /*!< Indicates whether or not the a DAC synchronization event is generated + This parameter can be any value of @ref HRTIM_DACSynchronization */ + uint32_t PreloadEnable; /*!< Specifies whether or not register preload is enabled + This parameter can be a combination of @ref HRTIM_RegisterPreloadEnable */ + uint32_t UpdateGating; /*!< Specifies how the update occurs with respect to a burst DMA transaction or + update enable inputs (Slave timers only) + This parameter can be any value of @ref HRTIM_UpdateGating */ + uint32_t BurstMode; /*!< Specifies how the timer behaves during a burst mode operation + This parameter can be a combination of @ref HRTIM_TimerBurstMode */ + uint32_t RepetitionUpdate; /*!< Specifies whether or not registers update is triggered by the repetition event + This parameter can be a combination of @ref HRTIM_TimerRepetitionUpdate */ +} HRTIM_TimerInitTypeDef; + +/** + * @brief Basic output compare mode configuration definition + */ +typedef struct { + uint32_t Mode; /*!< Specifies the output compare mode (toggle, active, inactive) + This parameter can be a combination of @ref HRTIM_BasicOCMode */ + uint32_t Pulse; /*!< Specifies the compare value to be loaded into the Compare Register. + The compare value must be above or equal to 3 periods of the fHRTIM clock */ + uint32_t Polarity; /*!< Specifies the output polarity + This parameter can be any value of @ref HRTIM_Output_Polarity */ + uint32_t IdleState; /*!< Specifies whether the output level is active or inactive when in IDLE state + This parameter can be any value of @ref HRTIM_OutputIDLEState */ +} HRTIM_BasicOCChannelCfgTypeDef; + +/** + * @brief Basic PWM output mode configuration definition + */ +typedef struct { + uint32_t Pulse; /*!< Specifies the compare value to be loaded into the Compare Register. + The compare value must be above or equal to 3 periods of the fHRTIM clock */ + uint32_t Polarity; /*!< Specifies the output polarity + This parameter can be any value of @ref HRTIM_OutputPolarity */ + uint32_t IdleState; /*!< Specifies whether the output level is active or inactive when in IDLE state + This parameter can be any value of @ref HRTIM_OutputIDLEState */ +} HRTIM_BasicPWMChannelCfgTypeDef; + +/** + * @brief Basic capture mode configuration definition + */ +typedef struct { + uint32_t CaptureUnit; /*!< Specifies the external event Channel + This parameter can be any 'EEVx' value of @ref HRTIM_CaptureUnit */ + uint32_t Event; /*!< Specifies the external event triggering the capture + This parameter can be any 'EEVx' value of @ref HRTIM_ExternalEventChannels */ + uint32_t EventPolarity; /*!< Specifies the polarity of the external event (in case of level sensitivity) + This parameter can be a value of @ref HRTIM_ExternalEventPolarity */ + uint32_t EventSensitivity; /*!< Specifies the sensitivity of the external event + This parameter can be a value of @ref HRTIM_ExternalEventSensitivity */ + uint32_t EventFilter; /*!< Defines the frequency used to sample the External Event and the length of the digital filter + This parameter can be a value of @ref HRTIM_ExternalEventFilter */ +} HRTIM_BasicCaptureChannelCfgTypeDef; + +/** + * @brief Basic One Pulse mode configuration definition + */ +typedef struct { + uint32_t Pulse; /*!< Specifies the compare value to be loaded into the Compare Register. + The compare value must be above or equal to 3 periods of the fHRTIM clock */ + uint32_t OutputPolarity; /*!< Specifies the output polarity + This parameter can be any value of @ref HRTIM_Output_Polarity */ + uint32_t OutputIdleState; /*!< Specifies whether the output level is active or inactive when in IDLE state + This parameter can be any value of @ref HRTIM_Output_IDLE_State */ + uint32_t Event; /*!< Specifies the external event triggering the pulse generation + This parameter can be any 'EEVx' value of @ref HRTIM_Capture_Unit_Trigger */ + uint32_t EventPolarity; /*!< Specifies the polarity of the external event (in case of level sensitivity) + This parameter can be a value of @ref HRTIM_ExternalEventPolarity */ + uint32_t EventSensitivity; /*!< Specifies the sensitivity of the external event + This parameter can be a value of @ref HRTIM_ExternalEventSensitivity */ + uint32_t EventFilter; /*!< Defines the frequency used to sample the External Event and the length of the digital filter + This parameter can be a value of @ref HRTIM_ExternalEventFilter */ +} HRTIM_BasicOnePulseChannelCfgTypeDef; + +/** + * @brief Timer configuration definition + */ +typedef struct { + uint32_t PushPull; /*!< Specifies whether or not the push-pull mode is enabled + This parameter can be a value of @ref HRTIM_TimerPushPullMode */ + uint32_t FaultEnable; /*!< Specifies which fault channels are enabled for the timer + This parameter can be a combination of @ref HRTIM_TimerFaultEnabling */ + uint32_t FaultLock; /*!< Specifies whether or not fault enabling status is write protected + This parameter can be a value of @ref HRTIM_TimerFaultLock */ + uint32_t DeadTimeInsertion; /*!< Specifies whether or not dead time insertion is enabled for the timer + This parameter can be a value of @ref HRTIM_TimerDeadtimeInsertion */ + uint32_t DelayedProtectionMode; /*!< Specifies the delayed protection mode + This parameter can be a value of @ref HRTIM_TimerDelayedProtectionMode */ + uint32_t UpdateTrigger; /*!< Specifies source(s) triggering the timer registers update + This parameter can be a combination of @ref HRTIM_TimerUpdateTrigger */ + uint32_t ResetTrigger; /*!< Specifies source(s) triggering the timer counter reset + This parameter can be a combination of @ref HRTIM_TimerResetTrigger */ + uint32_t ResetUpdate; /*!< Specifies whether or not registers update is triggered when the timer counter is reset + This parameter can be a combination of @ref HRTIM_TimerResetUpdate */ +} HRTIM_TimerCfgTypeDef; + +/** + * @brief Compare unit configuration definition + */ +typedef struct { + uint32_t CompareValue; /*!< Specifies the compare value of the timer compare unit + the minimum value must be greater than or equal to 3 periods of the fHRTIM clock + the maximum value must be less than or equal to 0xFFFF - 1 periods of the fHRTIM clock */ + uint32_t AutoDelayedMode; /*!< Specifies the auto delayed mode for compare unit 2 or 4 + This parameter can be a value of @ref HRTIM_CompareUnitAutoDelayedMode */ + uint32_t AutoDelayedTimeout; /*!< Specifies compare value for timing unit 1 or 3 when auto delayed mode with time out is selected + CompareValue + AutoDelayedTimeout must be less than 0xFFFF */ +} HRTIM_CompareCfgTypeDef; + +/** + * @brief Capture unit configuration definition + */ +typedef struct { + uint32_t Trigger; /*!< Specifies source(s) triggering the capture + This parameter can be a combination of @ref HRTIM_CaptureUnitTrigger */ +} HRTIM_CaptureCfgTypeDef; + +/** + * @brief Output configuration definition + */ +typedef struct { + uint32_t Polarity; /*!< Specifies the output polarity + This parameter can be any value of @ref HRTIM_Output_Polarity */ + uint32_t SetSource; /*!< Specifies the event(s) transitioning the output from its inactive level to its active level + This parameter can be any value of @ref HRTIM_OutputSetSource */ + uint32_t ResetSource; /*!< Specifies the event(s) transitioning the output from its active level to its inactive level + This parameter can be any value of @ref HRTIM_OutputResetSource */ + uint32_t IdleMode; /*!< Specifies whether or not the output is affected by a burst mode operation + This parameter can be any value of @ref HRTIM_OutputIdleMode */ + uint32_t IdleState; /*!< Specifies whether the output level is active or inactive when in IDLE state + This parameter can be any value of @ref HRTIM_OutputIDLEState */ + uint32_t FaultState; /*!< Specifies whether the output level is active or inactive when in FAULT state + This parameter can be any value of @ref HRTIM_OutputFAULTState */ + uint32_t ChopperModeEnable; /*!< Indicates whether or not the chopper mode is enabled + This parameter can be any value of @ref HRTIM_OutputChopperModeEnable */ + uint32_t BurstModeEntryDelayed; /* !HRTIM_MASTER.MCR |= (__TIMERS__)) + +/* The counter of a timing unit is disabled only if all the timer outputs */ +/* are disabled and no capture is configured */ +#define HRTIM_TAOEN_MASK (HRTIM_OENR_TA2OEN | HRTIM_OENR_TA1OEN) +#define HRTIM_TBOEN_MASK (HRTIM_OENR_TB2OEN | HRTIM_OENR_TB1OEN) +#define HRTIM_TCOEN_MASK (HRTIM_OENR_TC2OEN | HRTIM_OENR_TC1OEN) +#define HRTIM_TDOEN_MASK (HRTIM_OENR_TD2OEN | HRTIM_OENR_TD1OEN) +#define HRTIM_TEOEN_MASK (HRTIM_OENR_TE2OEN | HRTIM_OENR_TE1OEN) +#define __HRTIM_DISABLE(__HANDLE__, __TIMERS__)\ + do {\ + if (((__TIMERS__) & HRTIM_TIMERID_MASTER) == HRTIM_TIMERID_MASTER)\ + {\ + ((__HANDLE__)->HRTIM_MASTER.MCR &= ~HRTIM_TIMERID_MASTER);\ + }\ + if (((__TIMERS__) & HRTIM_TIMERID_TIMER_A) == HRTIM_TIMERID_TIMER_A)\ + {\ + if (((__HANDLE__)->HRTIM_COMMON.OENR & HRTIM_TAOEN_MASK) == RESET)\ + {\ + ((__HANDLE__)->HRTIM_MASTER.MCR &= ~HRTIM_TIMERID_TIMER_A);\ + }\ + }\ + if (((__TIMERS__) & HRTIM_TIMERID_TIMER_B) == HRTIM_TIMERID_TIMER_B)\ + {\ + if (((__HANDLE__)->HRTIM_COMMON.OENR & HRTIM_TBOEN_MASK) == RESET)\ + {\ + ((__HANDLE__)->HRTIM_MASTER.MCR &= ~HRTIM_TIMERID_TIMER_B);\ + }\ + }\ + if (((__TIMERS__) & HRTIM_TIMERID_TIMER_C) == HRTIM_TIMERID_TIMER_C)\ + {\ + if (((__HANDLE__)->HRTIM_COMMON.OENR & HRTIM_TCOEN_MASK) == RESET)\ + {\ + ((__HANDLE__)->HRTIM_MASTER.MCR &= ~HRTIM_TIMERID_TIMER_C);\ + }\ + }\ + if (((__TIMERS__) & HRTIM_TIMERID_TIMER_D) == HRTIM_TIMERID_TIMER_D)\ + {\ + if (((__HANDLE__)->HRTIM_COMMON.OENR & HRTIM_TDOEN_MASK) == RESET)\ + {\ + ((__HANDLE__)->HRTIM_MASTER.MCR &= ~HRTIM_TIMERID_TIMER_D);\ + }\ + }\ + if (((__TIMERS__) & HRTIM_TIMERID_TIMER_E) == HRTIM_TIMERID_TIMER_E)\ + {\ + if (((__HANDLE__)->HRTIM_COMMON.OENR & HRTIM_TEOEN_MASK) == RESET)\ + {\ + ((__HANDLE__)->HRTIM_MASTER.MCR &= ~HRTIM_TIMERID_TIMER_E);\ + }\ + }\ + } while(0) + +/* Exported functions --------------------------------------------------------*/ + +/* Simple time base related functions *****************************************/ +void HRTIM_SimpleBase_Init(HRTIM_TypeDef* HRTIMx, uint32_t TimerIdx, HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruct); + +void HRTIM_DeInit(HRTIM_TypeDef* HRTIMx); + +void HRTIM_SimpleBaseStart(HRTIM_TypeDef *HRTIMx, uint32_t TimerIdx); +void HRTIM_SimpleBaseStop(HRTIM_TypeDef *HRTIMx, uint32_t TimerIdx); + +/* Simple output compare related functions ************************************/ +void HRTIM_SimpleOC_Init(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruct); + +void HRTIM_SimpleOCChannelConfig(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + uint32_t OCChannel, + HRTIM_BasicOCChannelCfgTypeDef* pBasicOCChannelCfg); + +void HRTIM_SimpleOCStart(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + uint32_t OCChannel); +void HRTIM_SimpleOCStop(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t OCChannel); +/* Simple PWM output related functions ****************************************/ +void HRTIM_SimplePWM_Init(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruct); + +void HRTIM_SimplePWMChannelConfig(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + uint32_t PWMChannel, + HRTIM_BasicPWMChannelCfgTypeDef* pBasicPWMChannelCfg); + +void HRTIM_SimplePWMStart(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t PWMChannel); +void HRTIM_SimplePWMStop(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t PWMChannel); +/* Simple capture related functions *******************************************/ +void HRTIM_SimpleCapture_Init(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruct); + +void HRTIM_SimpleCaptureChannelConfig(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + uint32_t CaptureChannel, + HRTIM_BasicCaptureChannelCfgTypeDef* pBasicCaptureChannelCfg); + +void HRTIM_SimpleCaptureStart(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t CaptureChannel); +void HRTIM_SimpleCaptureStop(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t CaptureChannel); +/* SImple one pulse related functions *****************************************/ +void HRTIM_SimpleOnePulse_Init(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruct); + +void HRTIM_SimpleOnePulseChannelConfig(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + uint32_t OnePulseChannel, + HRTIM_BasicOnePulseChannelCfgTypeDef* pBasicOnePulseChannelCfg); + +void HRTIM_SimpleOnePulseStart(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t OnePulseChannel); +void HRTIM_SimpleOnePulseStop(HRTIM_TypeDef * HRTIM_, + uint32_t TimerIdx, + uint32_t OnePulseChannel); +/* Waveform related functions *************************************************/ +void HRTIM_Waveform_Init(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruct, + HRTIM_TimerInitTypeDef* HRTIM_TimerInitStruct); + +void HRTIM_WaveformTimerConfig(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + HRTIM_TimerCfgTypeDef * HRTIM_TimerCfgStruct); + +void HRTIM_WaveformCompareConfig(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + uint32_t CompareUnit, + HRTIM_CompareCfgTypeDef* pCompareCfg); + +void HRTIM_SlaveSetCompare(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t CompareUnit, + uint32_t Compare); + +void HRTIM_MasterSetCompare(HRTIM_TypeDef * HRTIMx, + uint32_t CompareUnit, + uint32_t Compare); + +void HRTIM_WaveformCaptureConfig(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + uint32_t CaptureUnit, + HRTIM_CaptureCfgTypeDef* pCaptureCfg); + +void HRTIM_WaveformOuputConfig(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + uint32_t Output, + HRTIM_OutputCfgTypeDef * pOutputCfg); + +void HRTIM_TimerEventFilteringConfig(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + uint32_t Event, + HRTIM_TimerEventFilteringCfgTypeDef * pTimerEventFilteringCfg); + +void HRTIM_DeadTimeConfig(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + HRTIM_DeadTimeCfgTypeDef* pDeadTimeCfg); + +void HRTIM_ChopperModeConfig(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + HRTIM_ChopperModeCfgTypeDef* pChopperModeCfg); + +void HRTIM_BurstDMAConfig(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + uint32_t RegistersToUpdate); + +void HRTIM_SynchronizationConfig(HRTIM_TypeDef *HRTIMx, + HRTIM_SynchroCfgTypeDef * pSynchroCfg); + +void HRTIM_BurstModeConfig(HRTIM_TypeDef *HRTIMx, + HRTIM_BurstModeCfgTypeDef* pBurstModeCfg); + +void HRTIM_EventConfig(HRTIM_TypeDef *HRTIMx, + uint32_t Event, + HRTIM_EventCfgTypeDef* pEventCfg); + +void HRTIM_EventPrescalerConfig(HRTIM_TypeDef *HRTIMx, + uint32_t Prescaler); + +void HRTIM_FaultConfig(HRTIM_TypeDef *hrtim, + HRTIM_FaultCfgTypeDef* pFaultCfg, + uint32_t Fault); + +void HRTIM_FaultPrescalerConfig(HRTIM_TypeDef *HRTIMx, + uint32_t Prescaler); +void HRTIM_FaultModeCtl(HRTIM_TypeDef * HRTIMx, uint32_t Fault, uint32_t Enable); + +void HRTIM_ADCTriggerConfig(HRTIM_TypeDef *HRTIMx, + uint32_t ADCTrigger, + HRTIM_ADCTriggerCfgTypeDef* pADCTriggerCfg); + +void HRTIM_WaveformCounterStart(HRTIM_TypeDef *HRTIMx, + uint32_t TimersToStart); + +void HRTIM_WaveformCounterStop(HRTIM_TypeDef *HRTIMx, + uint32_t TimersToStop); + +void HRTIM_WaveformOutputStart(HRTIM_TypeDef *HRTIMx, + uint32_t OuputsToStart); +void HRTIM_WaveformOutputStop(HRTIM_TypeDef * HRTIM_, + uint32_t OuputsToStop); + +void HRTIM_DLLCalibrationStart(HRTIM_TypeDef *HRTIMx, + uint32_t CalibrationRate); + +/* Interrupt/flags and DMA management */ +void HRTIM_ITConfig(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, uint32_t HRTIM_TIM_IT, FunctionalState NewState); +void HRTIM_ITCommonConfig(HRTIM_TypeDef * HRTIMx, uint32_t HRTIM_CommonIT, FunctionalState NewState); + +void HRTIM_ClearFlag(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, uint32_t HRTIM_FLAG); +void HRTIM_ClearCommonFlag(HRTIM_TypeDef * HRTIMx, uint32_t HRTIM_CommonFLAG); + +void HRTIM_ClearITPendingBit(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, uint32_t HRTIM_IT); +void HRTIM_ClearCommonITPendingBit(HRTIM_TypeDef * HRTIMx, uint32_t HRTIM_CommonIT); + +FlagStatus HRTIM_GetFlagStatus(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, uint32_t HRTIM_FLAG); +FlagStatus HRTIM_GetCommonFlagStatus(HRTIM_TypeDef * HRTIMx, uint32_t HRTIM_CommonFLAG); + +ITStatus HRTIM_GetITStatus(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, uint32_t HRTIM_IT); +ITStatus HRTIM_GetCommonITStatus(HRTIM_TypeDef * HRTIMx, uint32_t HRTIM_CommonIT); + + +void HRTIM_DMACmd(HRTIM_TypeDef* HRTIMx, uint32_t TimerIdx, uint32_t HRTIM_DMA, FunctionalState NewState); + +void HRTIM_BurstModeCtl(HRTIM_TypeDef *HRTIMx, + uint32_t Enable); + +void HRTIM_SoftwareCapture(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + uint32_t CaptureUnit); + +void HRTIM_SoftwareUpdate(HRTIM_TypeDef *HRTIMx, + uint32_t TimersToUpdate); + +void HRTIM_SoftwareReset(HRTIM_TypeDef *HRTIMx, + uint32_t TimersToReset); + + +uint32_t HRTIM_GetCapturedValue(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + uint32_t CaptureUnit); + +void HRTIM_WaveformOutputConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t Output, + HRTIM_OutputCfgTypeDef * pOutputCfg); + +void HRTIM_WaveformSetOutputLevel(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + uint32_t Output, + uint32_t OutputLevel); + +uint32_t HRTIM_WaveformGetOutputLevel(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + uint32_t Output); + +uint32_t HRTIM_WaveformGetOutputState(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t Output); + +uint32_t HRTIM_GetDelayedProtectionStatus(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx, + uint32_t Output); + +uint32_t HRTIM_GetBurstStatus(HRTIM_TypeDef *HRTIMx); + +uint32_t HRTIM_GetCurrentPushPullStatus(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx); + +uint32_t HRTIM_GetIdlePushPullStatus(HRTIM_TypeDef *HRTIMx, + uint32_t TimerIdx); +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F30x_HRTIM_H */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_i2c.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_i2c.h new file mode 100644 index 0000000..109f4bd --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_i2c.h @@ -0,0 +1,477 @@ +/** + ****************************************************************************** + * @file stm32f30x_i2c.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the I2C firmware + * library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_I2C_H +#define __STM32F30x_I2C_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup I2C + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief I2C Init structure definition + */ + +typedef struct +{ + uint32_t I2C_Timing; /*!< Specifies the I2C_TIMINGR_register value. + This parameter calculated by referring to I2C initialization + section in Reference manual*/ + + uint32_t I2C_AnalogFilter; /*!< Enables or disables analog noise filter. + This parameter can be a value of @ref I2C_Analog_Filter */ + + uint32_t I2C_DigitalFilter; /*!< Configures the digital noise filter. + This parameter can be a number between 0x00 and 0x0F */ + + uint32_t I2C_Mode; /*!< Specifies the I2C mode. + This parameter can be a value of @ref I2C_mode */ + + uint32_t I2C_OwnAddress1; /*!< Specifies the device own address 1. + This parameter can be a 7-bit or 10-bit address */ + + uint32_t I2C_Ack; /*!< Enables or disables the acknowledgement. + This parameter can be a value of @ref I2C_acknowledgement */ + + uint32_t I2C_AcknowledgedAddress; /*!< Specifies if 7-bit or 10-bit address is acknowledged. + This parameter can be a value of @ref I2C_acknowledged_address */ +}I2C_InitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + + +/** @defgroup I2C_Exported_Constants + * @{ + */ + +#define IS_I2C_ALL_PERIPH(PERIPH) (((PERIPH) == I2C1) || \ + ((PERIPH) == I2C2)) + +/** @defgroup I2C_Analog_Filter + * @{ + */ + +#define I2C_AnalogFilter_Enable ((uint32_t)0x00000000) +#define I2C_AnalogFilter_Disable I2C_CR1_ANFOFF + +#define IS_I2C_ANALOG_FILTER(FILTER) (((FILTER) == I2C_AnalogFilter_Enable) || \ + ((FILTER) == I2C_AnalogFilter_Disable)) +/** + * @} + */ + +/** @defgroup I2C_Digital_Filter + * @{ + */ + +#define IS_I2C_DIGITAL_FILTER(FILTER) ((FILTER) <= 0x0000000F) +/** + * @} + */ + +/** @defgroup I2C_mode + * @{ + */ + +#define I2C_Mode_I2C ((uint32_t)0x00000000) +#define I2C_Mode_SMBusDevice I2C_CR1_SMBDEN +#define I2C_Mode_SMBusHost I2C_CR1_SMBHEN + +#define IS_I2C_MODE(MODE) (((MODE) == I2C_Mode_I2C) || \ + ((MODE) == I2C_Mode_SMBusDevice) || \ + ((MODE) == I2C_Mode_SMBusHost)) +/** + * @} + */ + +/** @defgroup I2C_acknowledgement + * @{ + */ + +#define I2C_Ack_Enable ((uint32_t)0x00000000) +#define I2C_Ack_Disable I2C_CR2_NACK + +#define IS_I2C_ACK(ACK) (((ACK) == I2C_Ack_Enable) || \ + ((ACK) == I2C_Ack_Disable)) +/** + * @} + */ + +/** @defgroup I2C_acknowledged_address + * @{ + */ + +#define I2C_AcknowledgedAddress_7bit ((uint32_t)0x00000000) +#define I2C_AcknowledgedAddress_10bit I2C_OAR1_OA1MODE + +#define IS_I2C_ACKNOWLEDGE_ADDRESS(ADDRESS) (((ADDRESS) == I2C_AcknowledgedAddress_7bit) || \ + ((ADDRESS) == I2C_AcknowledgedAddress_10bit)) +/** + * @} + */ + +/** @defgroup I2C_own_address1 + * @{ + */ + +#define IS_I2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= (uint32_t)0x000003FF) +/** + * @} + */ + +/** @defgroup I2C_transfer_direction + * @{ + */ + +#define I2C_Direction_Transmitter ((uint16_t)0x0000) +#define I2C_Direction_Receiver ((uint16_t)0x0400) + +#define IS_I2C_DIRECTION(DIRECTION) (((DIRECTION) == I2C_Direction_Transmitter) || \ + ((DIRECTION) == I2C_Direction_Receiver)) +/** + * @} + */ + +/** @defgroup I2C_DMA_transfer_requests + * @{ + */ + +#define I2C_DMAReq_Tx I2C_CR1_TXDMAEN +#define I2C_DMAReq_Rx I2C_CR1_RXDMAEN + +#define IS_I2C_DMA_REQ(REQ) ((((REQ) & (uint32_t)0xFFFF3FFF) == 0x00) && ((REQ) != 0x00)) +/** + * @} + */ + +/** @defgroup I2C_slave_address + * @{ + */ + +#define IS_I2C_SLAVE_ADDRESS(ADDRESS) ((ADDRESS) <= (uint16_t)0x03FF) +/** + * @} + */ + + +/** @defgroup I2C_own_address2 + * @{ + */ + +#define IS_I2C_OWN_ADDRESS2(ADDRESS2) ((ADDRESS2) <= (uint16_t)0x00FF) + +/** + * @} + */ + +/** @defgroup I2C_own_address2_mask + * @{ + */ + +#define I2C_OA2_NoMask ((uint8_t)0x00) +#define I2C_OA2_Mask01 ((uint8_t)0x01) +#define I2C_OA2_Mask02 ((uint8_t)0x02) +#define I2C_OA2_Mask03 ((uint8_t)0x03) +#define I2C_OA2_Mask04 ((uint8_t)0x04) +#define I2C_OA2_Mask05 ((uint8_t)0x05) +#define I2C_OA2_Mask06 ((uint8_t)0x06) +#define I2C_OA2_Mask07 ((uint8_t)0x07) + +#define IS_I2C_OWN_ADDRESS2_MASK(MASK) (((MASK) == I2C_OA2_NoMask) || \ + ((MASK) == I2C_OA2_Mask01) || \ + ((MASK) == I2C_OA2_Mask02) || \ + ((MASK) == I2C_OA2_Mask03) || \ + ((MASK) == I2C_OA2_Mask04) || \ + ((MASK) == I2C_OA2_Mask05) || \ + ((MASK) == I2C_OA2_Mask06) || \ + ((MASK) == I2C_OA2_Mask07)) + +/** + * @} + */ + +/** @defgroup I2C_timeout + * @{ + */ + +#define IS_I2C_TIMEOUT(TIMEOUT) ((TIMEOUT) <= (uint16_t)0x0FFF) + +/** + * @} + */ + +/** @defgroup I2C_registers + * @{ + */ + +#define I2C_Register_CR1 ((uint8_t)0x00) +#define I2C_Register_CR2 ((uint8_t)0x04) +#define I2C_Register_OAR1 ((uint8_t)0x08) +#define I2C_Register_OAR2 ((uint8_t)0x0C) +#define I2C_Register_TIMINGR ((uint8_t)0x10) +#define I2C_Register_TIMEOUTR ((uint8_t)0x14) +#define I2C_Register_ISR ((uint8_t)0x18) +#define I2C_Register_ICR ((uint8_t)0x1C) +#define I2C_Register_PECR ((uint8_t)0x20) +#define I2C_Register_RXDR ((uint8_t)0x24) +#define I2C_Register_TXDR ((uint8_t)0x28) + +#define IS_I2C_REGISTER(REGISTER) (((REGISTER) == I2C_Register_CR1) || \ + ((REGISTER) == I2C_Register_CR2) || \ + ((REGISTER) == I2C_Register_OAR1) || \ + ((REGISTER) == I2C_Register_OAR2) || \ + ((REGISTER) == I2C_Register_TIMINGR) || \ + ((REGISTER) == I2C_Register_TIMEOUTR) || \ + ((REGISTER) == I2C_Register_ISR) || \ + ((REGISTER) == I2C_Register_ICR) || \ + ((REGISTER) == I2C_Register_PECR) || \ + ((REGISTER) == I2C_Register_RXDR) || \ + ((REGISTER) == I2C_Register_TXDR)) +/** + * @} + */ + +/** @defgroup I2C_interrupts_definition + * @{ + */ + +#define I2C_IT_ERRI I2C_CR1_ERRIE +#define I2C_IT_TCI I2C_CR1_TCIE +#define I2C_IT_STOPI I2C_CR1_STOPIE +#define I2C_IT_NACKI I2C_CR1_NACKIE +#define I2C_IT_ADDRI I2C_CR1_ADDRIE +#define I2C_IT_RXI I2C_CR1_RXIE +#define I2C_IT_TXI I2C_CR1_TXIE + +#define IS_I2C_CONFIG_IT(IT) ((((IT) & (uint32_t)0xFFFFFF01) == 0x00) && ((IT) != 0x00)) + +/** + * @} + */ + +/** @defgroup I2C_flags_definition + * @{ + */ + +#define I2C_FLAG_TXE I2C_ISR_TXE +#define I2C_FLAG_TXIS I2C_ISR_TXIS +#define I2C_FLAG_RXNE I2C_ISR_RXNE +#define I2C_FLAG_ADDR I2C_ISR_ADDR +#define I2C_FLAG_NACKF I2C_ISR_NACKF +#define I2C_FLAG_STOPF I2C_ISR_STOPF +#define I2C_FLAG_TC I2C_ISR_TC +#define I2C_FLAG_TCR I2C_ISR_TCR +#define I2C_FLAG_BERR I2C_ISR_BERR +#define I2C_FLAG_ARLO I2C_ISR_ARLO +#define I2C_FLAG_OVR I2C_ISR_OVR +#define I2C_FLAG_PECERR I2C_ISR_PECERR +#define I2C_FLAG_TIMEOUT I2C_ISR_TIMEOUT +#define I2C_FLAG_ALERT I2C_ISR_ALERT +#define I2C_FLAG_BUSY I2C_ISR_BUSY + +#define IS_I2C_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFF4000) == 0x00) && ((FLAG) != 0x00)) + +#define IS_I2C_GET_FLAG(FLAG) (((FLAG) == I2C_FLAG_TXE) || ((FLAG) == I2C_FLAG_TXIS) || \ + ((FLAG) == I2C_FLAG_RXNE) || ((FLAG) == I2C_FLAG_ADDR) || \ + ((FLAG) == I2C_FLAG_NACKF) || ((FLAG) == I2C_FLAG_STOPF) || \ + ((FLAG) == I2C_FLAG_TC) || ((FLAG) == I2C_FLAG_TCR) || \ + ((FLAG) == I2C_FLAG_BERR) || ((FLAG) == I2C_FLAG_ARLO) || \ + ((FLAG) == I2C_FLAG_OVR) || ((FLAG) == I2C_FLAG_PECERR) || \ + ((FLAG) == I2C_FLAG_TIMEOUT) || ((FLAG) == I2C_FLAG_ALERT) || \ + ((FLAG) == I2C_FLAG_BUSY)) + +/** + * @} + */ + + +/** @defgroup I2C_interrupts_definition + * @{ + */ + +#define I2C_IT_TXIS I2C_ISR_TXIS +#define I2C_IT_RXNE I2C_ISR_RXNE +#define I2C_IT_ADDR I2C_ISR_ADDR +#define I2C_IT_NACKF I2C_ISR_NACKF +#define I2C_IT_STOPF I2C_ISR_STOPF +#define I2C_IT_TC I2C_ISR_TC +#define I2C_IT_TCR I2C_ISR_TCR +#define I2C_IT_BERR I2C_ISR_BERR +#define I2C_IT_ARLO I2C_ISR_ARLO +#define I2C_IT_OVR I2C_ISR_OVR +#define I2C_IT_PECERR I2C_ISR_PECERR +#define I2C_IT_TIMEOUT I2C_ISR_TIMEOUT +#define I2C_IT_ALERT I2C_ISR_ALERT + +#define IS_I2C_CLEAR_IT(IT) ((((IT) & (uint32_t)0xFFFFC001) == 0x00) && ((IT) != 0x00)) + +#define IS_I2C_GET_IT(IT) (((IT) == I2C_IT_TXIS) || ((IT) == I2C_IT_RXNE) || \ + ((IT) == I2C_IT_ADDR) || ((IT) == I2C_IT_NACKF) || \ + ((IT) == I2C_IT_STOPF) || ((IT) == I2C_IT_TC) || \ + ((IT) == I2C_IT_TCR) || ((IT) == I2C_IT_BERR) || \ + ((IT) == I2C_IT_ARLO) || ((IT) == I2C_IT_OVR) || \ + ((IT) == I2C_IT_PECERR) || ((IT) == I2C_IT_TIMEOUT) || \ + ((IT) == I2C_IT_ALERT)) + + +/** + * @} + */ + +/** @defgroup I2C_ReloadEndMode_definition + * @{ + */ + +#define I2C_Reload_Mode I2C_CR2_RELOAD +#define I2C_AutoEnd_Mode I2C_CR2_AUTOEND +#define I2C_SoftEnd_Mode ((uint32_t)0x00000000) + + +#define IS_RELOAD_END_MODE(MODE) (((MODE) == I2C_Reload_Mode) || \ + ((MODE) == I2C_AutoEnd_Mode) || \ + ((MODE) == I2C_SoftEnd_Mode)) + + +/** + * @} + */ + +/** @defgroup I2C_StartStopMode_definition + * @{ + */ + +#define I2C_No_StartStop ((uint32_t)0x00000000) +#define I2C_Generate_Stop I2C_CR2_STOP +#define I2C_Generate_Start_Read (uint32_t)(I2C_CR2_START | I2C_CR2_RD_WRN) +#define I2C_Generate_Start_Write I2C_CR2_START + + +#define IS_START_STOP_MODE(MODE) (((MODE) == I2C_Generate_Stop) || \ + ((MODE) == I2C_Generate_Start_Read) || \ + ((MODE) == I2C_Generate_Start_Write) || \ + ((MODE) == I2C_No_StartStop)) + + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + + +/* Initialization and Configuration functions *********************************/ +void I2C_DeInit(I2C_TypeDef* I2Cx); +void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct); +void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct); +void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx); +void I2C_ITConfig(I2C_TypeDef* I2Cx, uint32_t I2C_IT, FunctionalState NewState); +void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_StopModeCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint16_t Address, uint8_t Mask); +void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_SlaveByteControlCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_SlaveAddressConfig(I2C_TypeDef* I2Cx, uint16_t Address); +void I2C_10BitAddressingModeCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); + +/* Communications handling functions ******************************************/ +void I2C_AutoEndCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_ReloadCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_NumberOfBytesConfig(I2C_TypeDef* I2Cx, uint8_t Number_Bytes); +void I2C_MasterRequestConfig(I2C_TypeDef* I2Cx, uint16_t I2C_Direction); +void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_10BitAddressHeaderCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState); +uint8_t I2C_GetAddressMatched(I2C_TypeDef* I2Cx); +uint16_t I2C_GetTransferDirection(I2C_TypeDef* I2Cx); +void I2C_TransferHandling(I2C_TypeDef* I2Cx, uint16_t Address, uint8_t Number_Bytes, uint32_t ReloadEndMode, uint32_t StartStopMode); + +/* SMBUS management functions ************************************************/ +void I2C_SMBusAlertCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_ClockTimeoutCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_ExtendedClockTimeoutCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_IdleClockTimeoutCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_TimeoutAConfig(I2C_TypeDef* I2Cx, uint16_t Timeout); +void I2C_TimeoutBConfig(I2C_TypeDef* I2Cx, uint16_t Timeout); +void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_PECRequestCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx); + +/* I2C registers management functions *****************************************/ +uint32_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register); + +/* Data transfers management functions ****************************************/ +void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data); +uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx); + +/* DMA transfers management functions *****************************************/ +void I2C_DMACmd(I2C_TypeDef* I2Cx, uint32_t I2C_DMAReq, FunctionalState NewState); + +/* Interrupts and flags management functions **********************************/ +FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG); +void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG); +ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT); +void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT); + + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F30x_I2C_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_iwdg.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_iwdg.h new file mode 100644 index 0000000..6469db4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_iwdg.h @@ -0,0 +1,153 @@ +/** + ****************************************************************************** + * @file stm32f30x_iwdg.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the IWDG + * firmware library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_IWDG_H +#define __STM32F30x_IWDG_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup IWDG + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup IWDG_Exported_Constants + * @{ + */ + +/** @defgroup IWDG_WriteAccess + * @{ + */ + +#define IWDG_WriteAccess_Enable ((uint16_t)0x5555) +#define IWDG_WriteAccess_Disable ((uint16_t)0x0000) +#define IS_IWDG_WRITE_ACCESS(ACCESS) (((ACCESS) == IWDG_WriteAccess_Enable) || \ + ((ACCESS) == IWDG_WriteAccess_Disable)) +/** + * @} + */ + +/** @defgroup IWDG_prescaler + * @{ + */ + +#define IWDG_Prescaler_4 ((uint8_t)0x00) +#define IWDG_Prescaler_8 ((uint8_t)0x01) +#define IWDG_Prescaler_16 ((uint8_t)0x02) +#define IWDG_Prescaler_32 ((uint8_t)0x03) +#define IWDG_Prescaler_64 ((uint8_t)0x04) +#define IWDG_Prescaler_128 ((uint8_t)0x05) +#define IWDG_Prescaler_256 ((uint8_t)0x06) +#define IS_IWDG_PRESCALER(PRESCALER) (((PRESCALER) == IWDG_Prescaler_4) || \ + ((PRESCALER) == IWDG_Prescaler_8) || \ + ((PRESCALER) == IWDG_Prescaler_16) || \ + ((PRESCALER) == IWDG_Prescaler_32) || \ + ((PRESCALER) == IWDG_Prescaler_64) || \ + ((PRESCALER) == IWDG_Prescaler_128)|| \ + ((PRESCALER) == IWDG_Prescaler_256)) +/** + * @} + */ + +/** @defgroup IWDG_Flag + * @{ + */ + +#define IWDG_FLAG_PVU ((uint16_t)0x0001) +#define IWDG_FLAG_RVU ((uint16_t)0x0002) +#define IWDG_FLAG_WVU ((uint16_t)0x0002) +#define IS_IWDG_FLAG(FLAG) (((FLAG) == IWDG_FLAG_PVU) || ((FLAG) == IWDG_FLAG_RVU) || \ + ((FLAG) == IWDG_FLAG_WVU)) +/** + * @} + */ + +/** @defgroup IWDG_Reload_Value + * @{ + */ +#define IS_IWDG_RELOAD(RELOAD) ((RELOAD) <= 0xFFF) + +/** + * @} + */ + +/** @defgroup IWDG_CounterWindow_Value + * @{ + */ +#define IS_IWDG_WINDOW_VALUE(VALUE) ((VALUE) <= 0xFFF) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* Prescaler and Counter configuration functions ******************************/ +void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess); +void IWDG_SetPrescaler(uint8_t IWDG_Prescaler); +void IWDG_SetReload(uint16_t Reload); +void IWDG_ReloadCounter(void); +void IWDG_SetWindowValue(uint16_t WindowValue); + +/* IWDG activation function ***************************************************/ +void IWDG_Enable(void); + +/* Flag management function ***************************************************/ +FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F30x_IWDG_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_misc.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_misc.h new file mode 100644 index 0000000..f65b478 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_misc.h @@ -0,0 +1,204 @@ +/** + ****************************************************************************** + * @file stm32f30x_misc.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the miscellaneous + * firmware library functions (add-on to CMSIS functions). + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_MISC_H +#define __STM32F30x_MISC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup MISC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief NVIC Init Structure definition + */ + +typedef struct +{ + uint8_t NVIC_IRQChannel; /*!< Specifies the IRQ channel to be enabled or disabled. + This parameter can be a value of @ref IRQn_Type (For + the complete STM32 Devices IRQ Channels list, please + refer to stm32f30x.h file) */ + + uint8_t NVIC_IRQChannelPreemptionPriority; /*!< Specifies the pre-emption priority for the IRQ channel + specified in NVIC_IRQChannel. This parameter can be a value + between 0 and 15. + A lower priority value indicates a higher priority */ + + + uint8_t NVIC_IRQChannelSubPriority; /*!< Specifies the subpriority level for the IRQ channel specified + in NVIC_IRQChannel. This parameter can be a value + between 0 and 15. + A lower priority value indicates a higher priority */ + + FunctionalState NVIC_IRQChannelCmd; /*!< Specifies whether the IRQ channel defined in NVIC_IRQChannel + will be enabled or disabled. + This parameter can be set either to ENABLE or DISABLE */ +} NVIC_InitTypeDef; + +/** + * +@verbatim + The table below gives the allowed values of the pre-emption priority and subpriority according + to the Priority Grouping configuration performed by NVIC_PriorityGroupConfig function + ============================================================================================================================ + NVIC_PriorityGroup | NVIC_IRQChannelPreemptionPriority | NVIC_IRQChannelSubPriority | Description + ============================================================================================================================ + NVIC_PriorityGroup_0 | 0 | 0-15 | 0 bits for pre-emption priority + | | | 4 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_1 | 0-1 | 0-7 | 1 bits for pre-emption priority + | | | 3 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_2 | 0-3 | 0-3 | 2 bits for pre-emption priority + | | | 2 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_3 | 0-7 | 0-1 | 3 bits for pre-emption priority + | | | 1 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_4 | 0-15 | 0 | 4 bits for pre-emption priority + | | | 0 bits for subpriority + ============================================================================================================================ +@endverbatim +*/ + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup MISC_Exported_Constants + * @{ + */ + +/** @defgroup MISC_Vector_Table_Base + * @{ + */ + +#define NVIC_VectTab_RAM ((uint32_t)0x20000000) +#define NVIC_VectTab_FLASH ((uint32_t)0x08000000) +#define IS_NVIC_VECTTAB(VECTTAB) (((VECTTAB) == NVIC_VectTab_RAM) || \ + ((VECTTAB) == NVIC_VectTab_FLASH)) +/** + * @} + */ + +/** @defgroup MISC_System_Low_Power + * @{ + */ + +#define NVIC_LP_SEVONPEND ((uint8_t)0x10) +#define NVIC_LP_SLEEPDEEP ((uint8_t)0x04) +#define NVIC_LP_SLEEPONEXIT ((uint8_t)0x02) +#define IS_NVIC_LP(LP) (((LP) == NVIC_LP_SEVONPEND) || \ + ((LP) == NVIC_LP_SLEEPDEEP) || \ + ((LP) == NVIC_LP_SLEEPONEXIT)) +/** + * @} + */ + +/** @defgroup MISC_Preemption_Priority_Group + * @{ + */ + +#define NVIC_PriorityGroup_0 ((uint32_t)0x700) /*!< 0 bits for pre-emption priority + 4 bits for subpriority */ +#define NVIC_PriorityGroup_1 ((uint32_t)0x600) /*!< 1 bits for pre-emption priority + 3 bits for subpriority */ +#define NVIC_PriorityGroup_2 ((uint32_t)0x500) /*!< 2 bits for pre-emption priority + 2 bits for subpriority */ +#define NVIC_PriorityGroup_3 ((uint32_t)0x400) /*!< 3 bits for pre-emption priority + 1 bits for subpriority */ +#define NVIC_PriorityGroup_4 ((uint32_t)0x300) /*!< 4 bits for pre-emption priority + 0 bits for subpriority */ + +#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PriorityGroup_0) || \ + ((GROUP) == NVIC_PriorityGroup_1) || \ + ((GROUP) == NVIC_PriorityGroup_2) || \ + ((GROUP) == NVIC_PriorityGroup_3) || \ + ((GROUP) == NVIC_PriorityGroup_4)) + +#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x10) + +#define IS_NVIC_SUB_PRIORITY(PRIORITY) ((PRIORITY) < 0x10) + +#define IS_NVIC_OFFSET(OFFSET) ((OFFSET) < 0x000FFFFF) + +/** + * @} + */ + +/** @defgroup MISC_SysTick_clock_source + */ + +#define SysTick_CLKSource_HCLK_Div8 ((uint32_t)0xFFFFFFFB) +#define SysTick_CLKSource_HCLK ((uint32_t)0x00000004) +#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SysTick_CLKSource_HCLK) || \ + ((SOURCE) == SysTick_CLKSource_HCLK_Div8)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup); +void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct); +void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset); +void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState); +void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F30x_MISC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_opamp.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_opamp.h new file mode 100644 index 0000000..f1e170e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_opamp.h @@ -0,0 +1,277 @@ +/** + ****************************************************************************** + * @file stm32f30x_opamp.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the operational + * amplifiers (OPAMP) firmware library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_OPAMP_H +#define __STM32F30x_OPAMP_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup OPAMP + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief OPAMP Init structure definition + */ + +typedef struct +{ + + uint32_t OPAMP_InvertingInput; /*!< Selects the inverting input of the operational amplifier. + This parameter can be a value of @ref OPAMP_InvertingInput */ + + uint32_t OPAMP_NonInvertingInput; /*!< Selects the non inverting input of the operational amplifier. + This parameter can be a value of @ref OPAMP_NonInvertingInput */ + +}OPAMP_InitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup OPAMP_Exported_Constants + * @{ + */ + +/** @defgroup OPAMP_Selection + * @{ + */ + +#define OPAMP_Selection_OPAMP1 ((uint32_t)0x00000000) /*!< OPAMP1 Selection */ +#define OPAMP_Selection_OPAMP2 ((uint32_t)0x00000004) /*!< OPAMP2 Selection */ +#define OPAMP_Selection_OPAMP3 ((uint32_t)0x00000008) /*!< OPAMP3 Selection */ +#define OPAMP_Selection_OPAMP4 ((uint32_t)0x0000000C) /*!< OPAMP4 Selection */ + +#define IS_OPAMP_ALL_PERIPH(PERIPH) (((PERIPH) == OPAMP_Selection_OPAMP1) || \ + ((PERIPH) == OPAMP_Selection_OPAMP2) || \ + ((PERIPH) == OPAMP_Selection_OPAMP3) || \ + ((PERIPH) == OPAMP_Selection_OPAMP4)) + +/** + * @} + */ + +/** @defgroup OPAMP_InvertingInput + * @{ + */ + +#define OPAMP_InvertingInput_IO1 ((uint32_t)0x00000000) /*!< IO1 (PC5 for OPAMP1 and OPAMP2, PB10 for OPAMP3 and OPAMP4) + connected to OPAMPx inverting input */ +#define OPAMP_InvertingInput_IO2 OPAMP_CSR_VMSEL_0 /*!< IO2 (PA3 for OPAMP1, PA5 for OPAMP2, PB2 for OPAMP3, PD8 for OPAMP4) + connected to OPAMPx inverting input */ +#define OPAMP_InvertingInput_PGA OPAMP_CSR_VMSEL_1 /*!< Resistor feedback output connected to OPAMPx inverting input (PGA mode) */ +#define OPAMP_InvertingInput_Vout OPAMP_CSR_VMSEL /*!< Vout connected to OPAMPx inverting input (follower mode) */ + +#define IS_OPAMP_INVERTING_INPUT(INPUT) (((INPUT) == OPAMP_InvertingInput_IO1) || \ + ((INPUT) == OPAMP_InvertingInput_IO2) || \ + ((INPUT) == OPAMP_InvertingInput_PGA) || \ + ((INPUT) == OPAMP_InvertingInput_Vout)) +/** + * @} + */ + +/** @defgroup OPAMP_NonInvertingInput + * @{ + */ + +#define OPAMP_NonInvertingInput_IO1 ((uint32_t)0x00000000) /*!< IO1 (PA7 for OPAMP1, PD14 for OPAMP2, PB13 for OPAMP3, PD11 for OPAMP4) + connected to OPAMPx non inverting input */ +#define OPAMP_NonInvertingInput_IO2 OPAMP_CSR_VPSEL_0 /*!< IO2 (PA5 for OPAMP1, PB14 for OPAMP2, PA5 for OPAMP3, PB11 for OPAMP4) + connected to OPAMPx non inverting input */ +#define OPAMP_NonInvertingInput_IO3 OPAMP_CSR_VPSEL_1 /*!< IO3 (PA3 for OPAMP1, PB0 for OPAMP2, PA1 for OPAMP3, PA4 for OPAMP4) + connected to OPAMPx non inverting input */ +#define OPAMP_NonInvertingInput_IO4 OPAMP_CSR_VPSEL /*!< IO4 (PA1 for OPAMP1, PA7 for OPAMP2, PB0 for OPAMP3, PB13 for OPAMP4) + connected to OPAMPx non inverting input */ + +#define IS_OPAMP_NONINVERTING_INPUT(INPUT) (((INPUT) == OPAMP_NonInvertingInput_IO1) || \ + ((INPUT) == OPAMP_NonInvertingInput_IO2) || \ + ((INPUT) == OPAMP_NonInvertingInput_IO3) || \ + ((INPUT) == OPAMP_NonInvertingInput_IO4)) +/** + * @} + */ + +/** @defgroup OPAMP_PGAGain_Config + * @{ + */ + +#define OPAMP_OPAMP_PGAGain_2 ((uint32_t)0x00000000) +#define OPAMP_OPAMP_PGAGain_4 OPAMP_CSR_PGGAIN_0 +#define OPAMP_OPAMP_PGAGain_8 OPAMP_CSR_PGGAIN_1 +#define OPAMP_OPAMP_PGAGain_16 ((uint32_t)0x0000C000) + +#define IS_OPAMP_PGAGAIN(GAIN) (((GAIN) == OPAMP_OPAMP_PGAGain_2) || \ + ((GAIN) == OPAMP_OPAMP_PGAGain_4) || \ + ((GAIN) == OPAMP_OPAMP_PGAGain_8) || \ + ((GAIN) == OPAMP_OPAMP_PGAGain_16)) +/** + * @} + */ + +/** @defgroup OPAMP_PGAConnect_Config + * @{ + */ + +#define OPAMP_PGAConnect_No ((uint32_t)0x00000000) +#define OPAMP_PGAConnect_IO1 OPAMP_CSR_PGGAIN_3 +#define OPAMP_PGAConnect_IO2 ((uint32_t)0x00030000) + +#define IS_OPAMP_PGACONNECT(CONNECT) (((CONNECT) == OPAMP_PGAConnect_No) || \ + ((CONNECT) == OPAMP_PGAConnect_IO1) || \ + ((CONNECT) == OPAMP_PGAConnect_IO2)) +/** + * @} + */ + +/** @defgroup OPAMP_SecondaryInvertingInput + * @{ + */ + +#define IS_OPAMP_SECONDARY_INVINPUT(INVINPUT) (((INVINPUT) == OPAMP_InvertingInput_IO1) || \ + ((INVINPUT) == OPAMP_InvertingInput_IO2)) +/** + * @} + */ + +/** @defgroup OPAMP_Input + * @{ + */ + +#define OPAMP_Input_Inverting ((uint32_t)0x00000018) /*!< Inverting input */ +#define OPAMP_Input_NonInverting ((uint32_t)0x00000013) /*!< Non inverting input */ + +#define IS_OPAMP_INPUT(INPUT) (((INPUT) == OPAMP_Input_Inverting) || \ + ((INPUT) == OPAMP_Input_NonInverting)) + +/** + * @} + */ + +/** @defgroup OPAMP_Vref + * @{ + */ + +#define OPAMP_Vref_3VDDA ((uint32_t)0x00000000) /*!< OPMAP Vref = 3.3% VDDA */ +#define OPAMP_Vref_10VDDA OPAMP_CSR_CALSEL_0 /*!< OPMAP Vref = 10% VDDA */ +#define OPAMP_Vref_50VDDA OPAMP_CSR_CALSEL_1 /*!< OPMAP Vref = 50% VDDA */ +#define OPAMP_Vref_90VDDA OPAMP_CSR_CALSEL /*!< OPMAP Vref = 90% VDDA */ + +#define IS_OPAMP_VREF(VREF) (((VREF) == OPAMP_Vref_3VDDA) || \ + ((VREF) == OPAMP_Vref_10VDDA) || \ + ((VREF) == OPAMP_Vref_50VDDA) || \ + ((VREF) == OPAMP_Vref_90VDDA)) + +/** + * @} + */ + +/** @defgroup OPAMP_Trimming + */ + +#define OPAMP_Trimming_Factory ((uint32_t)0x00000000) /*!< Factory trimming */ +#define OPAMP_Trimming_User OPAMP_CSR_USERTRIM /*!< User trimming */ + +#define IS_OPAMP_TRIMMING(TRIMMING) (((TRIMMING) == OPAMP_Trimming_Factory) || \ + ((TRIMMING) == OPAMP_Trimming_User)) + +/** + * @} + */ + +/** @defgroup OPAMP_TrimValue + * @{ + */ + +#define IS_OPAMP_TRIMMINGVALUE(VALUE) ((VALUE) <= 0x0000001F) /*!< Trimming value */ + +/** + * @} + */ + +/** @defgroup OPAMP_OutputLevel + * @{ + */ + +#define OPAMP_OutputLevel_High OPAMP_CSR_OUTCAL +#define OPAMP_OutputLevel_Low ((uint32_t)0x00000000) + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +/* Function used to set the OPAMP configuration to the default reset state ***/ +void OPAMP_DeInit(uint32_t OPAMP_Selection); + +/* Initialization and Configuration functions *********************************/ +void OPAMP_Init(uint32_t OPAMP_Selection, OPAMP_InitTypeDef* OPAMP_InitStruct); +void OPAMP_StructInit(OPAMP_InitTypeDef* OPAMP_InitStruct); +void OPAMP_PGAConfig(uint32_t OPAMP_Selection, uint32_t OPAMP_PGAGain, uint32_t OPAMP_PGAConnect); +void OPAMP_VrefConfig(uint32_t OPAMP_Selection, uint32_t OPAMP_Vref); +void OPAMP_VrefConnectADCCmd(uint32_t OPAMP_Selection, FunctionalState NewState); +void OPAMP_TimerControlledMuxConfig(uint32_t OPAMP_Selection, OPAMP_InitTypeDef* OPAMP_InitStruct); +void OPAMP_TimerControlledMuxCmd(uint32_t OPAMP_Selection, FunctionalState NewState); +void OPAMP_Cmd(uint32_t OPAMP_Selection, FunctionalState NewState); +uint32_t OPAMP_GetOutputLevel(uint32_t OPAMP_Selection); + +/* Calibration functions ******************************************************/ +void OPAMP_VrefConnectNonInvertingInput(uint32_t OPAMP_Selection, FunctionalState NewState); +void OPAMP_OffsetTrimModeSelect(uint32_t OPAMP_Selection, uint32_t OPAMP_Trimming); +void OPAMP_OffsetTrimConfig(uint32_t OPAMP_Selection, uint32_t OPAMP_Input, uint32_t OPAMP_TrimValue); +void OPAMP_StartCalibration(uint32_t OPAMP_Selection, FunctionalState NewState); + +/* OPAMP configuration locking function ***************************************/ +void OPAMP_LockConfig(uint32_t OPAMP_Selection); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F30x_OPAMP_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_pwr.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_pwr.h new file mode 100644 index 0000000..caffbbd --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_pwr.h @@ -0,0 +1,187 @@ +/** + ****************************************************************************** + * @file stm32f30x_pwr.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the PWR firmware + * library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_PWR_H +#define __STM32F30x_PWR_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup PWR + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup PWR_Exported_Constants + * @{ + */ + +/** @defgroup PWR_PVD_detection_level + * @{ + */ + +#define PWR_PVDLevel_0 PWR_CR_PLS_LEV0 +#define PWR_PVDLevel_1 PWR_CR_PLS_LEV1 +#define PWR_PVDLevel_2 PWR_CR_PLS_LEV2 +#define PWR_PVDLevel_3 PWR_CR_PLS_LEV3 +#define PWR_PVDLevel_4 PWR_CR_PLS_LEV4 +#define PWR_PVDLevel_5 PWR_CR_PLS_LEV5 +#define PWR_PVDLevel_6 PWR_CR_PLS_LEV6 +#define PWR_PVDLevel_7 PWR_CR_PLS_LEV7 + +#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLevel_0) || ((LEVEL) == PWR_PVDLevel_1)|| \ + ((LEVEL) == PWR_PVDLevel_2) || ((LEVEL) == PWR_PVDLevel_3)|| \ + ((LEVEL) == PWR_PVDLevel_4) || ((LEVEL) == PWR_PVDLevel_5)|| \ + ((LEVEL) == PWR_PVDLevel_6) || ((LEVEL) == PWR_PVDLevel_7)) +/** + * @} + */ + +/** @defgroup PWR_WakeUp_Pins + * @{ + */ + +#define PWR_WakeUpPin_1 PWR_CSR_EWUP1 +#define PWR_WakeUpPin_2 PWR_CSR_EWUP2 +#define PWR_WakeUpPin_3 PWR_CSR_EWUP3 +#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WakeUpPin_1) || \ + ((PIN) == PWR_WakeUpPin_2) || \ + ((PIN) == PWR_WakeUpPin_3)) +/** + * @} + */ + + +/** @defgroup PWR_Regulator_state_is_Sleep_STOP_mode + * @{ + */ + +#define PWR_Regulator_ON ((uint32_t)0x00000000) +#define PWR_Regulator_LowPower PWR_CR_LPSDSR +#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_Regulator_ON) || \ + ((REGULATOR) == PWR_Regulator_LowPower)) +/** + * @} + */ + +/** @defgroup PWR_SLEEP_mode_entry + * @{ + */ + +#define PWR_SLEEPEntry_WFI ((uint8_t)0x01) +#define PWR_SLEEPEntry_WFE ((uint8_t)0x02) +#define IS_PWR_SLEEP_ENTRY(ENTRY) (((ENTRY) == PWR_SLEEPEntry_WFI) || ((ENTRY) == PWR_SLEEPEntry_WFE)) + +/** + * @} + */ + +/** @defgroup PWR_STOP_mode_entry + * @{ + */ + +#define PWR_STOPEntry_WFI ((uint8_t)0x01) +#define PWR_STOPEntry_WFE ((uint8_t)0x02) +#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPEntry_WFI) || ((ENTRY) == PWR_STOPEntry_WFE)) + +/** + * @} + */ + +/** @defgroup PWR_Flag + * @{ + */ + +#define PWR_FLAG_WU PWR_CSR_WUF +#define PWR_FLAG_SB PWR_CSR_SBF +#define PWR_FLAG_PVDO PWR_CSR_PVDO +#define PWR_FLAG_VREFINTRDY PWR_CSR_VREFINTRDYF + +#define IS_PWR_GET_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB) || \ + ((FLAG) == PWR_FLAG_PVDO) || ((FLAG) == PWR_FLAG_VREFINTRDY)) + +#define IS_PWR_CLEAR_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB)) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +/* Function used to set the PWR configuration to the default reset state ******/ +void PWR_DeInit(void); + +/* Backup Domain Access function **********************************************/ +void PWR_BackupAccessCmd(FunctionalState NewState); + +/* PVD configuration functions ************************************************/ +void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel); +void PWR_PVDCmd(FunctionalState NewState); + +/* WakeUp pins configuration functions ****************************************/ +void PWR_WakeUpPinCmd(uint32_t PWR_WakeUpPin, FunctionalState NewState); + +/* Low Power modes configuration functions ************************************/ +void PWR_EnterSleepMode(uint8_t PWR_SLEEPEntry); +void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry); +void PWR_EnterSTANDBYMode(void); + +/* Flags management functions *************************************************/ +FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG); +void PWR_ClearFlag(uint32_t PWR_FLAG); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F30x_PWR_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_rcc.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_rcc.h new file mode 100644 index 0000000..189214b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_rcc.h @@ -0,0 +1,699 @@ +/** + ****************************************************************************** + * @file stm32f30x_rcc.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the RCC + * firmware library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_RCC_H +#define __STM32F30x_RCC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup RCC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +typedef struct +{ + uint32_t SYSCLK_Frequency; + uint32_t HCLK_Frequency; + uint32_t PCLK1_Frequency; + uint32_t PCLK2_Frequency; + uint32_t ADC12CLK_Frequency; + uint32_t ADC34CLK_Frequency; + uint32_t I2C1CLK_Frequency; + uint32_t I2C2CLK_Frequency; + uint32_t I2C3CLK_Frequency; + uint32_t TIM1CLK_Frequency; + uint32_t HRTIM1CLK_Frequency; + uint32_t TIM8CLK_Frequency; + uint32_t USART1CLK_Frequency; + uint32_t USART2CLK_Frequency; + uint32_t USART3CLK_Frequency; + uint32_t UART4CLK_Frequency; + uint32_t UART5CLK_Frequency; + uint32_t TIM15CLK_Frequency; + uint32_t TIM16CLK_Frequency; + uint32_t TIM17CLK_Frequency; +}RCC_ClocksTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup RCC_Exported_Constants + * @{ + */ + +/** @defgroup RCC_HSE_configuration + * @{ + */ + +#define RCC_HSE_OFF ((uint8_t)0x00) +#define RCC_HSE_ON ((uint8_t)0x01) +#define RCC_HSE_Bypass ((uint8_t)0x05) +#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \ + ((HSE) == RCC_HSE_Bypass)) + +/** + * @} + */ + +/** @defgroup RCC_PLL_Clock_Source + * @{ + */ + +#define RCC_PLLSource_HSI_Div2 RCC_CFGR_PLLSRC_HSI_Div2 +#define RCC_PLLSource_PREDIV1 RCC_CFGR_PLLSRC_PREDIV1 + +#define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \ + ((SOURCE) == RCC_PLLSource_PREDIV1)) +/** + * @} + */ + +/** @defgroup RCC_PLL_Multiplication_Factor + * @{ + */ + +#define RCC_PLLMul_2 RCC_CFGR_PLLMULL2 +#define RCC_PLLMul_3 RCC_CFGR_PLLMULL3 +#define RCC_PLLMul_4 RCC_CFGR_PLLMULL4 +#define RCC_PLLMul_5 RCC_CFGR_PLLMULL5 +#define RCC_PLLMul_6 RCC_CFGR_PLLMULL6 +#define RCC_PLLMul_7 RCC_CFGR_PLLMULL7 +#define RCC_PLLMul_8 RCC_CFGR_PLLMULL8 +#define RCC_PLLMul_9 RCC_CFGR_PLLMULL9 +#define RCC_PLLMul_10 RCC_CFGR_PLLMULL10 +#define RCC_PLLMul_11 RCC_CFGR_PLLMULL11 +#define RCC_PLLMul_12 RCC_CFGR_PLLMULL12 +#define RCC_PLLMul_13 RCC_CFGR_PLLMULL13 +#define RCC_PLLMul_14 RCC_CFGR_PLLMULL14 +#define RCC_PLLMul_15 RCC_CFGR_PLLMULL15 +#define RCC_PLLMul_16 RCC_CFGR_PLLMULL16 +#define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_2) || ((MUL) == RCC_PLLMul_3) || \ + ((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \ + ((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \ + ((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \ + ((MUL) == RCC_PLLMul_10) || ((MUL) == RCC_PLLMul_11) || \ + ((MUL) == RCC_PLLMul_12) || ((MUL) == RCC_PLLMul_13) || \ + ((MUL) == RCC_PLLMul_14) || ((MUL) == RCC_PLLMul_15) || \ + ((MUL) == RCC_PLLMul_16)) +/** + * @} + */ + +/** @defgroup RCC_PREDIV1_division_factor + * @{ + */ +#define RCC_PREDIV1_Div1 RCC_CFGR2_PREDIV1_DIV1 +#define RCC_PREDIV1_Div2 RCC_CFGR2_PREDIV1_DIV2 +#define RCC_PREDIV1_Div3 RCC_CFGR2_PREDIV1_DIV3 +#define RCC_PREDIV1_Div4 RCC_CFGR2_PREDIV1_DIV4 +#define RCC_PREDIV1_Div5 RCC_CFGR2_PREDIV1_DIV5 +#define RCC_PREDIV1_Div6 RCC_CFGR2_PREDIV1_DIV6 +#define RCC_PREDIV1_Div7 RCC_CFGR2_PREDIV1_DIV7 +#define RCC_PREDIV1_Div8 RCC_CFGR2_PREDIV1_DIV8 +#define RCC_PREDIV1_Div9 RCC_CFGR2_PREDIV1_DIV9 +#define RCC_PREDIV1_Div10 RCC_CFGR2_PREDIV1_DIV10 +#define RCC_PREDIV1_Div11 RCC_CFGR2_PREDIV1_DIV11 +#define RCC_PREDIV1_Div12 RCC_CFGR2_PREDIV1_DIV12 +#define RCC_PREDIV1_Div13 RCC_CFGR2_PREDIV1_DIV13 +#define RCC_PREDIV1_Div14 RCC_CFGR2_PREDIV1_DIV14 +#define RCC_PREDIV1_Div15 RCC_CFGR2_PREDIV1_DIV15 +#define RCC_PREDIV1_Div16 RCC_CFGR2_PREDIV1_DIV16 + +#define IS_RCC_PREDIV1(PREDIV1) (((PREDIV1) == RCC_PREDIV1_Div1) || ((PREDIV1) == RCC_PREDIV1_Div2) || \ + ((PREDIV1) == RCC_PREDIV1_Div3) || ((PREDIV1) == RCC_PREDIV1_Div4) || \ + ((PREDIV1) == RCC_PREDIV1_Div5) || ((PREDIV1) == RCC_PREDIV1_Div6) || \ + ((PREDIV1) == RCC_PREDIV1_Div7) || ((PREDIV1) == RCC_PREDIV1_Div8) || \ + ((PREDIV1) == RCC_PREDIV1_Div9) || ((PREDIV1) == RCC_PREDIV1_Div10) || \ + ((PREDIV1) == RCC_PREDIV1_Div11) || ((PREDIV1) == RCC_PREDIV1_Div12) || \ + ((PREDIV1) == RCC_PREDIV1_Div13) || ((PREDIV1) == RCC_PREDIV1_Div14) || \ + ((PREDIV1) == RCC_PREDIV1_Div15) || ((PREDIV1) == RCC_PREDIV1_Div16)) +/** + * @} + */ + +/** @defgroup RCC_System_Clock_Source + * @{ + */ + +#define RCC_SYSCLKSource_HSI RCC_CFGR_SW_HSI +#define RCC_SYSCLKSource_HSE RCC_CFGR_SW_HSE +#define RCC_SYSCLKSource_PLLCLK RCC_CFGR_SW_PLL +#define IS_RCC_SYSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSource_HSI) || \ + ((SOURCE) == RCC_SYSCLKSource_HSE) || \ + ((SOURCE) == RCC_SYSCLKSource_PLLCLK)) +/** + * @} + */ + +/** @defgroup RCC_AHB_Clock_Source + * @{ + */ + +#define RCC_SYSCLK_Div1 RCC_CFGR_HPRE_DIV1 +#define RCC_SYSCLK_Div2 RCC_CFGR_HPRE_DIV2 +#define RCC_SYSCLK_Div4 RCC_CFGR_HPRE_DIV4 +#define RCC_SYSCLK_Div8 RCC_CFGR_HPRE_DIV8 +#define RCC_SYSCLK_Div16 RCC_CFGR_HPRE_DIV16 +#define RCC_SYSCLK_Div64 RCC_CFGR_HPRE_DIV64 +#define RCC_SYSCLK_Div128 RCC_CFGR_HPRE_DIV128 +#define RCC_SYSCLK_Div256 RCC_CFGR_HPRE_DIV256 +#define RCC_SYSCLK_Div512 RCC_CFGR_HPRE_DIV512 +#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_Div1) || ((HCLK) == RCC_SYSCLK_Div2) || \ + ((HCLK) == RCC_SYSCLK_Div4) || ((HCLK) == RCC_SYSCLK_Div8) || \ + ((HCLK) == RCC_SYSCLK_Div16) || ((HCLK) == RCC_SYSCLK_Div64) || \ + ((HCLK) == RCC_SYSCLK_Div128) || ((HCLK) == RCC_SYSCLK_Div256) || \ + ((HCLK) == RCC_SYSCLK_Div512)) +/** + * @} + */ + +/** @defgroup RCC_APB1_APB2_clock_source + * @{ + */ + +#define RCC_HCLK_Div1 ((uint32_t)0x00000000) +#define RCC_HCLK_Div2 ((uint32_t)0x00000400) +#define RCC_HCLK_Div4 ((uint32_t)0x00000500) +#define RCC_HCLK_Div8 ((uint32_t)0x00000600) +#define RCC_HCLK_Div16 ((uint32_t)0x00000700) +#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_Div1) || ((PCLK) == RCC_HCLK_Div2) || \ + ((PCLK) == RCC_HCLK_Div4) || ((PCLK) == RCC_HCLK_Div8) || \ + ((PCLK) == RCC_HCLK_Div16)) +/** + * @} + */ + +/** @defgroup RCC_ADC_clock_source + * @{ + */ + +/* ADC1 & ADC2 */ +#define RCC_ADC12PLLCLK_OFF ((uint32_t)0x00000000) +#define RCC_ADC12PLLCLK_Div1 ((uint32_t)0x00000100) +#define RCC_ADC12PLLCLK_Div2 ((uint32_t)0x00000110) +#define RCC_ADC12PLLCLK_Div4 ((uint32_t)0x00000120) +#define RCC_ADC12PLLCLK_Div6 ((uint32_t)0x00000130) +#define RCC_ADC12PLLCLK_Div8 ((uint32_t)0x00000140) +#define RCC_ADC12PLLCLK_Div10 ((uint32_t)0x00000150) +#define RCC_ADC12PLLCLK_Div12 ((uint32_t)0x00000160) +#define RCC_ADC12PLLCLK_Div16 ((uint32_t)0x00000170) +#define RCC_ADC12PLLCLK_Div32 ((uint32_t)0x00000180) +#define RCC_ADC12PLLCLK_Div64 ((uint32_t)0x00000190) +#define RCC_ADC12PLLCLK_Div128 ((uint32_t)0x000001A0) +#define RCC_ADC12PLLCLK_Div256 ((uint32_t)0x000001B0) + +/* ADC3 & ADC4 */ +#define RCC_ADC34PLLCLK_OFF ((uint32_t)0x10000000) +#define RCC_ADC34PLLCLK_Div1 ((uint32_t)0x10002000) +#define RCC_ADC34PLLCLK_Div2 ((uint32_t)0x10002200) +#define RCC_ADC34PLLCLK_Div4 ((uint32_t)0x10002400) +#define RCC_ADC34PLLCLK_Div6 ((uint32_t)0x10002600) +#define RCC_ADC34PLLCLK_Div8 ((uint32_t)0x10002800) +#define RCC_ADC34PLLCLK_Div10 ((uint32_t)0x10002A00) +#define RCC_ADC34PLLCLK_Div12 ((uint32_t)0x10002C00) +#define RCC_ADC34PLLCLK_Div16 ((uint32_t)0x10002E00) +#define RCC_ADC34PLLCLK_Div32 ((uint32_t)0x10003000) +#define RCC_ADC34PLLCLK_Div64 ((uint32_t)0x10003200) +#define RCC_ADC34PLLCLK_Div128 ((uint32_t)0x10003400) +#define RCC_ADC34PLLCLK_Div256 ((uint32_t)0x10003600) + +#define IS_RCC_ADCCLK(ADCCLK) (((ADCCLK) == RCC_ADC12PLLCLK_OFF) || ((ADCCLK) == RCC_ADC12PLLCLK_Div1) || \ + ((ADCCLK) == RCC_ADC12PLLCLK_Div2) || ((ADCCLK) == RCC_ADC12PLLCLK_Div4) || \ + ((ADCCLK) == RCC_ADC12PLLCLK_Div6) || ((ADCCLK) == RCC_ADC12PLLCLK_Div8) || \ + ((ADCCLK) == RCC_ADC12PLLCLK_Div10) || ((ADCCLK) == RCC_ADC12PLLCLK_Div12) || \ + ((ADCCLK) == RCC_ADC12PLLCLK_Div16) || ((ADCCLK) == RCC_ADC12PLLCLK_Div32) || \ + ((ADCCLK) == RCC_ADC12PLLCLK_Div64) || ((ADCCLK) == RCC_ADC12PLLCLK_Div128) || \ + ((ADCCLK) == RCC_ADC12PLLCLK_Div256) || ((ADCCLK) == RCC_ADC34PLLCLK_OFF) || \ + ((ADCCLK) == RCC_ADC34PLLCLK_Div1) || ((ADCCLK) == RCC_ADC34PLLCLK_Div2) || \ + ((ADCCLK) == RCC_ADC34PLLCLK_Div4) || ((ADCCLK) == RCC_ADC34PLLCLK_Div6) || \ + ((ADCCLK) == RCC_ADC34PLLCLK_Div8) || ((ADCCLK) == RCC_ADC34PLLCLK_Div10) || \ + ((ADCCLK) == RCC_ADC34PLLCLK_Div12) || ((ADCCLK) == RCC_ADC34PLLCLK_Div16) || \ + ((ADCCLK) == RCC_ADC34PLLCLK_Div32) || ((ADCCLK) == RCC_ADC34PLLCLK_Div64) || \ + ((ADCCLK) == RCC_ADC34PLLCLK_Div128) || ((ADCCLK) == RCC_ADC34PLLCLK_Div256)) + +/** + * @} + */ + +/** @defgroup RCC_TIM_clock_source + * @{ + */ + +#define RCC_TIM1CLK_HCLK ((uint32_t)0x00000000) +#define RCC_TIM1CLK_PLLCLK RCC_CFGR3_TIM1SW + +#define RCC_TIM8CLK_HCLK ((uint32_t)0x10000000) +#define RCC_TIM8CLK_PLLCLK ((uint32_t)0x10000200) + +#define RCC_TIM15CLK_HCLK ((uint32_t)0x20000000) +#define RCC_TIM15CLK_PLLCLK ((uint32_t)0x20000400) + +#define RCC_TIM16CLK_HCLK ((uint32_t)0x30000000) +#define RCC_TIM16CLK_PLLCLK ((uint32_t)0x30000800) + +#define RCC_TIM17CLK_HCLK ((uint32_t)0x40000000) +#define RCC_TIM17CLK_PLLCLK ((uint32_t)0x40002000) + +#define IS_RCC_TIMCLK(TIMCLK) (((TIMCLK) == RCC_TIM1CLK_HCLK) || ((TIMCLK) == RCC_TIM1CLK_PLLCLK) || \ + ((TIMCLK) == RCC_TIM8CLK_HCLK) || ((TIMCLK) == RCC_TIM8CLK_PLLCLK) || \ + ((TIMCLK) == RCC_TIM15CLK_HCLK) || ((TIMCLK) == RCC_TIM15CLK_PLLCLK) || \ + ((TIMCLK) == RCC_TIM16CLK_HCLK) || ((TIMCLK) == RCC_TIM16CLK_PLLCLK) || \ + ((TIMCLK) == RCC_TIM17CLK_HCLK) || ((TIMCLK) == RCC_TIM17CLK_PLLCLK)) + +/** + * @} + */ + +/** @defgroup RCC_HRTIM_clock_source + * @{ + */ + +#define RCC_HRTIM1CLK_HCLK ((uint32_t)0x00000000) +#define RCC_HRTIM1CLK_PLLCLK RCC_CFGR3_HRTIM1SW + +#define IS_RCC_HRTIMCLK(HRTIMCLK) (((HRTIMCLK) == RCC_HRTIM1CLK_HCLK) || ((HRTIMCLK) == RCC_HRTIM1CLK_PLLCLK)) + +/** + * @} + */ + +/** @defgroup RCC_I2C_clock_source + * @{ + */ + +#define RCC_I2C1CLK_HSI ((uint32_t)0x00000000) +#define RCC_I2C1CLK_SYSCLK RCC_CFGR3_I2C1SW + +#define RCC_I2C2CLK_HSI ((uint32_t)0x10000000) +#define RCC_I2C2CLK_SYSCLK ((uint32_t)0x10000020) + +#define RCC_I2C3CLK_HSI ((uint32_t)0x20000000) +#define RCC_I2C3CLK_SYSCLK ((uint32_t)0x20000040) + +#define IS_RCC_I2CCLK(I2CCLK) (((I2CCLK) == RCC_I2C1CLK_HSI) || ((I2CCLK) == RCC_I2C1CLK_SYSCLK) || \ + ((I2CCLK) == RCC_I2C2CLK_HSI) || ((I2CCLK) == RCC_I2C2CLK_SYSCLK) || \ + ((I2CCLK) == RCC_I2C3CLK_HSI) || ((I2CCLK) == RCC_I2C3CLK_SYSCLK)) + +/** + * @} + */ + +/** @defgroup RCC_USART_clock_source + * @{ + */ + +#define RCC_USART1CLK_PCLK ((uint32_t)0x10000000) +#define RCC_USART1CLK_SYSCLK ((uint32_t)0x10000001) +#define RCC_USART1CLK_LSE ((uint32_t)0x10000002) +#define RCC_USART1CLK_HSI ((uint32_t)0x10000003) + +#define RCC_USART2CLK_PCLK ((uint32_t)0x20000000) +#define RCC_USART2CLK_SYSCLK ((uint32_t)0x20010000) +#define RCC_USART2CLK_LSE ((uint32_t)0x20020000) +#define RCC_USART2CLK_HSI ((uint32_t)0x20030000) + +#define RCC_USART3CLK_PCLK ((uint32_t)0x30000000) +#define RCC_USART3CLK_SYSCLK ((uint32_t)0x30040000) +#define RCC_USART3CLK_LSE ((uint32_t)0x30080000) +#define RCC_USART3CLK_HSI ((uint32_t)0x300C0000) + +#define RCC_UART4CLK_PCLK ((uint32_t)0x40000000) +#define RCC_UART4CLK_SYSCLK ((uint32_t)0x40100000) +#define RCC_UART4CLK_LSE ((uint32_t)0x40200000) +#define RCC_UART4CLK_HSI ((uint32_t)0x40300000) + +#define RCC_UART5CLK_PCLK ((uint32_t)0x50000000) +#define RCC_UART5CLK_SYSCLK ((uint32_t)0x50400000) +#define RCC_UART5CLK_LSE ((uint32_t)0x50800000) +#define RCC_UART5CLK_HSI ((uint32_t)0x50C00000) + +#define IS_RCC_USARTCLK(USARTCLK) (((USARTCLK) == RCC_USART1CLK_PCLK) || ((USARTCLK) == RCC_USART1CLK_SYSCLK) || \ + ((USARTCLK) == RCC_USART1CLK_LSE) || ((USARTCLK) == RCC_USART1CLK_HSI) ||\ + ((USARTCLK) == RCC_USART2CLK_PCLK) || ((USARTCLK) == RCC_USART2CLK_SYSCLK) || \ + ((USARTCLK) == RCC_USART2CLK_LSE) || ((USARTCLK) == RCC_USART2CLK_HSI) || \ + ((USARTCLK) == RCC_USART3CLK_PCLK) || ((USARTCLK) == RCC_USART3CLK_SYSCLK) || \ + ((USARTCLK) == RCC_USART3CLK_LSE) || ((USARTCLK) == RCC_USART3CLK_HSI) || \ + ((USARTCLK) == RCC_UART4CLK_PCLK) || ((USARTCLK) == RCC_UART4CLK_SYSCLK) || \ + ((USARTCLK) == RCC_UART4CLK_LSE) || ((USARTCLK) == RCC_UART4CLK_HSI) || \ + ((USARTCLK) == RCC_UART5CLK_PCLK) || ((USARTCLK) == RCC_UART5CLK_SYSCLK) || \ + ((USARTCLK) == RCC_UART5CLK_LSE) || ((USARTCLK) == RCC_UART5CLK_HSI)) + +/** + * @} + */ + +/** @defgroup RCC_Interrupt_Source + * @{ + */ + +#define RCC_IT_LSIRDY ((uint8_t)0x01) +#define RCC_IT_LSERDY ((uint8_t)0x02) +#define RCC_IT_HSIRDY ((uint8_t)0x04) +#define RCC_IT_HSERDY ((uint8_t)0x08) +#define RCC_IT_PLLRDY ((uint8_t)0x10) +#define RCC_IT_CSS ((uint8_t)0x80) + +#define IS_RCC_IT(IT) ((((IT) & (uint8_t)0xC0) == 0x00) && ((IT) != 0x00)) + +#define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \ + ((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \ + ((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS)) + + +#define IS_RCC_CLEAR_IT(IT) ((((IT) & (uint8_t)0x40) == 0x00) && ((IT) != 0x00)) + +/** + * @} + */ + +/** @defgroup RCC_LSE_configuration + * @{ + */ + +#define RCC_LSE_OFF ((uint32_t)0x00000000) +#define RCC_LSE_ON RCC_BDCR_LSEON +#define RCC_LSE_Bypass ((uint32_t)(RCC_BDCR_LSEON | RCC_BDCR_LSEBYP)) +#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \ + ((LSE) == RCC_LSE_Bypass)) +/** + * @} + */ + +/** @defgroup RCC_RTC_Clock_Source + * @{ + */ + +#define RCC_RTCCLKSource_LSE RCC_BDCR_RTCSEL_LSE +#define RCC_RTCCLKSource_LSI RCC_BDCR_RTCSEL_LSI +#define RCC_RTCCLKSource_HSE_Div32 RCC_BDCR_RTCSEL_HSE + +#define IS_RCC_RTCCLK_SOURCE(SOURCE) (((SOURCE) == RCC_RTCCLKSource_LSE) || \ + ((SOURCE) == RCC_RTCCLKSource_LSI) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div32)) +/** + * @} + */ + +/** @defgroup RCC_I2S_Clock_Source + * @{ + */ +#define RCC_I2S2CLKSource_SYSCLK ((uint8_t)0x00) +#define RCC_I2S2CLKSource_Ext ((uint8_t)0x01) + +#define IS_RCC_I2SCLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S2CLKSource_SYSCLK) || ((SOURCE) == RCC_I2S2CLKSource_Ext)) + +/** @defgroup RCC_LSE_Drive_Configuration + * @{ + */ + +#define RCC_LSEDrive_Low ((uint32_t)0x00000000) +#define RCC_LSEDrive_MediumLow RCC_BDCR_LSEDRV_0 +#define RCC_LSEDrive_MediumHigh RCC_BDCR_LSEDRV_1 +#define RCC_LSEDrive_High RCC_BDCR_LSEDRV +#define IS_RCC_LSE_DRIVE(DRIVE) (((DRIVE) == RCC_LSEDrive_Low) || ((DRIVE) == RCC_LSEDrive_MediumLow) || \ + ((DRIVE) == RCC_LSEDrive_MediumHigh) || ((DRIVE) == RCC_LSEDrive_High)) +/** + * @} + */ + +/** @defgroup RCC_AHB_Peripherals + * @{ + */ + +#define RCC_AHBPeriph_ADC34 RCC_AHBENR_ADC34EN +#define RCC_AHBPeriph_ADC12 RCC_AHBENR_ADC12EN +#define RCC_AHBPeriph_GPIOA RCC_AHBENR_GPIOAEN +#define RCC_AHBPeriph_GPIOB RCC_AHBENR_GPIOBEN +#define RCC_AHBPeriph_GPIOC RCC_AHBENR_GPIOCEN +#define RCC_AHBPeriph_GPIOD RCC_AHBENR_GPIODEN +#define RCC_AHBPeriph_GPIOE RCC_AHBENR_GPIOEEN +#define RCC_AHBPeriph_GPIOF RCC_AHBENR_GPIOFEN +#define RCC_AHBPeriph_TS RCC_AHBENR_TSEN +#define RCC_AHBPeriph_CRC RCC_AHBENR_CRCEN +#define RCC_AHBPeriph_FLITF RCC_AHBENR_FLITFEN +#define RCC_AHBPeriph_SRAM RCC_AHBENR_SRAMEN +#define RCC_AHBPeriph_DMA2 RCC_AHBENR_DMA2EN +#define RCC_AHBPeriph_DMA1 RCC_AHBENR_DMA1EN + +#define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xCE81FFA8) == 0x00) && ((PERIPH) != 0x00)) +#define IS_RCC_AHB_RST_PERIPH(PERIPH) ((((PERIPH) & 0xCE81FFFF) == 0x00) && ((PERIPH) != 0x00)) + +/** + * @} + */ + +/** @defgroup RCC_APB2_Peripherals + * @{ + */ + +#define RCC_APB2Periph_SYSCFG RCC_APB2ENR_SYSCFGEN +#define RCC_APB2Periph_TIM1 RCC_APB2ENR_TIM1EN +#define RCC_APB2Periph_SPI1 RCC_APB2ENR_SPI1EN +#define RCC_APB2Periph_TIM8 RCC_APB2ENR_TIM8EN +#define RCC_APB2Periph_USART1 RCC_APB2ENR_USART1EN +#define RCC_APB2Periph_TIM15 RCC_APB2ENR_TIM15EN +#define RCC_APB2Periph_TIM16 RCC_APB2ENR_TIM16EN +#define RCC_APB2Periph_TIM17 RCC_APB2ENR_TIM17EN +#define RCC_APB2Periph_HRTIM1 RCC_APB2ENR_HRTIM1 + +#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xDFF887FE) == 0x00) && ((PERIPH) != 0x00)) + +/** + * @} + */ + +/** @defgroup RCC_APB1_Peripherals + * @{ + */ +#define RCC_APB1Periph_TIM2 RCC_APB1ENR_TIM2EN +#define RCC_APB1Periph_TIM3 RCC_APB1ENR_TIM3EN +#define RCC_APB1Periph_TIM4 RCC_APB1ENR_TIM4EN +#define RCC_APB1Periph_TIM6 RCC_APB1ENR_TIM6EN +#define RCC_APB1Periph_TIM7 RCC_APB1ENR_TIM7EN +#define RCC_APB1Periph_WWDG RCC_APB1ENR_WWDGEN +#define RCC_APB1Periph_SPI2 RCC_APB1ENR_SPI2EN +#define RCC_APB1Periph_SPI3 RCC_APB1ENR_SPI3EN +#define RCC_APB1Periph_USART2 RCC_APB1ENR_USART2EN +#define RCC_APB1Periph_USART3 RCC_APB1ENR_USART3EN +#define RCC_APB1Periph_UART4 RCC_APB1ENR_UART4EN +#define RCC_APB1Periph_UART5 RCC_APB1ENR_UART5EN +#define RCC_APB1Periph_I2C1 RCC_APB1ENR_I2C1EN +#define RCC_APB1Periph_I2C2 RCC_APB1ENR_I2C2EN +#define RCC_APB1Periph_USB RCC_APB1ENR_USBEN +#define RCC_APB1Periph_CAN1 RCC_APB1ENR_CAN1EN +#define RCC_APB1Periph_PWR RCC_APB1ENR_PWREN +#define RCC_APB1Periph_DAC1 RCC_APB1ENR_DAC1EN +#define RCC_APB1Periph_I2C3 RCC_APB1ENR_I2C3EN +#define RCC_APB1Periph_DAC2 RCC_APB1ENR_DAC2EN +#define RCC_APB1Periph_DAC RCC_APB1Periph_DAC1 + + +#define IS_RCC_APB1_PERIPH(PERIPH) ((((PERIPH) & 0x890137C8) == 0x00) && ((PERIPH) != 0x00)) +/** + * @} + */ + +/** @defgroup RCC_MCO_Clock_Source + * @{ + */ + +#define RCC_MCOSource_NoClock ((uint8_t)0x00) +#define RCC_MCOSource_LSI ((uint8_t)0x02) +#define RCC_MCOSource_LSE ((uint8_t)0x03) +#define RCC_MCOSource_SYSCLK ((uint8_t)0x04) +#define RCC_MCOSource_HSI ((uint8_t)0x05) +#define RCC_MCOSource_HSE ((uint8_t)0x06) +#define RCC_MCOSource_PLLCLK_Div2 ((uint8_t)0x07) + +#define IS_RCC_MCO_SOURCE(SOURCE) (((SOURCE) == RCC_MCOSource_NoClock) ||((SOURCE) == RCC_MCOSource_SYSCLK) ||\ + ((SOURCE) == RCC_MCOSource_HSI) || ((SOURCE) == RCC_MCOSource_HSE) || \ + ((SOURCE) == RCC_MCOSource_LSI) || ((SOURCE) == RCC_MCOSource_LSE) || \ + ((SOURCE) == RCC_MCOSource_PLLCLK_Div2)) +/** + * @} + */ + +/** @defgroup RCC_MCOPrescaler + * @{ + */ + +#define RCC_MCOPrescaler_1 RCC_CFGR_MCO_PRE_1 +#define RCC_MCOPrescaler_2 RCC_CFGR_MCO_PRE_2 +#define RCC_MCOPrescaler_4 RCC_CFGR_MCO_PRE_4 +#define RCC_MCOPrescaler_8 RCC_CFGR_MCO_PRE_8 +#define RCC_MCOPrescaler_16 RCC_CFGR_MCO_PRE_16 +#define RCC_MCOPrescaler_32 RCC_CFGR_MCO_PRE_32 +#define RCC_MCOPrescaler_64 RCC_CFGR_MCO_PRE_64 +#define RCC_MCOPrescaler_128 RCC_CFGR_MCO_PRE_128 + +#define IS_RCC_MCO_PRESCALER(PRESCALER) (((PRESCALER) == RCC_MCOPrescaler_1) || \ + ((PRESCALER) == RCC_MCOPrescaler_2) || \ + ((PRESCALER) == RCC_MCOPrescaler_4) || \ + ((PRESCALER) == RCC_MCOPrescaler_8) || \ + ((PRESCALER) == RCC_MCOPrescaler_16) || \ + ((PRESCALER) == RCC_MCOPrescaler_32) || \ + ((PRESCALER) == RCC_MCOPrescaler_64) || \ + ((PRESCALER) == RCC_MCOPrescaler_128)) +/** + * @} + */ + +/** @defgroup RCC_USB_Device_clock_source + * @{ + */ + +#define RCC_USBCLKSource_PLLCLK_1Div5 ((uint8_t)0x00) +#define RCC_USBCLKSource_PLLCLK_Div1 ((uint8_t)0x01) + +#define IS_RCC_USBCLK_SOURCE(SOURCE) (((SOURCE) == RCC_USBCLKSource_PLLCLK_1Div5) || \ + ((SOURCE) == RCC_USBCLKSource_PLLCLK_Div1)) +/** + * @} + */ + +/** @defgroup RCC_Flag + * @{ + */ +#define RCC_FLAG_HSIRDY ((uint8_t)0x01) +#define RCC_FLAG_HSERDY ((uint8_t)0x11) +#define RCC_FLAG_PLLRDY ((uint8_t)0x19) +#define RCC_FLAG_MCOF ((uint8_t)0x9C) +#define RCC_FLAG_LSERDY ((uint8_t)0x21) +#define RCC_FLAG_LSIRDY ((uint8_t)0x41) +#define RCC_FLAG_OBLRST ((uint8_t)0x59) +#define RCC_FLAG_PINRST ((uint8_t)0x5A) +#define RCC_FLAG_PORRST ((uint8_t)0x5B) +#define RCC_FLAG_SFTRST ((uint8_t)0x5C) +#define RCC_FLAG_IWDGRST ((uint8_t)0x5D) +#define RCC_FLAG_WWDGRST ((uint8_t)0x5E) +#define RCC_FLAG_LPWRRST ((uint8_t)0x5F) + +#define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \ + ((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \ + ((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_OBLRST) || \ + ((FLAG) == RCC_FLAG_PINRST) || ((FLAG) == RCC_FLAG_PORRST) || \ + ((FLAG) == RCC_FLAG_SFTRST) || ((FLAG) == RCC_FLAG_IWDGRST)|| \ + ((FLAG) == RCC_FLAG_WWDGRST)|| ((FLAG) == RCC_FLAG_LPWRRST)|| \ + ((FLAG) == RCC_FLAG_MCOF)) + +#define IS_RCC_HSI_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1F) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +/* Function used to set the RCC clock configuration to the default reset state */ +void RCC_DeInit(void); + +/* Internal/external clocks, PLL, CSS and MCO configuration functions *********/ +void RCC_HSEConfig(uint8_t RCC_HSE); +ErrorStatus RCC_WaitForHSEStartUp(void); +void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue); +void RCC_HSICmd(FunctionalState NewState); +void RCC_LSEConfig(uint32_t RCC_LSE); +void RCC_LSEDriveConfig(uint32_t RCC_LSEDrive); +void RCC_LSICmd(FunctionalState NewState); +void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul); +void RCC_PLLCmd(FunctionalState NewState); +void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Div); +void RCC_ClockSecuritySystemCmd(FunctionalState NewState); +#ifdef STM32F303xC + void RCC_MCOConfig(uint8_t RCC_MCOSource); +#else + void RCC_MCOConfig(uint8_t RCC_MCOSource,uint32_t RCC_MCOPrescaler); +#endif /* STM32F303xC */ + +/* System, AHB and APB busses clocks configuration functions ******************/ +void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource); +uint8_t RCC_GetSYSCLKSource(void); +void RCC_HCLKConfig(uint32_t RCC_SYSCLK); +void RCC_PCLK1Config(uint32_t RCC_HCLK); +void RCC_PCLK2Config(uint32_t RCC_HCLK); +void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks); + +/* Peripheral clocks configuration functions **********************************/ +void RCC_ADCCLKConfig(uint32_t RCC_PLLCLK); +void RCC_I2CCLKConfig(uint32_t RCC_I2CCLK); +void RCC_TIMCLKConfig(uint32_t RCC_TIMCLK); +void RCC_HRTIM1CLKConfig(uint32_t RCC_HRTIMCLK); +void RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource); +void RCC_USARTCLKConfig(uint32_t RCC_USARTCLK); +void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource); + +void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource); +void RCC_RTCCLKCmd(FunctionalState NewState); +void RCC_BackupResetCmd(FunctionalState NewState); + +void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState); +void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState); +void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState); + +void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState); +void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState); +void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState); + +/* Interrupts and flags management functions **********************************/ +void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState); +FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG); +void RCC_ClearFlag(void); +ITStatus RCC_GetITStatus(uint8_t RCC_IT); +void RCC_ClearITPendingBit(uint8_t RCC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F30x_RCC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_rtc.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_rtc.h new file mode 100644 index 0000000..85dad30 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_rtc.h @@ -0,0 +1,852 @@ +/** + ****************************************************************************** + * @file stm32f30x_rtc.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the RTC firmware + * library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_RTC_H +#define __STM32F30x_RTC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup RTC + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief RTC Init structures definition + */ +typedef struct +{ + uint32_t RTC_HourFormat; /*!< Specifies the RTC Hour Format. + This parameter can be a value of @ref RTC_Hour_Formats */ + + uint32_t RTC_AsynchPrediv; /*!< Specifies the RTC Asynchronous Predivider value. + This parameter must be set to a value lower than 0x7F */ + + uint32_t RTC_SynchPrediv; /*!< Specifies the RTC Synchronous Predivider value. + This parameter must be set to a value lower than 0x1FFF */ +}RTC_InitTypeDef; + +/** + * @brief RTC Time structure definition + */ +typedef struct +{ + uint8_t RTC_Hours; /*!< Specifies the RTC Time Hour. + This parameter must be set to a value in the 0-12 range + if the RTC_HourFormat_12 is selected or 0-23 range if + the RTC_HourFormat_24 is selected. */ + + uint8_t RTC_Minutes; /*!< Specifies the RTC Time Minutes. + This parameter must be set to a value in the 0-59 range. */ + + uint8_t RTC_Seconds; /*!< Specifies the RTC Time Seconds. + This parameter must be set to a value in the 0-59 range. */ + + uint8_t RTC_H12; /*!< Specifies the RTC AM/PM Time. + This parameter can be a value of @ref RTC_AM_PM_Definitions */ +}RTC_TimeTypeDef; + +/** + * @brief RTC Date structure definition + */ +typedef struct +{ + uint8_t RTC_WeekDay; /*!< Specifies the RTC Date WeekDay. + This parameter can be a value of @ref RTC_WeekDay_Definitions */ + + uint8_t RTC_Month; /*!< Specifies the RTC Date Month (in BCD format). + This parameter can be a value of @ref RTC_Month_Date_Definitions */ + + uint8_t RTC_Date; /*!< Specifies the RTC Date. + This parameter must be set to a value in the 1-31 range. */ + + uint8_t RTC_Year; /*!< Specifies the RTC Date Year. + This parameter must be set to a value in the 0-99 range. */ +}RTC_DateTypeDef; + +/** + * @brief RTC Alarm structure definition + */ +typedef struct +{ + RTC_TimeTypeDef RTC_AlarmTime; /*!< Specifies the RTC Alarm Time members. */ + + uint32_t RTC_AlarmMask; /*!< Specifies the RTC Alarm Masks. + This parameter can be a value of @ref RTC_AlarmMask_Definitions */ + + uint32_t RTC_AlarmDateWeekDaySel; /*!< Specifies the RTC Alarm is on Date or WeekDay. + This parameter can be a value of @ref RTC_AlarmDateWeekDay_Definitions */ + + uint8_t RTC_AlarmDateWeekDay; /*!< Specifies the RTC Alarm Date/WeekDay. + If the Alarm Date is selected, this parameter + must be set to a value in the 1-31 range. + If the Alarm WeekDay is selected, this + parameter can be a value of @ref RTC_WeekDay_Definitions */ +}RTC_AlarmTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup RTC_Exported_Constants + * @{ + */ + + +/** @defgroup RTC_Hour_Formats + * @{ + */ +#define RTC_HourFormat_24 ((uint32_t)0x00000000) +#define RTC_HourFormat_12 ((uint32_t)0x00000040) +#define IS_RTC_HOUR_FORMAT(FORMAT) (((FORMAT) == RTC_HourFormat_12) || \ + ((FORMAT) == RTC_HourFormat_24)) +/** + * @} + */ + +/** @defgroup RTC_Asynchronous_Predivider + * @{ + */ +#define IS_RTC_ASYNCH_PREDIV(PREDIV) ((PREDIV) <= 0x7F) + +/** + * @} + */ + + +/** @defgroup RTC_Synchronous_Predivider + * @{ + */ +#define IS_RTC_SYNCH_PREDIV(PREDIV) ((PREDIV) <= 0x7FFF) + +/** + * @} + */ + +/** @defgroup RTC_Time_Definitions + * @{ + */ +#define IS_RTC_HOUR12(HOUR) (((HOUR) > 0) && ((HOUR) <= 12)) +#define IS_RTC_HOUR24(HOUR) ((HOUR) <= 23) +#define IS_RTC_MINUTES(MINUTES) ((MINUTES) <= 59) +#define IS_RTC_SECONDS(SECONDS) ((SECONDS) <= 59) + +/** + * @} + */ + +/** @defgroup RTC_AM_PM_Definitions + * @{ + */ +#define RTC_H12_AM ((uint8_t)0x00) +#define RTC_H12_PM ((uint8_t)0x40) +#define IS_RTC_H12(PM) (((PM) == RTC_H12_AM) || ((PM) == RTC_H12_PM)) + +/** + * @} + */ + +/** @defgroup RTC_Year_Date_Definitions + * @{ + */ +#define IS_RTC_YEAR(YEAR) ((YEAR) <= 99) + +/** + * @} + */ + +/** @defgroup RTC_Month_Date_Definitions + * @{ + */ + +/* Coded in BCD format */ +#define RTC_Month_January ((uint8_t)0x01) +#define RTC_Month_February ((uint8_t)0x02) +#define RTC_Month_March ((uint8_t)0x03) +#define RTC_Month_April ((uint8_t)0x04) +#define RTC_Month_May ((uint8_t)0x05) +#define RTC_Month_June ((uint8_t)0x06) +#define RTC_Month_July ((uint8_t)0x07) +#define RTC_Month_August ((uint8_t)0x08) +#define RTC_Month_September ((uint8_t)0x09) +#define RTC_Month_October ((uint8_t)0x10) +#define RTC_Month_November ((uint8_t)0x11) +#define RTC_Month_December ((uint8_t)0x12) +#define IS_RTC_MONTH(MONTH) (((MONTH) >= 1) && ((MONTH) <= 12)) +#define IS_RTC_DATE(DATE) (((DATE) >= 1) && ((DATE) <= 31)) + +/** + * @} + */ + +/** @defgroup RTC_WeekDay_Definitions + * @{ + */ + +#define RTC_Weekday_Monday ((uint8_t)0x01) +#define RTC_Weekday_Tuesday ((uint8_t)0x02) +#define RTC_Weekday_Wednesday ((uint8_t)0x03) +#define RTC_Weekday_Thursday ((uint8_t)0x04) +#define RTC_Weekday_Friday ((uint8_t)0x05) +#define RTC_Weekday_Saturday ((uint8_t)0x06) +#define RTC_Weekday_Sunday ((uint8_t)0x07) +#define IS_RTC_WEEKDAY(WEEKDAY) (((WEEKDAY) == RTC_Weekday_Monday) || \ + ((WEEKDAY) == RTC_Weekday_Tuesday) || \ + ((WEEKDAY) == RTC_Weekday_Wednesday) || \ + ((WEEKDAY) == RTC_Weekday_Thursday) || \ + ((WEEKDAY) == RTC_Weekday_Friday) || \ + ((WEEKDAY) == RTC_Weekday_Saturday) || \ + ((WEEKDAY) == RTC_Weekday_Sunday)) +/** + * @} + */ + + +/** @defgroup RTC_Alarm_Definitions + * @{ + */ +#define IS_RTC_ALARM_DATE_WEEKDAY_DATE(DATE) (((DATE) > 0) && ((DATE) <= 31)) +#define IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(WEEKDAY) (((WEEKDAY) == RTC_Weekday_Monday) || \ + ((WEEKDAY) == RTC_Weekday_Tuesday) || \ + ((WEEKDAY) == RTC_Weekday_Wednesday) || \ + ((WEEKDAY) == RTC_Weekday_Thursday) || \ + ((WEEKDAY) == RTC_Weekday_Friday) || \ + ((WEEKDAY) == RTC_Weekday_Saturday) || \ + ((WEEKDAY) == RTC_Weekday_Sunday)) + +/** + * @} + */ + + +/** @defgroup RTC_AlarmDateWeekDay_Definitions + * @{ + */ +#define RTC_AlarmDateWeekDaySel_Date ((uint32_t)0x00000000) +#define RTC_AlarmDateWeekDaySel_WeekDay ((uint32_t)0x40000000) + +#define IS_RTC_ALARM_DATE_WEEKDAY_SEL(SEL) (((SEL) == RTC_AlarmDateWeekDaySel_Date) || \ + ((SEL) == RTC_AlarmDateWeekDaySel_WeekDay)) + +/** + * @} + */ + + +/** @defgroup RTC_AlarmMask_Definitions + * @{ + */ +#define RTC_AlarmMask_None ((uint32_t)0x00000000) +#define RTC_AlarmMask_DateWeekDay ((uint32_t)0x80000000) +#define RTC_AlarmMask_Hours ((uint32_t)0x00800000) +#define RTC_AlarmMask_Minutes ((uint32_t)0x00008000) +#define RTC_AlarmMask_Seconds ((uint32_t)0x00000080) +#define RTC_AlarmMask_All ((uint32_t)0x80808080) +#define IS_ALARM_MASK(MASK) (((MASK) & 0x7F7F7F7F) == (uint32_t)RESET) + +/** + * @} + */ + +/** @defgroup RTC_Alarms_Definitions + * @{ + */ +#define RTC_Alarm_A ((uint32_t)0x00000100) +#define RTC_Alarm_B ((uint32_t)0x00000200) +#define IS_RTC_ALARM(ALARM) (((ALARM) == RTC_Alarm_A) || ((ALARM) == RTC_Alarm_B)) +#define IS_RTC_CMD_ALARM(ALARM) (((ALARM) & (RTC_Alarm_A | RTC_Alarm_B)) != (uint32_t)RESET) + +/** + * @} + */ + +/** @defgroup RTC_Alarm_Sub_Seconds_Masks_Definitions + * @{ + */ +#define RTC_AlarmSubSecondMask_All ((uint32_t)0x00000000) /*!< All Alarm SS fields are masked. + There is no comparison on sub seconds + for Alarm */ +#define RTC_AlarmSubSecondMask_SS14_1 ((uint32_t)0x01000000) /*!< SS[14:1] are don't care in Alarm + comparison. Only SS[0] is compared. */ +#define RTC_AlarmSubSecondMask_SS14_2 ((uint32_t)0x02000000) /*!< SS[14:2] are don't care in Alarm + comparison. Only SS[1:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_3 ((uint32_t)0x03000000) /*!< SS[14:3] are don't care in Alarm + comparison. Only SS[2:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_4 ((uint32_t)0x04000000) /*!< SS[14:4] are don't care in Alarm + comparison. Only SS[3:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_5 ((uint32_t)0x05000000) /*!< SS[14:5] are don't care in Alarm + comparison. Only SS[4:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_6 ((uint32_t)0x06000000) /*!< SS[14:6] are don't care in Alarm + comparison. Only SS[5:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_7 ((uint32_t)0x07000000) /*!< SS[14:7] are don't care in Alarm + comparison. Only SS[6:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_8 ((uint32_t)0x08000000) /*!< SS[14:8] are don't care in Alarm + comparison. Only SS[7:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_9 ((uint32_t)0x09000000) /*!< SS[14:9] are don't care in Alarm + comparison. Only SS[8:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_10 ((uint32_t)0x0A000000) /*!< SS[14:10] are don't care in Alarm + comparison. Only SS[9:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_11 ((uint32_t)0x0B000000) /*!< SS[14:11] are don't care in Alarm + comparison. Only SS[10:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_12 ((uint32_t)0x0C000000) /*!< SS[14:12] are don't care in Alarm + comparison.Only SS[11:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14_13 ((uint32_t)0x0D000000) /*!< SS[14:13] are don't care in Alarm + comparison. Only SS[12:0] are compared */ +#define RTC_AlarmSubSecondMask_SS14 ((uint32_t)0x0E000000) /*!< SS[14] is don't care in Alarm + comparison.Only SS[13:0] are compared */ +#define RTC_AlarmSubSecondMask_None ((uint32_t)0x0F000000) /*!< SS[14:0] are compared and must match + to activate alarm. */ +#define IS_RTC_ALARM_SUB_SECOND_MASK(MASK) (((MASK) == RTC_AlarmSubSecondMask_All) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_1) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_2) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_3) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_4) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_5) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_6) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_7) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_8) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_9) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_10) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_11) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_12) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14_13) || \ + ((MASK) == RTC_AlarmSubSecondMask_SS14) || \ + ((MASK) == RTC_AlarmSubSecondMask_None)) +/** + * @} + */ + +/** @defgroup RTC_Alarm_Sub_Seconds_Value + * @{ + */ + +#define IS_RTC_ALARM_SUB_SECOND_VALUE(VALUE) ((VALUE) <= 0x00007FFF) + +/** + * @} + */ + +/** @defgroup RTC_Wakeup_Timer_Definitions + * @{ + */ +#define RTC_WakeUpClock_RTCCLK_Div16 ((uint32_t)0x00000000) +#define RTC_WakeUpClock_RTCCLK_Div8 ((uint32_t)0x00000001) +#define RTC_WakeUpClock_RTCCLK_Div4 ((uint32_t)0x00000002) +#define RTC_WakeUpClock_RTCCLK_Div2 ((uint32_t)0x00000003) +#define RTC_WakeUpClock_CK_SPRE_16bits ((uint32_t)0x00000004) +#define RTC_WakeUpClock_CK_SPRE_17bits ((uint32_t)0x00000006) +#define IS_RTC_WAKEUP_CLOCK(CLOCK) (((CLOCK) == RTC_WakeUpClock_RTCCLK_Div16) || \ + ((CLOCK) == RTC_WakeUpClock_RTCCLK_Div8) || \ + ((CLOCK) == RTC_WakeUpClock_RTCCLK_Div4) || \ + ((CLOCK) == RTC_WakeUpClock_RTCCLK_Div2) || \ + ((CLOCK) == RTC_WakeUpClock_CK_SPRE_16bits) || \ + ((CLOCK) == RTC_WakeUpClock_CK_SPRE_17bits)) +#define IS_RTC_WAKEUP_COUNTER(COUNTER) ((COUNTER) <= 0xFFFF) +/** + * @} + */ + +/** @defgroup RTC_Time_Stamp_Edges_definitions + * @{ + */ +#define RTC_TimeStampEdge_Rising ((uint32_t)0x00000000) +#define RTC_TimeStampEdge_Falling ((uint32_t)0x00000008) +#define IS_RTC_TIMESTAMP_EDGE(EDGE) (((EDGE) == RTC_TimeStampEdge_Rising) || \ + ((EDGE) == RTC_TimeStampEdge_Falling)) +/** + * @} + */ + +/** @defgroup RTC_Output_selection_Definitions + * @{ + */ +#define RTC_Output_Disable ((uint32_t)0x00000000) +#define RTC_Output_AlarmA ((uint32_t)0x00200000) +#define RTC_Output_AlarmB ((uint32_t)0x00400000) +#define RTC_Output_WakeUp ((uint32_t)0x00600000) + +#define IS_RTC_OUTPUT(OUTPUT) (((OUTPUT) == RTC_Output_Disable) || \ + ((OUTPUT) == RTC_Output_AlarmA) || \ + ((OUTPUT) == RTC_Output_AlarmB) || \ + ((OUTPUT) == RTC_Output_WakeUp)) + +/** + * @} + */ + +/** @defgroup RTC_Output_Polarity_Definitions + * @{ + */ +#define RTC_OutputPolarity_High ((uint32_t)0x00000000) +#define RTC_OutputPolarity_Low ((uint32_t)0x00100000) +#define IS_RTC_OUTPUT_POL(POL) (((POL) == RTC_OutputPolarity_High) || \ + ((POL) == RTC_OutputPolarity_Low)) +/** + * @} + */ + +/** @defgroup RTC_Digital_Calibration_Definitions + * @{ + */ +#define RTC_CalibSign_Positive ((uint32_t)0x00000000) +#define RTC_CalibSign_Negative ((uint32_t)0x00000080) +#define IS_RTC_CALIB_SIGN(SIGN) (((SIGN) == RTC_CalibSign_Positive) || \ + ((SIGN) == RTC_CalibSign_Negative)) +#define IS_RTC_CALIB_VALUE(VALUE) ((VALUE) < 0x20) + +/** + * @} + */ + + /** @defgroup RTC_Calib_Output_selection_Definitions + * @{ + */ +#define RTC_CalibOutput_512Hz ((uint32_t)0x00000000) +#define RTC_CalibOutput_1Hz ((uint32_t)0x00080000) +#define IS_RTC_CALIB_OUTPUT(OUTPUT) (((OUTPUT) == RTC_CalibOutput_512Hz) || \ + ((OUTPUT) == RTC_CalibOutput_1Hz)) +/** + * @} + */ + +/** @defgroup RTC_Smooth_calib_period_Definitions + * @{ + */ +#define RTC_SmoothCalibPeriod_32sec ((uint32_t)0x00000000) /*!< if RTCCLK = 32768 Hz, Smooth calibation + period is 32s, else 2exp20 RTCCLK seconds */ +#define RTC_SmoothCalibPeriod_16sec ((uint32_t)0x00002000) /*!< if RTCCLK = 32768 Hz, Smooth calibation + period is 16s, else 2exp19 RTCCLK seconds */ +#define RTC_SmoothCalibPeriod_8sec ((uint32_t)0x00004000) /*!< if RTCCLK = 32768 Hz, Smooth calibation + period is 8s, else 2exp18 RTCCLK seconds */ +#define IS_RTC_SMOOTH_CALIB_PERIOD(PERIOD) (((PERIOD) == RTC_SmoothCalibPeriod_32sec) || \ + ((PERIOD) == RTC_SmoothCalibPeriod_16sec) || \ + ((PERIOD) == RTC_SmoothCalibPeriod_8sec)) + +/** + * @} + */ + +/** @defgroup RTC_Smooth_calib_Plus_pulses_Definitions + * @{ + */ +#define RTC_SmoothCalibPlusPulses_Set ((uint32_t)0x00008000) /*!< The number of RTCCLK pulses added + during a X -second window = Y - CALM[8:0]. + with Y = 512, 256, 128 when X = 32, 16, 8 */ +#define RTC_SmoothCalibPlusPulses_Reset ((uint32_t)0x00000000) /*!< The number of RTCCLK pulses subbstited + during a 32-second window = CALM[8:0]. */ +#define IS_RTC_SMOOTH_CALIB_PLUS(PLUS) (((PLUS) == RTC_SmoothCalibPlusPulses_Set) || \ + ((PLUS) == RTC_SmoothCalibPlusPulses_Reset)) + +/** + * @} + */ + +/** @defgroup RTC_Smooth_calib_Minus_pulses_Definitions + * @{ + */ +#define IS_RTC_SMOOTH_CALIB_MINUS(VALUE) ((VALUE) <= 0x000001FF) + +/** + * @} + */ + +/** @defgroup RTC_DayLightSaving_Definitions + * @{ + */ +#define RTC_DayLightSaving_SUB1H ((uint32_t)0x00020000) +#define RTC_DayLightSaving_ADD1H ((uint32_t)0x00010000) +#define IS_RTC_DAYLIGHT_SAVING(SAVE) (((SAVE) == RTC_DayLightSaving_SUB1H) || \ + ((SAVE) == RTC_DayLightSaving_ADD1H)) + +#define RTC_StoreOperation_Reset ((uint32_t)0x00000000) +#define RTC_StoreOperation_Set ((uint32_t)0x00040000) +#define IS_RTC_STORE_OPERATION(OPERATION) (((OPERATION) == RTC_StoreOperation_Reset) || \ + ((OPERATION) == RTC_StoreOperation_Set)) +/** + * @} + */ + +/** @defgroup RTC_Tamper_Trigger_Definitions + * @{ + */ +#define RTC_TamperTrigger_RisingEdge ((uint32_t)0x00000000) +#define RTC_TamperTrigger_FallingEdge ((uint32_t)0x00000001) +#define RTC_TamperTrigger_LowLevel ((uint32_t)0x00000000) +#define RTC_TamperTrigger_HighLevel ((uint32_t)0x00000001) +#define IS_RTC_TAMPER_TRIGGER(TRIGGER) (((TRIGGER) == RTC_TamperTrigger_RisingEdge) || \ + ((TRIGGER) == RTC_TamperTrigger_FallingEdge) || \ + ((TRIGGER) == RTC_TamperTrigger_LowLevel) || \ + ((TRIGGER) == RTC_TamperTrigger_HighLevel)) + +/** + * @} + */ + +/** @defgroup RTC_Tamper_Filter_Definitions + * @{ + */ +#define RTC_TamperFilter_Disable ((uint32_t)0x00000000) /*!< Tamper filter is disabled */ + +#define RTC_TamperFilter_2Sample ((uint32_t)0x00000800) /*!< Tamper is activated after 2 + consecutive samples at the active level */ +#define RTC_TamperFilter_4Sample ((uint32_t)0x00001000) /*!< Tamper is activated after 4 + consecutive samples at the active level */ +#define RTC_TamperFilter_8Sample ((uint32_t)0x00001800) /*!< Tamper is activated after 8 + consecutive samples at the active leve. */ +#define IS_RTC_TAMPER_FILTER(FILTER) (((FILTER) == RTC_TamperFilter_Disable) || \ + ((FILTER) == RTC_TamperFilter_2Sample) || \ + ((FILTER) == RTC_TamperFilter_4Sample) || \ + ((FILTER) == RTC_TamperFilter_8Sample)) +/** + * @} + */ + +/** @defgroup RTC_Tamper_Sampling_Frequencies_Definitions + * @{ + */ +#define RTC_TamperSamplingFreq_RTCCLK_Div32768 ((uint32_t)0x00000000) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 32768 */ +#define RTC_TamperSamplingFreq_RTCCLK_Div16384 ((uint32_t)0x000000100) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 16384 */ +#define RTC_TamperSamplingFreq_RTCCLK_Div8192 ((uint32_t)0x00000200) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 8192 */ +#define RTC_TamperSamplingFreq_RTCCLK_Div4096 ((uint32_t)0x00000300) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 4096 */ +#define RTC_TamperSamplingFreq_RTCCLK_Div2048 ((uint32_t)0x00000400) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 2048 */ +#define RTC_TamperSamplingFreq_RTCCLK_Div1024 ((uint32_t)0x00000500) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 1024 */ +#define RTC_TamperSamplingFreq_RTCCLK_Div512 ((uint32_t)0x00000600) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 512 */ +#define RTC_TamperSamplingFreq_RTCCLK_Div256 ((uint32_t)0x00000700) /*!< Each of the tamper inputs are sampled + with a frequency = RTCCLK / 256 */ +#define IS_RTC_TAMPER_SAMPLING_FREQ(FREQ) (((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div32768) || \ + ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div16384) || \ + ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div8192) || \ + ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div4096) || \ + ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div2048) || \ + ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div1024) || \ + ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div512) || \ + ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div256)) + +/** + * @} + */ + + /** @defgroup RTC_Tamper_Pin_Precharge_Duration_Definitions + * @{ + */ +#define RTC_TamperPrechargeDuration_1RTCCLK ((uint32_t)0x00000000) /*!< Tamper pins are pre-charged before + sampling during 1 RTCCLK cycle */ +#define RTC_TamperPrechargeDuration_2RTCCLK ((uint32_t)0x00002000) /*!< Tamper pins are pre-charged before + sampling during 2 RTCCLK cycles */ +#define RTC_TamperPrechargeDuration_4RTCCLK ((uint32_t)0x00004000) /*!< Tamper pins are pre-charged before + sampling during 4 RTCCLK cycles */ +#define RTC_TamperPrechargeDuration_8RTCCLK ((uint32_t)0x00006000) /*!< Tamper pins are pre-charged before + sampling during 8 RTCCLK cycles */ + +#define IS_RTC_TAMPER_PRECHARGE_DURATION(DURATION) (((DURATION) == RTC_TamperPrechargeDuration_1RTCCLK) || \ + ((DURATION) == RTC_TamperPrechargeDuration_2RTCCLK) || \ + ((DURATION) == RTC_TamperPrechargeDuration_4RTCCLK) || \ + ((DURATION) == RTC_TamperPrechargeDuration_8RTCCLK)) +/** + * @} + */ + +/** @defgroup RTC_Tamper_Pins_Definitions + * @{ + */ +#define RTC_Tamper_1 RTC_TAFCR_TAMP1E /*!< Tamper detection enable for + input tamper 1 */ +#define RTC_Tamper_2 RTC_TAFCR_TAMP2E /*!< Tamper detection enable for + input tamper 2 */ +#define RTC_Tamper_3 RTC_TAFCR_TAMP3E /*!< Tamper detection enable for + input tamper 3 */ + +#define IS_RTC_TAMPER(TAMPER) ((((TAMPER) & (uint32_t)0xFFFFFFD6) == 0x00) && ((TAMPER) != (uint32_t)RESET)) + + +/** + * @} + */ + +/** @defgroup RTC_Output_Type_ALARM_OUT + * @{ + */ +#define RTC_OutputType_OpenDrain ((uint32_t)0x00000000) +#define RTC_OutputType_PushPull ((uint32_t)0x00040000) +#define IS_RTC_OUTPUT_TYPE(TYPE) (((TYPE) == RTC_OutputType_OpenDrain) || \ + ((TYPE) == RTC_OutputType_PushPull)) + +/** + * @} + */ + +/** @defgroup RTC_Add_1_Second_Parameter_Definitions + * @{ + */ +#define RTC_ShiftAdd1S_Reset ((uint32_t)0x00000000) +#define RTC_ShiftAdd1S_Set ((uint32_t)0x80000000) +#define IS_RTC_SHIFT_ADD1S(SEL) (((SEL) == RTC_ShiftAdd1S_Reset) || \ + ((SEL) == RTC_ShiftAdd1S_Set)) +/** + * @} + */ + +/** @defgroup RTC_Substract_Fraction_Of_Second_Value + * @{ + */ +#define IS_RTC_SHIFT_SUBFS(FS) ((FS) <= 0x00007FFF) + +/** + * @} + */ + +/** @defgroup RTC_Backup_Registers_Definitions + * @{ + */ + +#define RTC_BKP_DR0 ((uint32_t)0x00000000) +#define RTC_BKP_DR1 ((uint32_t)0x00000001) +#define RTC_BKP_DR2 ((uint32_t)0x00000002) +#define RTC_BKP_DR3 ((uint32_t)0x00000003) +#define RTC_BKP_DR4 ((uint32_t)0x00000004) +#define RTC_BKP_DR5 ((uint32_t)0x00000005) +#define RTC_BKP_DR6 ((uint32_t)0x00000006) +#define RTC_BKP_DR7 ((uint32_t)0x00000007) +#define RTC_BKP_DR8 ((uint32_t)0x00000008) +#define RTC_BKP_DR9 ((uint32_t)0x00000009) +#define RTC_BKP_DR10 ((uint32_t)0x0000000A) +#define RTC_BKP_DR11 ((uint32_t)0x0000000B) +#define RTC_BKP_DR12 ((uint32_t)0x0000000C) +#define RTC_BKP_DR13 ((uint32_t)0x0000000D) +#define RTC_BKP_DR14 ((uint32_t)0x0000000E) +#define RTC_BKP_DR15 ((uint32_t)0x0000000F) +#define IS_RTC_BKP(BKP) (((BKP) == RTC_BKP_DR0) || \ + ((BKP) == RTC_BKP_DR1) || \ + ((BKP) == RTC_BKP_DR2) || \ + ((BKP) == RTC_BKP_DR3) || \ + ((BKP) == RTC_BKP_DR4) || \ + ((BKP) == RTC_BKP_DR5) || \ + ((BKP) == RTC_BKP_DR6) || \ + ((BKP) == RTC_BKP_DR7) || \ + ((BKP) == RTC_BKP_DR8) || \ + ((BKP) == RTC_BKP_DR9) || \ + ((BKP) == RTC_BKP_DR10) || \ + ((BKP) == RTC_BKP_DR11) || \ + ((BKP) == RTC_BKP_DR12) || \ + ((BKP) == RTC_BKP_DR13) || \ + ((BKP) == RTC_BKP_DR14) || \ + ((BKP) == RTC_BKP_DR15)) +/** + * @} + */ + +/** @defgroup RTC_Input_parameter_format_definitions + * @{ + */ +#define RTC_Format_BIN ((uint32_t)0x000000000) +#define RTC_Format_BCD ((uint32_t)0x000000001) +#define IS_RTC_FORMAT(FORMAT) (((FORMAT) == RTC_Format_BIN) || ((FORMAT) == RTC_Format_BCD)) + +/** + * @} + */ + +/** @defgroup RTC_Flags_Definitions + * @{ + */ +#define RTC_FLAG_RECALPF ((uint32_t)0x00010000) +#define RTC_FLAG_TAMP3F ((uint32_t)0x00008000) +#define RTC_FLAG_TAMP2F ((uint32_t)0x00004000) +#define RTC_FLAG_TAMP1F ((uint32_t)0x00002000) +#define RTC_FLAG_TSOVF ((uint32_t)0x00001000) +#define RTC_FLAG_TSF ((uint32_t)0x00000800) +#define RTC_FLAG_WUTF ((uint32_t)0x00000400) +#define RTC_FLAG_ALRBF ((uint32_t)0x00000200) +#define RTC_FLAG_ALRAF ((uint32_t)0x00000100) +#define RTC_FLAG_INITF ((uint32_t)0x00000040) +#define RTC_FLAG_RSF ((uint32_t)0x00000020) +#define RTC_FLAG_INITS ((uint32_t)0x00000010) +#define RTC_FLAG_SHPF ((uint32_t)0x00000008) +#define RTC_FLAG_WUTWF ((uint32_t)0x00000004) +#define RTC_FLAG_ALRBWF ((uint32_t)0x00000002) +#define RTC_FLAG_ALRAWF ((uint32_t)0x00000001) +#define IS_RTC_GET_FLAG(FLAG) (((FLAG) == RTC_FLAG_TSOVF) || ((FLAG) == RTC_FLAG_TSF) || \ + ((FLAG) == RTC_FLAG_WUTF) || ((FLAG) == RTC_FLAG_ALRBF) || \ + ((FLAG) == RTC_FLAG_ALRAF) || ((FLAG) == RTC_FLAG_INITF) || \ + ((FLAG) == RTC_FLAG_RSF) || ((FLAG) == RTC_FLAG_WUTWF) || \ + ((FLAG) == RTC_FLAG_ALRBWF) || ((FLAG) == RTC_FLAG_ALRAWF) || \ + ((FLAG) == RTC_FLAG_TAMP1F) || ((FLAG) == RTC_FLAG_TAMP2F) || \ + ((FLAG) == RTC_FLAG_TAMP3F) || ((FLAG) == RTC_FLAG_RECALPF) || \ + ((FLAG) == RTC_FLAG_SHPF)) +#define IS_RTC_CLEAR_FLAG(FLAG) (((FLAG) != (uint32_t)RESET) && (((FLAG) & 0xFFFF00DF) == (uint32_t)RESET)) + +/** + * @} + */ + +/** @defgroup RTC_Interrupts_Definitions + * @{ + */ +#define RTC_IT_TS ((uint32_t)0x00008000) +#define RTC_IT_WUT ((uint32_t)0x00004000) +#define RTC_IT_ALRB ((uint32_t)0x00002000) +#define RTC_IT_ALRA ((uint32_t)0x00001000) +#define RTC_IT_TAMP ((uint32_t)0x00000004) /* Used only to Enable the Tamper Interrupt */ +#define RTC_IT_TAMP1 ((uint32_t)0x00020000) +#define RTC_IT_TAMP2 ((uint32_t)0x00040000) +#define RTC_IT_TAMP3 ((uint32_t)0x00080000) + + +#define IS_RTC_CONFIG_IT(IT) (((IT) != (uint32_t)RESET) && (((IT) & 0xFFFF0FFB) == (uint32_t)RESET)) +#define IS_RTC_GET_IT(IT) (((IT) == RTC_IT_TS) || ((IT) == RTC_IT_WUT) || \ + ((IT) == RTC_IT_ALRB) || ((IT) == RTC_IT_ALRA) || \ + ((IT) == RTC_IT_TAMP1) || ((IT) == RTC_IT_TAMP2) || \ + ((IT) == RTC_IT_TAMP3)) +#define IS_RTC_CLEAR_IT(IT) (((IT) != (uint32_t)RESET) && (((IT) & 0xFFF10FFF) == (uint32_t)RESET)) + +/** + * @} + */ + +/** + * @} + */ + + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +/* Function used to set the RTC configuration to the default reset state *****/ +ErrorStatus RTC_DeInit(void); + + +/* Initialization and Configuration functions *********************************/ +ErrorStatus RTC_Init(RTC_InitTypeDef* RTC_InitStruct); +void RTC_StructInit(RTC_InitTypeDef* RTC_InitStruct); +void RTC_WriteProtectionCmd(FunctionalState NewState); +ErrorStatus RTC_EnterInitMode(void); +void RTC_ExitInitMode(void); +ErrorStatus RTC_WaitForSynchro(void); +ErrorStatus RTC_RefClockCmd(FunctionalState NewState); +void RTC_BypassShadowCmd(FunctionalState NewState); + +/* Time and Date configuration functions **************************************/ +ErrorStatus RTC_SetTime(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_TimeStruct); +void RTC_TimeStructInit(RTC_TimeTypeDef* RTC_TimeStruct); +void RTC_GetTime(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_TimeStruct); +uint32_t RTC_GetSubSecond(void); +ErrorStatus RTC_SetDate(uint32_t RTC_Format, RTC_DateTypeDef* RTC_DateStruct); +void RTC_DateStructInit(RTC_DateTypeDef* RTC_DateStruct); +void RTC_GetDate(uint32_t RTC_Format, RTC_DateTypeDef* RTC_DateStruct); + +/* Alarms (Alarm A and Alarm B) configuration functions **********************/ +void RTC_SetAlarm(uint32_t RTC_Format, uint32_t RTC_Alarm, RTC_AlarmTypeDef* RTC_AlarmStruct); +void RTC_AlarmStructInit(RTC_AlarmTypeDef* RTC_AlarmStruct); +void RTC_GetAlarm(uint32_t RTC_Format, uint32_t RTC_Alarm, RTC_AlarmTypeDef* RTC_AlarmStruct); +ErrorStatus RTC_AlarmCmd(uint32_t RTC_Alarm, FunctionalState NewState); +void RTC_AlarmSubSecondConfig(uint32_t RTC_Alarm, uint32_t RTC_AlarmSubSecondValue, uint32_t RTC_AlarmSubSecondMask); +uint32_t RTC_GetAlarmSubSecond(uint32_t RTC_Alarm); + +/* WakeUp Timer configuration functions ***************************************/ +void RTC_WakeUpClockConfig(uint32_t RTC_WakeUpClock); +void RTC_SetWakeUpCounter(uint32_t RTC_WakeUpCounter); +uint32_t RTC_GetWakeUpCounter(void); +ErrorStatus RTC_WakeUpCmd(FunctionalState NewState); + +/* Daylight Saving configuration functions ************************************/ +void RTC_DayLightSavingConfig(uint32_t RTC_DayLightSaving, uint32_t RTC_StoreOperation); +uint32_t RTC_GetStoreOperation(void); + +/* Output pin Configuration function ******************************************/ +void RTC_OutputConfig(uint32_t RTC_Output, uint32_t RTC_OutputPolarity); + +/* Digital Calibration configuration functions ********************************/ +void RTC_CalibOutputCmd(FunctionalState NewState); +void RTC_CalibOutputConfig(uint32_t RTC_CalibOutput); +ErrorStatus RTC_SmoothCalibConfig(uint32_t RTC_SmoothCalibPeriod, + uint32_t RTC_SmoothCalibPlusPulses, + uint32_t RTC_SmouthCalibMinusPulsesValue); + +/* TimeStamp configuration functions ******************************************/ +void RTC_TimeStampCmd(uint32_t RTC_TimeStampEdge, FunctionalState NewState); +void RTC_GetTimeStamp(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_StampTimeStruct, + RTC_DateTypeDef* RTC_StampDateStruct); +uint32_t RTC_GetTimeStampSubSecond(void); + +/* Tampers configuration functions ********************************************/ +void RTC_TamperTriggerConfig(uint32_t RTC_Tamper, uint32_t RTC_TamperTrigger); +void RTC_TamperCmd(uint32_t RTC_Tamper, FunctionalState NewState); +void RTC_TamperFilterConfig(uint32_t RTC_TamperFilter); +void RTC_TamperSamplingFreqConfig(uint32_t RTC_TamperSamplingFreq); +void RTC_TamperPinsPrechargeDuration(uint32_t RTC_TamperPrechargeDuration); +void RTC_TimeStampOnTamperDetectionCmd(FunctionalState NewState); +void RTC_TamperPullUpCmd(FunctionalState NewState); + +/* Backup Data Registers configuration functions ******************************/ +void RTC_WriteBackupRegister(uint32_t RTC_BKP_DR, uint32_t Data); +uint32_t RTC_ReadBackupRegister(uint32_t RTC_BKP_DR); + +/* Output Type Config configuration functions *********************************/ +void RTC_OutputTypeConfig(uint32_t RTC_OutputType); + +/* RTC_Shift_control_synchonisation_functions *********************************/ +ErrorStatus RTC_SynchroShiftConfig(uint32_t RTC_ShiftAdd1S, uint32_t RTC_ShiftSubFS); + +/* Interrupts and flags management functions **********************************/ +void RTC_ITConfig(uint32_t RTC_IT, FunctionalState NewState); +FlagStatus RTC_GetFlagStatus(uint32_t RTC_FLAG); +void RTC_ClearFlag(uint32_t RTC_FLAG); +ITStatus RTC_GetITStatus(uint32_t RTC_IT); +void RTC_ClearITPendingBit(uint32_t RTC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F30x_RTC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_spi.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_spi.h new file mode 100644 index 0000000..4cd0c3e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_spi.h @@ -0,0 +1,606 @@ +/** + ****************************************************************************** + * @file stm32f30x_spi.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the SPI + * firmware library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_SPI_H +#define __STM32F30x_SPI_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup SPI + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief SPI Init structure definition + */ + +typedef struct +{ + uint16_t SPI_Direction; /*!< Specifies the SPI unidirectional or bidirectional data mode. + This parameter can be a value of @ref SPI_data_direction */ + + uint16_t SPI_Mode; /*!< Specifies the SPI mode (Master/Slave). + This parameter can be a value of @ref SPI_mode */ + + uint16_t SPI_DataSize; /*!< Specifies the SPI data size. + This parameter can be a value of @ref SPI_data_size */ + + uint16_t SPI_CPOL; /*!< Specifies the serial clock steady state. + This parameter can be a value of @ref SPI_Clock_Polarity */ + + uint16_t SPI_CPHA; /*!< Specifies the clock active edge for the bit capture. + This parameter can be a value of @ref SPI_Clock_Phase */ + + uint16_t SPI_NSS; /*!< Specifies whether the NSS signal is managed by + hardware (NSS pin) or by software using the SSI bit. + This parameter can be a value of @ref SPI_Slave_Select_management */ + + uint16_t SPI_BaudRatePrescaler; /*!< Specifies the Baud Rate prescaler value which will be + used to configure the transmit and receive SCK clock. + This parameter can be a value of @ref SPI_BaudRate_Prescaler. + @note The communication clock is derived from the master + clock. The slave clock does not need to be set. */ + + uint16_t SPI_FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit. + This parameter can be a value of @ref SPI_MSB_LSB_transmission */ + + uint16_t SPI_CRCPolynomial; /*!< Specifies the polynomial used for the CRC calculation. */ +}SPI_InitTypeDef; + + +/** + * @brief I2S Init structure definition + */ + +typedef struct +{ + uint16_t I2S_Mode; /*!< Specifies the I2S operating mode. + This parameter can be a value of @ref I2S_Mode */ + + uint16_t I2S_Standard; /*!< Specifies the standard used for the I2S communication. + This parameter can be a value of @ref I2S_Standard */ + + uint16_t I2S_DataFormat; /*!< Specifies the data format for the I2S communication. + This parameter can be a value of @ref I2S_Data_Format */ + + uint16_t I2S_MCLKOutput; /*!< Specifies whether the I2S MCLK output is enabled or not. + This parameter can be a value of @ref I2S_MCLK_Output */ + + uint32_t I2S_AudioFreq; /*!< Specifies the frequency selected for the I2S communication. + This parameter can be a value of @ref I2S_Audio_Frequency */ + + uint16_t I2S_CPOL; /*!< Specifies the idle state of the I2S clock. + This parameter can be a value of @ref I2S_Clock_Polarity */ +}I2S_InitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup SPI_Exported_Constants + * @{ + */ + +#define IS_SPI_ALL_PERIPH(PERIPH) (((PERIPH) == SPI1) || \ + ((PERIPH) == SPI2) || \ + ((PERIPH) == SPI3)) + +#define IS_SPI_ALL_PERIPH_EXT(PERIPH) (((PERIPH) == SPI1) || \ + ((PERIPH) == SPI2) || \ + ((PERIPH) == SPI3) || \ + ((PERIPH) == I2S2ext) || \ + ((PERIPH) == I2S3ext)) + +#define IS_SPI_23_PERIPH(PERIPH) (((PERIPH) == SPI2) || \ + ((PERIPH) == SPI3)) + +#define IS_SPI_23_PERIPH_EXT(PERIPH) (((PERIPH) == SPI2) || \ + ((PERIPH) == SPI3) || \ + ((PERIPH) == I2S2ext) || \ + ((PERIPH) == I2S3ext)) + +#define IS_I2S_EXT_PERIPH(PERIPH) (((PERIPH) == I2S2ext) || \ + ((PERIPH) == I2S3ext)) + +/** @defgroup SPI_data_direction + * @{ + */ + +#define SPI_Direction_2Lines_FullDuplex ((uint16_t)0x0000) +#define SPI_Direction_2Lines_RxOnly ((uint16_t)0x0400) +#define SPI_Direction_1Line_Rx ((uint16_t)0x8000) +#define SPI_Direction_1Line_Tx ((uint16_t)0xC000) +#define IS_SPI_DIRECTION_MODE(MODE) (((MODE) == SPI_Direction_2Lines_FullDuplex) || \ + ((MODE) == SPI_Direction_2Lines_RxOnly) || \ + ((MODE) == SPI_Direction_1Line_Rx) || \ + ((MODE) == SPI_Direction_1Line_Tx)) +/** + * @} + */ + +/** @defgroup SPI_mode + * @{ + */ + +#define SPI_Mode_Master ((uint16_t)0x0104) +#define SPI_Mode_Slave ((uint16_t)0x0000) +#define IS_SPI_MODE(MODE) (((MODE) == SPI_Mode_Master) || \ + ((MODE) == SPI_Mode_Slave)) +/** + * @} + */ + +/** @defgroup SPI_data_size + * @{ + */ + +#define SPI_DataSize_4b ((uint16_t)0x0300) +#define SPI_DataSize_5b ((uint16_t)0x0400) +#define SPI_DataSize_6b ((uint16_t)0x0500) +#define SPI_DataSize_7b ((uint16_t)0x0600) +#define SPI_DataSize_8b ((uint16_t)0x0700) +#define SPI_DataSize_9b ((uint16_t)0x0800) +#define SPI_DataSize_10b ((uint16_t)0x0900) +#define SPI_DataSize_11b ((uint16_t)0x0A00) +#define SPI_DataSize_12b ((uint16_t)0x0B00) +#define SPI_DataSize_13b ((uint16_t)0x0C00) +#define SPI_DataSize_14b ((uint16_t)0x0D00) +#define SPI_DataSize_15b ((uint16_t)0x0E00) +#define SPI_DataSize_16b ((uint16_t)0x0F00) +#define IS_SPI_DATA_SIZE(SIZE) (((SIZE) == SPI_DataSize_4b) || \ + ((SIZE) == SPI_DataSize_5b) || \ + ((SIZE) == SPI_DataSize_6b) || \ + ((SIZE) == SPI_DataSize_7b) || \ + ((SIZE) == SPI_DataSize_8b) || \ + ((SIZE) == SPI_DataSize_9b) || \ + ((SIZE) == SPI_DataSize_10b) || \ + ((SIZE) == SPI_DataSize_11b) || \ + ((SIZE) == SPI_DataSize_12b) || \ + ((SIZE) == SPI_DataSize_13b) || \ + ((SIZE) == SPI_DataSize_14b) || \ + ((SIZE) == SPI_DataSize_15b) || \ + ((SIZE) == SPI_DataSize_16b)) +/** + * @} + */ + +/** @defgroup SPI_CRC_length + * @{ + */ + +#define SPI_CRCLength_8b ((uint16_t)0x0000) +#define SPI_CRCLength_16b ((uint16_t)0x0800) +#define IS_SPI_CRC_LENGTH(LENGTH) (((LENGTH) == SPI_CRCLength_8b) || \ + ((LENGTH) == SPI_CRCLength_16b)) +/** + * @} + */ + +/** @defgroup SPI_Clock_Polarity + * @{ + */ + +#define SPI_CPOL_Low ((uint16_t)0x0000) +#define SPI_CPOL_High ((uint16_t)0x0002) +#define IS_SPI_CPOL(CPOL) (((CPOL) == SPI_CPOL_Low) || \ + ((CPOL) == SPI_CPOL_High)) +/** + * @} + */ + +/** @defgroup SPI_Clock_Phase + * @{ + */ + +#define SPI_CPHA_1Edge ((uint16_t)0x0000) +#define SPI_CPHA_2Edge ((uint16_t)0x0001) +#define IS_SPI_CPHA(CPHA) (((CPHA) == SPI_CPHA_1Edge) || \ + ((CPHA) == SPI_CPHA_2Edge)) +/** + * @} + */ + +/** @defgroup SPI_Slave_Select_management + * @{ + */ + +#define SPI_NSS_Soft ((uint16_t)0x0200) +#define SPI_NSS_Hard ((uint16_t)0x0000) +#define IS_SPI_NSS(NSS) (((NSS) == SPI_NSS_Soft) || \ + ((NSS) == SPI_NSS_Hard)) +/** + * @} + */ + +/** @defgroup SPI_BaudRate_Prescaler + * @{ + */ + +#define SPI_BaudRatePrescaler_2 ((uint16_t)0x0000) +#define SPI_BaudRatePrescaler_4 ((uint16_t)0x0008) +#define SPI_BaudRatePrescaler_8 ((uint16_t)0x0010) +#define SPI_BaudRatePrescaler_16 ((uint16_t)0x0018) +#define SPI_BaudRatePrescaler_32 ((uint16_t)0x0020) +#define SPI_BaudRatePrescaler_64 ((uint16_t)0x0028) +#define SPI_BaudRatePrescaler_128 ((uint16_t)0x0030) +#define SPI_BaudRatePrescaler_256 ((uint16_t)0x0038) +#define IS_SPI_BAUDRATE_PRESCALER(PRESCALER) (((PRESCALER) == SPI_BaudRatePrescaler_2) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_4) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_8) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_16) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_32) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_64) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_128) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_256)) +/** + * @} + */ + +/** @defgroup SPI_MSB_LSB_transmission + * @{ + */ + +#define SPI_FirstBit_MSB ((uint16_t)0x0000) +#define SPI_FirstBit_LSB ((uint16_t)0x0080) +#define IS_SPI_FIRST_BIT(BIT) (((BIT) == SPI_FirstBit_MSB) || \ + ((BIT) == SPI_FirstBit_LSB)) +/** + * @} + */ + +/** @defgroup I2S_Mode + * @{ + */ + +#define I2S_Mode_SlaveTx ((uint16_t)0x0000) +#define I2S_Mode_SlaveRx ((uint16_t)0x0100) +#define I2S_Mode_MasterTx ((uint16_t)0x0200) +#define I2S_Mode_MasterRx ((uint16_t)0x0300) +#define IS_I2S_MODE(MODE) (((MODE) == I2S_Mode_SlaveTx) || \ + ((MODE) == I2S_Mode_SlaveRx) || \ + ((MODE) == I2S_Mode_MasterTx)|| \ + ((MODE) == I2S_Mode_MasterRx)) +/** + * @} + */ + +/** @defgroup I2S_Standard + * @{ + */ + +#define I2S_Standard_Phillips ((uint16_t)0x0000) +#define I2S_Standard_MSB ((uint16_t)0x0010) +#define I2S_Standard_LSB ((uint16_t)0x0020) +#define I2S_Standard_PCMShort ((uint16_t)0x0030) +#define I2S_Standard_PCMLong ((uint16_t)0x00B0) +#define IS_I2S_STANDARD(STANDARD) (((STANDARD) == I2S_Standard_Phillips) || \ + ((STANDARD) == I2S_Standard_MSB) || \ + ((STANDARD) == I2S_Standard_LSB) || \ + ((STANDARD) == I2S_Standard_PCMShort) || \ + ((STANDARD) == I2S_Standard_PCMLong)) +/** + * @} + */ + +/** @defgroup I2S_Data_Format + * @{ + */ + +#define I2S_DataFormat_16b ((uint16_t)0x0000) +#define I2S_DataFormat_16bextended ((uint16_t)0x0001) +#define I2S_DataFormat_24b ((uint16_t)0x0003) +#define I2S_DataFormat_32b ((uint16_t)0x0005) +#define IS_I2S_DATA_FORMAT(FORMAT) (((FORMAT) == I2S_DataFormat_16b) || \ + ((FORMAT) == I2S_DataFormat_16bextended) || \ + ((FORMAT) == I2S_DataFormat_24b) || \ + ((FORMAT) == I2S_DataFormat_32b)) +/** + * @} + */ + +/** @defgroup I2S_MCLK_Output + * @{ + */ + +#define I2S_MCLKOutput_Enable ((uint16_t)0x0200) +#define I2S_MCLKOutput_Disable ((uint16_t)0x0000) +#define IS_I2S_MCLK_OUTPUT(OUTPUT) (((OUTPUT) == I2S_MCLKOutput_Enable) || \ + ((OUTPUT) == I2S_MCLKOutput_Disable)) +/** + * @} + */ + +/** @defgroup I2S_Audio_Frequency + * @{ + */ + +#define I2S_AudioFreq_192k ((uint32_t)192000) +#define I2S_AudioFreq_96k ((uint32_t)96000) +#define I2S_AudioFreq_48k ((uint32_t)48000) +#define I2S_AudioFreq_44k ((uint32_t)44100) +#define I2S_AudioFreq_32k ((uint32_t)32000) +#define I2S_AudioFreq_22k ((uint32_t)22050) +#define I2S_AudioFreq_16k ((uint32_t)16000) +#define I2S_AudioFreq_11k ((uint32_t)11025) +#define I2S_AudioFreq_8k ((uint32_t)8000) +#define I2S_AudioFreq_Default ((uint32_t)2) + +#define IS_I2S_AUDIO_FREQ(FREQ) ((((FREQ) >= I2S_AudioFreq_8k) && \ + ((FREQ) <= I2S_AudioFreq_192k)) || \ + ((FREQ) == I2S_AudioFreq_Default)) +/** + * @} + */ + +/** @defgroup I2S_Clock_Polarity + * @{ + */ + +#define I2S_CPOL_Low ((uint16_t)0x0000) +#define I2S_CPOL_High ((uint16_t)0x0008) +#define IS_I2S_CPOL(CPOL) (((CPOL) == I2S_CPOL_Low) || \ + ((CPOL) == I2S_CPOL_High)) +/** + * @} + */ + +/** @defgroup SPI_FIFO_reception_threshold + * @{ + */ + +#define SPI_RxFIFOThreshold_HF ((uint16_t)0x0000) +#define SPI_RxFIFOThreshold_QF ((uint16_t)0x1000) +#define IS_SPI_RX_FIFO_THRESHOLD(THRESHOLD) (((THRESHOLD) == SPI_RxFIFOThreshold_HF) || \ + ((THRESHOLD) == SPI_RxFIFOThreshold_QF)) +/** + * @} + */ + +/** @defgroup SPI_I2S_DMA_transfer_requests + * @{ + */ + +#define SPI_I2S_DMAReq_Tx ((uint16_t)0x0002) +#define SPI_I2S_DMAReq_Rx ((uint16_t)0x0001) +#define IS_SPI_I2S_DMA_REQ(REQ) ((((REQ) & (uint16_t)0xFFFC) == 0x00) && ((REQ) != 0x00)) +/** + * @} + */ + +/** @defgroup SPI_last_DMA_transfers + * @{ + */ + +#define SPI_LastDMATransfer_TxEvenRxEven ((uint16_t)0x0000) +#define SPI_LastDMATransfer_TxOddRxEven ((uint16_t)0x4000) +#define SPI_LastDMATransfer_TxEvenRxOdd ((uint16_t)0x2000) +#define SPI_LastDMATransfer_TxOddRxOdd ((uint16_t)0x6000) +#define IS_SPI_LAST_DMA_TRANSFER(TRANSFER) (((TRANSFER) == SPI_LastDMATransfer_TxEvenRxEven) || \ + ((TRANSFER) == SPI_LastDMATransfer_TxOddRxEven) || \ + ((TRANSFER) == SPI_LastDMATransfer_TxEvenRxOdd) || \ + ((TRANSFER) == SPI_LastDMATransfer_TxOddRxOdd)) +/** + * @} + */ +/** @defgroup SPI_NSS_internal_software_management + * @{ + */ + +#define SPI_NSSInternalSoft_Set ((uint16_t)0x0100) +#define SPI_NSSInternalSoft_Reset ((uint16_t)0xFEFF) +#define IS_SPI_NSS_INTERNAL(INTERNAL) (((INTERNAL) == SPI_NSSInternalSoft_Set) || \ + ((INTERNAL) == SPI_NSSInternalSoft_Reset)) +/** + * @} + */ + +/** @defgroup SPI_CRC_Transmit_Receive + * @{ + */ + +#define SPI_CRC_Tx ((uint8_t)0x00) +#define SPI_CRC_Rx ((uint8_t)0x01) +#define IS_SPI_CRC(CRC) (((CRC) == SPI_CRC_Tx) || ((CRC) == SPI_CRC_Rx)) +/** + * @} + */ + +/** @defgroup SPI_direction_transmit_receive + * @{ + */ + +#define SPI_Direction_Rx ((uint16_t)0xBFFF) +#define SPI_Direction_Tx ((uint16_t)0x4000) +#define IS_SPI_DIRECTION(DIRECTION) (((DIRECTION) == SPI_Direction_Rx) || \ + ((DIRECTION) == SPI_Direction_Tx)) +/** + * @} + */ + +/** @defgroup SPI_I2S_interrupts_definition + * @{ + */ + +#define SPI_I2S_IT_TXE ((uint8_t)0x71) +#define SPI_I2S_IT_RXNE ((uint8_t)0x60) +#define SPI_I2S_IT_ERR ((uint8_t)0x50) + +#define IS_SPI_I2S_CONFIG_IT(IT) (((IT) == SPI_I2S_IT_TXE) || \ + ((IT) == SPI_I2S_IT_RXNE) || \ + ((IT) == SPI_I2S_IT_ERR)) + +#define I2S_IT_UDR ((uint8_t)0x53) +#define SPI_IT_MODF ((uint8_t)0x55) +#define SPI_I2S_IT_OVR ((uint8_t)0x56) +#define SPI_I2S_IT_FRE ((uint8_t)0x58) + +#define IS_SPI_I2S_GET_IT(IT) (((IT) == SPI_I2S_IT_RXNE) || ((IT) == SPI_I2S_IT_TXE) || \ + ((IT) == SPI_I2S_IT_OVR) || ((IT) == SPI_IT_MODF) || \ + ((IT) == SPI_I2S_IT_FRE)|| ((IT) == I2S_IT_UDR)) +/** + * @} + */ + + +/** @defgroup SPI_transmission_fifo_status_level + * @{ + */ + +#define SPI_TransmissionFIFOStatus_Empty ((uint16_t)0x0000) +#define SPI_TransmissionFIFOStatus_1QuarterFull ((uint16_t)0x0800) +#define SPI_TransmissionFIFOStatus_HalfFull ((uint16_t)0x1000) +#define SPI_TransmissionFIFOStatus_Full ((uint16_t)0x1800) + +/** + * @} + */ + +/** @defgroup SPI_reception_fifo_status_level + * @{ + */ +#define SPI_ReceptionFIFOStatus_Empty ((uint16_t)0x0000) +#define SPI_ReceptionFIFOStatus_1QuarterFull ((uint16_t)0x0200) +#define SPI_ReceptionFIFOStatus_HalfFull ((uint16_t)0x0400) +#define SPI_ReceptionFIFOStatus_Full ((uint16_t)0x0600) + +/** + * @} + */ + + +/** @defgroup SPI_I2S_flags_definition + * @{ + */ + +#define SPI_I2S_FLAG_RXNE ((uint16_t)0x0001) +#define SPI_I2S_FLAG_TXE ((uint16_t)0x0002) +#define I2S_FLAG_CHSIDE ((uint16_t)0x0004) +#define I2S_FLAG_UDR ((uint16_t)0x0008) +#define SPI_FLAG_CRCERR ((uint16_t)0x0010) +#define SPI_FLAG_MODF ((uint16_t)0x0020) +#define SPI_I2S_FLAG_OVR ((uint16_t)0x0040) +#define SPI_I2S_FLAG_BSY ((uint16_t)0x0080) +#define SPI_I2S_FLAG_FRE ((uint16_t)0x0100) + + + +#define IS_SPI_CLEAR_FLAG(FLAG) (((FLAG) == SPI_FLAG_CRCERR)) +#define IS_SPI_I2S_GET_FLAG(FLAG) (((FLAG) == SPI_I2S_FLAG_BSY) || ((FLAG) == SPI_I2S_FLAG_OVR) || \ + ((FLAG) == SPI_FLAG_MODF) || ((FLAG) == SPI_FLAG_CRCERR) || \ + ((FLAG) == SPI_I2S_FLAG_TXE) || ((FLAG) == SPI_I2S_FLAG_RXNE)|| \ + ((FLAG) == SPI_I2S_FLAG_FRE)|| ((FLAG) == I2S_FLAG_CHSIDE)|| \ + ((FLAG) == I2S_FLAG_UDR)) +/** + * @} + */ + +/** @defgroup SPI_CRC_polynomial + * @{ + */ + +#define IS_SPI_CRC_POLYNOMIAL(POLYNOMIAL) ((POLYNOMIAL) >= 0x1) +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +/* Function used to set the SPI configuration to the default reset state*******/ +void SPI_I2S_DeInit(SPI_TypeDef* SPIx); + +/* Initialization and Configuration functions *********************************/ +void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct); +void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct); +void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct); +void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct); +void SPI_TIModeCmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void SPI_NSSPulseModeCmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize); +void SPI_RxFIFOThresholdConfig(SPI_TypeDef* SPIx, uint16_t SPI_RxFIFOThreshold); +void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction); +void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft); +void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void I2S_FullDuplexConfig(SPI_TypeDef* I2Sxext, I2S_InitTypeDef* I2S_InitStruct); + +/* Data transfers functions ***************************************************/ +void SPI_SendData8(SPI_TypeDef* SPIx, uint8_t Data); +void SPI_I2S_SendData16(SPI_TypeDef* SPIx, uint16_t Data); +uint8_t SPI_ReceiveData8(SPI_TypeDef* SPIx); +uint16_t SPI_I2S_ReceiveData16(SPI_TypeDef* SPIx); + +/* Hardware CRC Calculation functions *****************************************/ +void SPI_CRCLengthConfig(SPI_TypeDef* SPIx, uint16_t SPI_CRCLength); +void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState); +void SPI_TransmitCRC(SPI_TypeDef* SPIx); +uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC); +uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx); + +/* DMA transfers management functions *****************************************/ +void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState); +void SPI_LastDMATransferCmd(SPI_TypeDef* SPIx, uint16_t SPI_LastDMATransfer); + +/* Interrupts and flags management functions **********************************/ +void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState); +uint16_t SPI_GetTransmissionFIFOStatus(SPI_TypeDef* SPIx); +uint16_t SPI_GetReceptionFIFOStatus(SPI_TypeDef* SPIx); +FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); +void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); +ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F30x_SPI_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_syscfg.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_syscfg.h new file mode 100644 index 0000000..d141386 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_syscfg.h @@ -0,0 +1,345 @@ +/** + ****************************************************************************** + * @file stm32f30x_syscfg.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the SYSCFG firmware + * library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/*!< Define to prevent recursive inclusion -----------------------------------*/ +#ifndef __STM32F30x_SYSCFG_H +#define __STM32F30x_SYSCFG_H + +#ifdef __cplusplus + extern "C" { +#endif + +/*!< Includes ----------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup SYSCFG + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup SYSCFG_Exported_Constants + * @{ + */ + +/** @defgroup SYSCFG_EXTI_Port_Sources + * @{ + */ +#define EXTI_PortSourceGPIOA ((uint8_t)0x00) +#define EXTI_PortSourceGPIOB ((uint8_t)0x01) +#define EXTI_PortSourceGPIOC ((uint8_t)0x02) +#define EXTI_PortSourceGPIOD ((uint8_t)0x03) +#define EXTI_PortSourceGPIOE ((uint8_t)0x04) +#define EXTI_PortSourceGPIOF ((uint8_t)0x05) + +#define IS_EXTI_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == EXTI_PortSourceGPIOA) || \ + ((PORTSOURCE) == EXTI_PortSourceGPIOB) || \ + ((PORTSOURCE) == EXTI_PortSourceGPIOC) || \ + ((PORTSOURCE) == EXTI_PortSourceGPIOD) || \ + ((PORTSOURCE) == EXTI_PortSourceGPIOE) || \ + ((PORTSOURCE) == EXTI_PortSourceGPIOF)) +/** + * @} + */ + +/** @defgroup SYSCFG_EXTI_Pin_sources + * @{ + */ +#define EXTI_PinSource0 ((uint8_t)0x00) +#define EXTI_PinSource1 ((uint8_t)0x01) +#define EXTI_PinSource2 ((uint8_t)0x02) +#define EXTI_PinSource3 ((uint8_t)0x03) +#define EXTI_PinSource4 ((uint8_t)0x04) +#define EXTI_PinSource5 ((uint8_t)0x05) +#define EXTI_PinSource6 ((uint8_t)0x06) +#define EXTI_PinSource7 ((uint8_t)0x07) +#define EXTI_PinSource8 ((uint8_t)0x08) +#define EXTI_PinSource9 ((uint8_t)0x09) +#define EXTI_PinSource10 ((uint8_t)0x0A) +#define EXTI_PinSource11 ((uint8_t)0x0B) +#define EXTI_PinSource12 ((uint8_t)0x0C) +#define EXTI_PinSource13 ((uint8_t)0x0D) +#define EXTI_PinSource14 ((uint8_t)0x0E) +#define EXTI_PinSource15 ((uint8_t)0x0F) + +#define IS_EXTI_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == EXTI_PinSource0) || \ + ((PINSOURCE) == EXTI_PinSource1) || \ + ((PINSOURCE) == EXTI_PinSource2) || \ + ((PINSOURCE) == EXTI_PinSource3) || \ + ((PINSOURCE) == EXTI_PinSource4) || \ + ((PINSOURCE) == EXTI_PinSource5) || \ + ((PINSOURCE) == EXTI_PinSource6) || \ + ((PINSOURCE) == EXTI_PinSource7) || \ + ((PINSOURCE) == EXTI_PinSource8) || \ + ((PINSOURCE) == EXTI_PinSource9) || \ + ((PINSOURCE) == EXTI_PinSource10) || \ + ((PINSOURCE) == EXTI_PinSource11) || \ + ((PINSOURCE) == EXTI_PinSource12) || \ + ((PINSOURCE) == EXTI_PinSource13) || \ + ((PINSOURCE) == EXTI_PinSource14) || \ + ((PINSOURCE) == EXTI_PinSource15)) +/** + * @} + */ + +/** @defgroup SYSCFG_Memory_Remap_Config + * @{ + */ +#define SYSCFG_MemoryRemap_Flash ((uint8_t)0x00) +#define SYSCFG_MemoryRemap_SystemMemory ((uint8_t)0x01) +#define SYSCFG_MemoryRemap_SRAM ((uint8_t)0x03) + + +#define IS_SYSCFG_MEMORY_REMAP(REMAP) (((REMAP) == SYSCFG_MemoryRemap_Flash) || \ + ((REMAP) == SYSCFG_MemoryRemap_SystemMemory) || \ + ((REMAP) == SYSCFG_MemoryRemap_SRAM)) + +/** + * @} + */ + +/** @defgroup SYSCFG_DMA_Remap_Config + * @{ + */ +#define SYSCFG_DMARemap_TIM17 SYSCFG_CFGR1_TIM17_DMA_RMP /*!< Remap TIM17 DMA requests from channel1 to channel2 */ +#define SYSCFG_DMARemap_TIM16 SYSCFG_CFGR1_TIM16_DMA_RMP /*!< Remap TIM16 DMA requests from channel3 to channel4 */ +#define SYSCFG_DMARemap_ADC2ADC4 SYSCFG_CFGR1_ADC24_DMA_RMP /*!< Remap ADC2 and ADC4 DMA requests */ + +#define SYSCFG_DMARemap_TIM6DAC1Ch1 SYSCFG_CFGR1_TIM6DAC1Ch1_DMA_RMP /* Remap TIM6/DAC1 Ch1 DMA requests */ +#define SYSCFG_DMARemap_TIM7DAC1Ch2 SYSCFG_CFGR1_TIM7DAC1Ch2_DMA_RMP /* Remap TIM7/DAC1 Ch2 DMA requests */ +#define SYSCFG_DMARemap_DAC2Ch1 SYSCFG_CFGR1_DAC2Ch1_DMA_RMP /* Remap DAC2 Ch1 DMA requests */ + +#define SYSCFG_DMARemapCh2_SPI1_RX ((uint32_t)0x80000003) /* Remap SPI1 RX DMA CH2 requests */ +#define SYSCFG_DMARemapCh4_SPI1_RX ((uint32_t)0x80000001) /* Remap SPI1 RX DMA CH4 requests */ +#define SYSCFG_DMARemapCh6_SPI1_RX ((uint32_t)0x80000002) /* Remap SPI1 RX DMA CH6 requests */ + +#define SYSCFG_DMARemapCh3_SPI1_TX ((uint32_t)0x8000000C) /* Remap SPI1 TX DMA CH2 requests */ +#define SYSCFG_DMARemapCh5_SPI1_TX ((uint32_t)0x80000004) /* Remap SPI1 TX DMA CH5 requests */ +#define SYSCFG_DMARemapCh7_SPI1_TX ((uint32_t)0x80000008) /* Remap SPI1 TX DMA CH7 requests */ + +#define SYSCFG_DMARemapCh7_I2C1_RX ((uint32_t)0x80000030) /* Remap I2C1 RX DMA CH7 requests */ +#define SYSCFG_DMARemapCh3_I2C1_RX ((uint32_t)0x80000010) /* Remap I2C1 RX DMA CH3 requests */ +#define SYSCFG_DMARemapCh5_I2C1_RX ((uint32_t)0x80000020) /* Remap I2C1 RX DMA CH5 requests */ + +#define SYSCFG_DMARemapCh6_I2C1_TX ((uint32_t)0x800000C0) /* Remap I2C1 TX DMA CH6 requests */ +#define SYSCFG_DMARemapCh2_I2C1_TX ((uint32_t)0x80000040) /* Remap I2C1 TX DMA CH2 requests */ +#define SYSCFG_DMARemapCh4_I2C1_TX ((uint32_t)0x80000080) /* Remap I2C1 TX DMA CH4 requests */ + +#define SYSCFG_DMARemapCh4_ADC2 ((uint32_t)0x80000300) /* Remap ADC2 DMA1 Ch4 requests */ +#define SYSCFG_DMARemapCh2_ADC2 ((uint32_t)0x80000200) /* Remap ADC2 DMA1 Ch2 requests */ + +/* SYSCFG_DMA_Remap_Legacy */ +#define SYSCFG_DMARemap_TIM6DAC1 SYSCFG_DMARemap_TIM6DAC1Ch1 /*!< Remap TIM6/DAC1 DMA requests */ +#define SYSCFG_DMARemap_TIM7DAC2 SYSCFG_DMARemap_TIM7DAC1Ch2 /*!< Remap TIM7/DAC2 DMA requests */ + +#define IS_SYSCFG_DMA_REMAP(REMAP) (((REMAP) == SYSCFG_DMARemap_TIM17) || \ + ((REMAP) == SYSCFG_DMARemap_TIM16) || \ + ((REMAP) == SYSCFG_DMARemap_ADC2ADC4) || \ + ((REMAP) == SYSCFG_DMARemap_TIM6DAC1Ch1) || \ + ((REMAP) == SYSCFG_DMARemap_TIM7DAC1Ch2) || \ + ((REMAP) == SYSCFG_DMARemap_DAC2Ch1) || \ + ((REMAP) == SYSCFG_DMARemapCh2_SPI1_RX) || \ + ((REMAP) == SYSCFG_DMARemapCh4_SPI1_RX) || \ + ((REMAP) == SYSCFG_DMARemapCh6_SPI1_RX) || \ + ((REMAP) == SYSCFG_DMARemapCh5_SPI1_TX) || \ + ((REMAP) == SYSCFG_DMARemapCh5_SPI1_TX) || \ + ((REMAP) == SYSCFG_DMARemapCh7_SPI1_TX) || \ + ((REMAP) == SYSCFG_DMARemapCh7_I2C1_RX) || \ + ((REMAP) == SYSCFG_DMARemapCh3_I2C1_RX) || \ + ((REMAP) == SYSCFG_DMARemapCh5_I2C1_RX) || \ + ((REMAP) == SYSCFG_DMARemapCh6_I2C1_TX) || \ + ((REMAP) == SYSCFG_DMARemapCh2_I2C1_TX) || \ + ((REMAP) == SYSCFG_DMARemapCh4_I2C1_TX) || \ + ((REMAP) == SYSCFG_DMARemapCh4_ADC2) || \ + ((REMAP) == SYSCFG_DMARemapCh2_ADC2)) + +/** + * @} + */ + +/** @defgroup SYSCFG_Trigger_Remap_Config + * @{ + */ +#define SYSCFG_TriggerRemap_DACTIM3 SYSCFG_CFGR1_DAC1_TRIG1_RMP /*!< Remap DAC trigger to TIM3 */ +#define SYSCFG_TriggerRemap_TIM1TIM17 SYSCFG_CFGR1_TIM1_ITR3_RMP /*!< Remap TIM1 ITR3 to TIM17 OC */ +#define SYSCFG_TriggerRemap_DACHRTIM1_TRIG1 ((uint32_t)0x80010000) /*!< Remap DAC trigger to HRTIM1 TRIG1 */ +#define SYSCFG_TriggerRemap_DACHRTIM1_TRIG2 ((uint32_t)0x80020000) /*!< Remap DAC trigger to HRTIM1 TRIG2 */ + +#define IS_SYSCFG_TRIGGER_REMAP(REMAP) (((REMAP) == SYSCFG_TriggerRemap_DACTIM3) || \ + ((REMAP) == SYSCFG_TriggerRemap_DACHRTIM1_TRIG1) || \ + ((REMAP) == SYSCFG_TriggerRemap_DACHRTIM1_TRIG2) || \ + ((REMAP) == SYSCFG_TriggerRemap_TIM1TIM17)) + +/** + * @} + */ + +/** @defgroup SYSCFG_EncoderRemap_Config + * @{ + */ +#define SYSCFG_EncoderRemap_No ((uint32_t)0x00000000) /*!< No redirection */ +#define SYSCFG_EncoderRemap_TIM2 SYSCFG_CFGR1_ENCODER_MODE_0 /*!< Timer 2 IC1 and IC2 connected to TIM15 IC1 and IC2 */ +#define SYSCFG_EncoderRemap_TIM3 SYSCFG_CFGR1_ENCODER_MODE_1 /*!< Timer 3 IC1 and IC2 connected to TIM15 IC1 and IC2 */ +#define SYSCFG_EncoderRemap_TIM4 SYSCFG_CFGR1_ENCODER_MODE /*!< Timer 4 IC1 and IC2 connected to TIM15 IC1 and IC2 */ + +#define IS_SYSCFG_ENCODER_REMAP(REMAP) (((REMAP) == SYSCFG_EncoderRemap_No) || \ + ((REMAP) == SYSCFG_EncoderRemap_TIM2) || \ + ((REMAP) == SYSCFG_EncoderRemap_TIM3) || \ + ((REMAP) == SYSCFG_EncoderRemap_TIM4)) + +/** + * @} + */ + +/** @defgroup SYSCFG_I2C_FastModePlus_Config + * @{ + */ +#define SYSCFG_I2CFastModePlus_PB6 SYSCFG_CFGR1_I2C_PB6_FMP /*!< Enable Fast Mode Plus on PB6 */ +#define SYSCFG_I2CFastModePlus_PB7 SYSCFG_CFGR1_I2C_PB7_FMP /*!< Enable Fast Mode Plus on PB7 */ +#define SYSCFG_I2CFastModePlus_PB8 SYSCFG_CFGR1_I2C_PB8_FMP /*!< Enable Fast Mode Plus on PB8 */ +#define SYSCFG_I2CFastModePlus_PB9 SYSCFG_CFGR1_I2C_PB9_FMP /*!< Enable Fast Mode Plus on PB9 */ +#define SYSCFG_I2CFastModePlus_I2C1 SYSCFG_CFGR1_I2C1_FMP /*!< Enable Fast Mode Plus on I2C1 pins */ +#define SYSCFG_I2CFastModePlus_I2C2 SYSCFG_CFGR1_I2C2_FMP /*!< Enable Fast Mode Plus on I2C2 pins */ + +#define IS_SYSCFG_I2C_FMP(PIN) (((PIN) == SYSCFG_I2CFastModePlus_PB6) || \ + ((PIN) == SYSCFG_I2CFastModePlus_PB7) || \ + ((PIN) == SYSCFG_I2CFastModePlus_PB8) || \ + ((PIN) == SYSCFG_I2CFastModePlus_PB9) || \ + ((PIN) == SYSCFG_I2CFastModePlus_I2C1) || \ + ((PIN) == SYSCFG_I2CFastModePlus_I2C2)) + +/** + * @} + */ + +/** @defgroup SYSCFG_FPU_Interrupt_Config + * @{ + */ +#define SYSCFG_IT_IXC SYSCFG_CFGR1_FPU_IE_5 /*!< Inexact Interrupt enable (interrupt disabled by default) */ +#define SYSCFG_IT_IDC SYSCFG_CFGR1_FPU_IE_4 /*!< Input denormal Interrupt enable */ +#define SYSCFG_IT_OFC SYSCFG_CFGR1_FPU_IE_3 /*!< Overflow Interrupt enable */ +#define SYSCFG_IT_UFC SYSCFG_CFGR1_FPU_IE_2 /*!< Underflow Interrupt enable */ +#define SYSCFG_IT_DZC SYSCFG_CFGR1_FPU_IE_1 /*!< Divide-by-zero Interrupt enable */ +#define SYSCFG_IT_IOC SYSCFG_CFGR1_FPU_IE_0 /*!< Invalid operation Interrupt enable */ + +#define IS_SYSCFG_IT(IT) ((((IT) & (uint32_t)0x03FFFFFF) == 0) && ((IT) != 0)) + +/** + * @} + */ + +/** @defgroup SYSCFG_Lock_Config + * @{ + */ +#define SYSCFG_Break_PVD SYSCFG_CFGR2_PVD_LOCK /*!< Enables and locks the PVD connection with TIM1/8/15/16/17 Break Input and also the PVD_EN and PVDSEL[2:0] bits of the Power Control Interface */ +#define SYSCFG_Break_SRAMParity SYSCFG_CFGR2_SRAM_PARITY_LOCK /*!< Enables and locks the SRAM_PARITY error signal with Break Input of TIM1/8/15/16/17 */ +#define SYSCFG_Break_Lockup SYSCFG_CFGR2_LOCKUP_LOCK /*!< Enables and locks the LOCKUP output of CortexM4 with Break Input of TIM1/8/15/16/17 */ + +#define IS_SYSCFG_LOCK_CONFIG(CONFIG) (((CONFIG) == SYSCFG_Break_PVD) || \ + ((CONFIG) == SYSCFG_Break_SRAMParity) || \ + ((CONFIG) == SYSCFG_Break_Lockup)) + +/** + * @} + */ + +/** @defgroup SYSCFG_SRAMWRP_Config + * @{ + */ +#define SYSCFG_SRAMWRP_Page0 SYSCFG_RCR_PAGE0 /*!< ICODE SRAM Write protection page 0 */ +#define SYSCFG_SRAMWRP_Page1 SYSCFG_RCR_PAGE1 /*!< ICODE SRAM Write protection page 1 */ +#define SYSCFG_SRAMWRP_Page2 SYSCFG_RCR_PAGE2 /*!< ICODE SRAM Write protection page 2 */ +#define SYSCFG_SRAMWRP_Page3 SYSCFG_RCR_PAGE3 /*!< ICODE SRAM Write protection page 3 */ +#define SYSCFG_SRAMWRP_Page4 SYSCFG_RCR_PAGE4 /*!< ICODE SRAM Write protection page 4 */ +#define SYSCFG_SRAMWRP_Page5 SYSCFG_RCR_PAGE5 /*!< ICODE SRAM Write protection page 5 */ +#define SYSCFG_SRAMWRP_Page6 SYSCFG_RCR_PAGE6 /*!< ICODE SRAM Write protection page 6 */ +#define SYSCFG_SRAMWRP_Page7 SYSCFG_RCR_PAGE7 /*!< ICODE SRAM Write protection page 7 */ + +#define IS_SYSCFG_PAGE(PAGE)((((PAGE) & (uint32_t)0xFFFFFF00) == 0x00000000) && ((PAGE) != 0x00000000)) + +/** + * @} + */ + +/** @defgroup SYSCFG_flags_definition + * @{ + */ + +#define SYSCFG_FLAG_PE SYSCFG_CFGR2_SRAM_PE + +#define IS_SYSCFG_FLAG(FLAG) (((FLAG) == SYSCFG_FLAG_PE)) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +/* Function used to set the SYSCFG configuration to the default reset state **/ +void SYSCFG_DeInit(void); + +/* SYSCFG configuration functions *********************************************/ +void SYSCFG_MemoryRemapConfig(uint32_t SYSCFG_MemoryRemap); +void SYSCFG_DMAChannelRemapConfig(uint32_t SYSCFG_DMARemap, FunctionalState NewState); +void SYSCFG_TriggerRemapConfig(uint32_t SYSCFG_TriggerRemap, FunctionalState NewState); +void SYSCFG_EncoderRemapConfig(uint32_t SYSCFG_EncoderRemap); +void SYSCFG_USBInterruptLineRemapCmd(FunctionalState NewState); +void SYSCFG_I2CFastModePlusConfig(uint32_t SYSCFG_I2CFastModePlus, FunctionalState NewState); +void SYSCFG_ITConfig(uint32_t SYSCFG_IT, FunctionalState NewState); +void SYSCFG_EXTILineConfig(uint8_t EXTI_PortSourceGPIOx, uint8_t EXTI_PinSourcex); +void SYSCFG_BreakConfig(uint32_t SYSCFG_Break); +void SYSCFG_BypassParityCheckDisable(void); +void SYSCFG_SRAMWRPEnable(uint32_t SYSCFG_SRAMWRP); +FlagStatus SYSCFG_GetFlagStatus(uint32_t SYSCFG_Flag); +void SYSCFG_ClearFlag(uint32_t SYSCFG_Flag); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F30x_SYSCFG_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_tim.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_tim.h new file mode 100644 index 0000000..64da3c6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_tim.h @@ -0,0 +1,1334 @@ +/** + ****************************************************************************** + * @file stm32f30x_tim.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the TIM firmware + * library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_TIM_H +#define __STM32F30x_TIM_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup stm32f30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup TIM + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + +/** + * @brief TIM Time Base Init structure definition + * @note This structure is used with all TIMx except for TIM6 and TIM7. + */ + +typedef struct +{ + uint16_t TIM_Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock. + This parameter can be a number between 0x0000 and 0xFFFF */ + + uint16_t TIM_CounterMode; /*!< Specifies the counter mode. + This parameter can be a value of @ref TIM_Counter_Mode */ + + uint32_t TIM_Period; /*!< Specifies the period value to be loaded into the active + Auto-Reload Register at the next update event. + This parameter must be a number between 0x0000 and 0xFFFF. */ + + uint16_t TIM_ClockDivision; /*!< Specifies the clock division. + This parameter can be a value of @ref TIM_Clock_Division_CKD */ + + uint16_t TIM_RepetitionCounter; /*!< Specifies the repetition counter value. Each time the RCR downcounter + reaches zero, an update event is generated and counting restarts + from the RCR value (N). + This means in PWM mode that (N+1) corresponds to: + - the number of PWM periods in edge-aligned mode + - the number of half PWM period in center-aligned mode + This parameter must be a number between 0x00 and 0xFF. + @note This parameter is valid only for TIM1 and TIM8. */ +} TIM_TimeBaseInitTypeDef; + +/** + * @brief TIM Output Compare Init structure definition + */ + +typedef struct +{ + uint32_t TIM_OCMode; /*!< Specifies the TIM mode. + This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */ + + uint16_t TIM_OutputState; /*!< Specifies the TIM Output Compare state. + This parameter can be a value of @ref TIM_Output_Compare_State */ + + uint16_t TIM_OutputNState; /*!< Specifies the TIM complementary Output Compare state. + This parameter can be a value of @ref TIM_Output_Compare_N_State + @note This parameter is valid only for TIM1 and TIM8. */ + + uint32_t TIM_Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. + This parameter can be a number between 0x0000 and 0xFFFF */ + + uint16_t TIM_OCPolarity; /*!< Specifies the output polarity. + This parameter can be a value of @ref TIM_Output_Compare_Polarity */ + + uint16_t TIM_OCNPolarity; /*!< Specifies the complementary output polarity. + This parameter can be a value of @ref TIM_Output_Compare_N_Polarity + @note This parameter is valid only for TIM1 and TIM8. */ + + uint16_t TIM_OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_Output_Compare_Idle_State + @note This parameter is valid only for TIM1 and TIM8. */ + + uint16_t TIM_OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State + @note This parameter is valid only for TIM1 and TIM8. */ +} TIM_OCInitTypeDef; + +/** + * @brief TIM Input Capture Init structure definition + */ + +typedef struct +{ + + uint16_t TIM_Channel; /*!< Specifies the TIM channel. + This parameter can be a value of @ref TIM_Channel */ + + uint16_t TIM_ICPolarity; /*!< Specifies the active edge of the input signal. + This parameter can be a value of @ref TIM_Input_Capture_Polarity */ + + uint16_t TIM_ICSelection; /*!< Specifies the input. + This parameter can be a value of @ref TIM_Input_Capture_Selection */ + + uint16_t TIM_ICPrescaler; /*!< Specifies the Input Capture Prescaler. + This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ + + uint16_t TIM_ICFilter; /*!< Specifies the input capture filter. + This parameter can be a number between 0x0 and 0xF */ +} TIM_ICInitTypeDef; + +/** + * @brief BDTR structure definition + * @note This structure is used only with TIM1 and TIM8. + */ + +typedef struct +{ + + uint16_t TIM_OSSRState; /*!< Specifies the Off-State selection used in Run mode. + This parameter can be a value of @ref TIM_OSSR_Off_State_Selection_for_Run_mode_state */ + + uint16_t TIM_OSSIState; /*!< Specifies the Off-State used in Idle state. + This parameter can be a value of @ref TIM_OSSI_Off_State_Selection_for_Idle_mode_state */ + + uint16_t TIM_LOCKLevel; /*!< Specifies the LOCK level parameters. + This parameter can be a value of @ref TIM_Lock_level */ + + uint16_t TIM_DeadTime; /*!< Specifies the delay time between the switching-off and the + switching-on of the outputs. + This parameter can be a number between 0x00 and 0xFF */ + + uint16_t TIM_Break; /*!< Specifies whether the TIM Break input is enabled or not. + This parameter can be a value of @ref TIM_Break_Input_enable_disable */ + + uint16_t TIM_BreakPolarity; /*!< Specifies the TIM Break Input pin polarity. + This parameter can be a value of @ref TIM_Break_Polarity */ + + uint16_t TIM_AutomaticOutput; /*!< Specifies whether the TIM Automatic Output feature is enabled or not. + This parameter can be a value of @ref TIM_AOE_Bit_Set_Reset */ +} TIM_BDTRInitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup TIM_Exported_constants + * @{ + */ + +#define IS_TIM_ALL_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM6) || \ + ((PERIPH) == TIM7) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15) || \ + ((PERIPH) == TIM16) || \ + ((PERIPH) == TIM17)) +/* LIST1: TIM1, TIM2, TIM3, TIM4, TIM8, TIM15, TIM16 and TIM17 */ +#define IS_TIM_LIST1_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15) || \ + ((PERIPH) == TIM16) || \ + ((PERIPH) == TIM17)) + +/* LIST2: TIM1, TIM2, TIM3, TIM4, TIM8 and TIM15 */ +#define IS_TIM_LIST2_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15)) +/* LIST3: TIM1, TIM2, TIM3, TIM4 and TIM8 */ +#define IS_TIM_LIST3_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM8)) +/* LIST4: TIM1 and TIM8 */ +#define IS_TIM_LIST4_PERIPH(PERIPH) (((PERIPH) == TIM1) ||\ + ((PERIPH) == TIM8)) +/* LIST5: TIM1, TIM2, TIM3, TIM4, TIM5, TIM6, TIM7 and TIM8 */ +#define IS_TIM_LIST5_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM6) || \ + ((PERIPH) == TIM7) || \ + ((PERIPH) == TIM8)) +/* LIST6: TIM1, TIM8, TIM15, TIM16 and TIM17 */ +#define IS_TIM_LIST6_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15) || \ + ((PERIPH) == TIM16) || \ + ((PERIPH) == TIM17)) + +/* LIST5: TIM1, TIM2, TIM3, TIM4, TIM5, TIM6, TIM7 and TIM8 */ +#define IS_TIM_LIST7_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM6) || \ + ((PERIPH) == TIM7) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15)) +/* LIST8: TIM16 (option register) */ +#define IS_TIM_LIST8_PERIPH(PERIPH) (((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM1)||\ + ((PERIPH) == TIM8)) + +/** @defgroup TIM_Output_Compare_and_PWM_modes + * @{ + */ + +#define TIM_OCMode_Timing ((uint32_t)0x00000) +#define TIM_OCMode_Active ((uint32_t)0x00010) +#define TIM_OCMode_Inactive ((uint32_t)0x00020) +#define TIM_OCMode_Toggle ((uint32_t)0x00030) +#define TIM_OCMode_PWM1 ((uint32_t)0x00060) +#define TIM_OCMode_PWM2 ((uint32_t)0x00070) + +#define TIM_OCMode_Retrigerrable_OPM1 ((uint32_t)0x10000) +#define TIM_OCMode_Retrigerrable_OPM2 ((uint32_t)0x10010) +#define TIM_OCMode_Combined_PWM1 ((uint32_t)0x10040) +#define TIM_OCMode_Combined_PWM2 ((uint32_t)0x10050) +#define TIM_OCMode_Asymmetric_PWM1 ((uint32_t)0x10060) +#define TIM_OCMode_Asymmetric_PWM2 ((uint32_t)0x10070) + +#define IS_TIM_OC_MODE(MODE) (((MODE) == TIM_OCMode_Timing) || \ + ((MODE) == TIM_OCMode_Active) || \ + ((MODE) == TIM_OCMode_Inactive) || \ + ((MODE) == TIM_OCMode_Toggle)|| \ + ((MODE) == TIM_OCMode_PWM1) || \ + ((MODE) == TIM_OCMode_PWM2) || \ + ((MODE) == TIM_OCMode_Retrigerrable_OPM1) || \ + ((MODE) == TIM_OCMode_Retrigerrable_OPM2) || \ + ((MODE) == TIM_OCMode_Combined_PWM1) || \ + ((MODE) == TIM_OCMode_Combined_PWM2) || \ + ((MODE) == TIM_OCMode_Asymmetric_PWM1) || \ + ((MODE) == TIM_OCMode_Asymmetric_PWM2)) + +#define IS_TIM_OCM(MODE) (((MODE) == TIM_OCMode_Timing) || \ + ((MODE) == TIM_OCMode_Active) || \ + ((MODE) == TIM_OCMode_Inactive) || \ + ((MODE) == TIM_OCMode_Toggle)|| \ + ((MODE) == TIM_OCMode_PWM1) || \ + ((MODE) == TIM_OCMode_PWM2) || \ + ((MODE) == TIM_ForcedAction_Active) || \ + ((MODE) == TIM_ForcedAction_InActive) || \ + ((MODE) == TIM_OCMode_Retrigerrable_OPM1) || \ + ((MODE) == TIM_OCMode_Retrigerrable_OPM2) || \ + ((MODE) == TIM_OCMode_Combined_PWM1) || \ + ((MODE) == TIM_OCMode_Combined_PWM2) || \ + ((MODE) == TIM_OCMode_Asymmetric_PWM1) || \ + ((MODE) == TIM_OCMode_Asymmetric_PWM2)) +/** + * @} + */ + +/** @defgroup TIM_One_Pulse_Mode + * @{ + */ + +#define TIM_OPMode_Single ((uint16_t)0x0008) +#define TIM_OPMode_Repetitive ((uint16_t)0x0000) +#define IS_TIM_OPM_MODE(MODE) (((MODE) == TIM_OPMode_Single) || \ + ((MODE) == TIM_OPMode_Repetitive)) +/** + * @} + */ + +/** @defgroup TIM_Channel + * @{ + */ + +#define TIM_Channel_1 ((uint16_t)0x0000) +#define TIM_Channel_2 ((uint16_t)0x0004) +#define TIM_Channel_3 ((uint16_t)0x0008) +#define TIM_Channel_4 ((uint16_t)0x000C) +#define TIM_Channel_5 ((uint16_t)0x0010) +#define TIM_Channel_6 ((uint16_t)0x0014) + +#define IS_TIM_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ + ((CHANNEL) == TIM_Channel_2) || \ + ((CHANNEL) == TIM_Channel_3) || \ + ((CHANNEL) == TIM_Channel_4)) + +#define IS_TIM_PWMI_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ + ((CHANNEL) == TIM_Channel_2)) +#define IS_TIM_COMPLEMENTARY_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ + ((CHANNEL) == TIM_Channel_2) || \ + ((CHANNEL) == TIM_Channel_3)) +/** + * @} + */ + +/** @defgroup TIM_Clock_Division_CKD + * @{ + */ + +#define TIM_CKD_DIV1 ((uint16_t)0x0000) +#define TIM_CKD_DIV2 ((uint16_t)0x0100) +#define TIM_CKD_DIV4 ((uint16_t)0x0200) +#define IS_TIM_CKD_DIV(DIV) (((DIV) == TIM_CKD_DIV1) || \ + ((DIV) == TIM_CKD_DIV2) || \ + ((DIV) == TIM_CKD_DIV4)) +/** + * @} + */ + +/** @defgroup TIM_Counter_Mode + * @{ + */ + +#define TIM_CounterMode_Up ((uint16_t)0x0000) +#define TIM_CounterMode_Down ((uint16_t)0x0010) +#define TIM_CounterMode_CenterAligned1 ((uint16_t)0x0020) +#define TIM_CounterMode_CenterAligned2 ((uint16_t)0x0040) +#define TIM_CounterMode_CenterAligned3 ((uint16_t)0x0060) +#define IS_TIM_COUNTER_MODE(MODE) (((MODE) == TIM_CounterMode_Up) || \ + ((MODE) == TIM_CounterMode_Down) || \ + ((MODE) == TIM_CounterMode_CenterAligned1) || \ + ((MODE) == TIM_CounterMode_CenterAligned2) || \ + ((MODE) == TIM_CounterMode_CenterAligned3)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Polarity + * @{ + */ + +#define TIM_OCPolarity_High ((uint16_t)0x0000) +#define TIM_OCPolarity_Low ((uint16_t)0x0002) +#define IS_TIM_OC_POLARITY(POLARITY) (((POLARITY) == TIM_OCPolarity_High) || \ + ((POLARITY) == TIM_OCPolarity_Low)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_Polarity + * @{ + */ + +#define TIM_OCNPolarity_High ((uint16_t)0x0000) +#define TIM_OCNPolarity_Low ((uint16_t)0x0008) +#define IS_TIM_OCN_POLARITY(POLARITY) (((POLARITY) == TIM_OCNPolarity_High) || \ + ((POLARITY) == TIM_OCNPolarity_Low)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_State + * @{ + */ + +#define TIM_OutputState_Disable ((uint16_t)0x0000) +#define TIM_OutputState_Enable ((uint16_t)0x0001) +#define IS_TIM_OUTPUT_STATE(STATE) (((STATE) == TIM_OutputState_Disable) || \ + ((STATE) == TIM_OutputState_Enable)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_State + * @{ + */ + +#define TIM_OutputNState_Disable ((uint16_t)0x0000) +#define TIM_OutputNState_Enable ((uint16_t)0x0004) +#define IS_TIM_OUTPUTN_STATE(STATE) (((STATE) == TIM_OutputNState_Disable) || \ + ((STATE) == TIM_OutputNState_Enable)) +/** + * @} + */ + +/** @defgroup TIM_Capture_Compare_State + * @{ + */ + +#define TIM_CCx_Enable ((uint16_t)0x0001) +#define TIM_CCx_Disable ((uint16_t)0x0000) +#define IS_TIM_CCX(CCX) (((CCX) == TIM_CCx_Enable) || \ + ((CCX) == TIM_CCx_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Capture_Compare_N_State + * @{ + */ + +#define TIM_CCxN_Enable ((uint16_t)0x0004) +#define TIM_CCxN_Disable ((uint16_t)0x0000) +#define IS_TIM_CCXN(CCXN) (((CCXN) == TIM_CCxN_Enable) || \ + ((CCXN) == TIM_CCxN_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Break_Input_enable_disable + * @{ + */ + +#define TIM_Break_Enable ((uint16_t)0x1000) +#define TIM_Break_Disable ((uint16_t)0x0000) +#define IS_TIM_BREAK_STATE(STATE) (((STATE) == TIM_Break_Enable) || \ + ((STATE) == TIM_Break_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Break1_Input_enable_disable + * @{ + */ + +#define TIM_Break1_Enable ((uint32_t)0x00001000) +#define TIM_Break1_Disable ((uint32_t)0x00000000) +#define IS_TIM_BREAK1_STATE(STATE) (((STATE) == TIM_Break1_Enable) || \ + ((STATE) == TIM_Break1_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Break2_Input_enable_disable + * @{ + */ + +#define TIM_Break2_Enable ((uint32_t)0x01000000) +#define TIM_Break2_Disable ((uint32_t)0x00000000) +#define IS_TIM_BREAK2_STATE(STATE) (((STATE) == TIM_Break2_Enable) || \ + ((STATE) == TIM_Break2_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Break_Polarity + * @{ + */ + +#define TIM_BreakPolarity_Low ((uint16_t)0x0000) +#define TIM_BreakPolarity_High ((uint16_t)0x2000) +#define IS_TIM_BREAK_POLARITY(POLARITY) (((POLARITY) == TIM_BreakPolarity_Low) || \ + ((POLARITY) == TIM_BreakPolarity_High)) +/** + * @} + */ + +/** @defgroup TIM_Break1_Polarity + * @{ + */ + +#define TIM_Break1Polarity_Low ((uint32_t)0x00000000) +#define TIM_Break1Polarity_High ((uint32_t)0x00002000) +#define IS_TIM_BREAK1_POLARITY(POLARITY) (((POLARITY) == TIM_Break1Polarity_Low) || \ + ((POLARITY) == TIM_Break1Polarity_High)) +/** + * @} + */ + +/** @defgroup TIM_Break2_Polarity + * @{ + */ + +#define TIM_Break2Polarity_Low ((uint32_t)0x00000000) +#define TIM_Break2Polarity_High ((uint32_t)0x02000000) +#define IS_TIM_BREAK2_POLARITY(POLARITY) (((POLARITY) == TIM_Break2Polarity_Low) || \ + ((POLARITY) == TIM_Break2Polarity_High)) +/** + * @} + */ + +/** @defgroup TIM_Break1_Filter + * @{ + */ + +#define IS_TIM_BREAK1_FILTER(FILTER) ((FILTER) <= 0xF) +/** + * @} + */ + +/** @defgroup TIM_Break2_Filter + * @{ + */ + +#define IS_TIM_BREAK2_FILTER(FILTER) ((FILTER) <= 0xF) +/** + * @} + */ + +/** @defgroup TIM_AOE_Bit_Set_Reset + * @{ + */ + +#define TIM_AutomaticOutput_Enable ((uint16_t)0x4000) +#define TIM_AutomaticOutput_Disable ((uint16_t)0x0000) +#define IS_TIM_AUTOMATIC_OUTPUT_STATE(STATE) (((STATE) == TIM_AutomaticOutput_Enable) || \ + ((STATE) == TIM_AutomaticOutput_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Lock_level + * @{ + */ + +#define TIM_LOCKLevel_OFF ((uint16_t)0x0000) +#define TIM_LOCKLevel_1 ((uint16_t)0x0100) +#define TIM_LOCKLevel_2 ((uint16_t)0x0200) +#define TIM_LOCKLevel_3 ((uint16_t)0x0300) +#define IS_TIM_LOCK_LEVEL(LEVEL) (((LEVEL) == TIM_LOCKLevel_OFF) || \ + ((LEVEL) == TIM_LOCKLevel_1) || \ + ((LEVEL) == TIM_LOCKLevel_2) || \ + ((LEVEL) == TIM_LOCKLevel_3)) +/** + * @} + */ + +/** @defgroup TIM_OSSI_Off_State_Selection_for_Idle_mode_state + * @{ + */ + +#define TIM_OSSIState_Enable ((uint16_t)0x0400) +#define TIM_OSSIState_Disable ((uint16_t)0x0000) +#define IS_TIM_OSSI_STATE(STATE) (((STATE) == TIM_OSSIState_Enable) || \ + ((STATE) == TIM_OSSIState_Disable)) +/** + * @} + */ + +/** @defgroup TIM_OSSR_Off_State_Selection_for_Run_mode_state + * @{ + */ + +#define TIM_OSSRState_Enable ((uint16_t)0x0800) +#define TIM_OSSRState_Disable ((uint16_t)0x0000) +#define IS_TIM_OSSR_STATE(STATE) (((STATE) == TIM_OSSRState_Enable) || \ + ((STATE) == TIM_OSSRState_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Idle_State + * @{ + */ + +#define TIM_OCIdleState_Set ((uint16_t)0x0100) +#define TIM_OCIdleState_Reset ((uint16_t)0x0000) +#define IS_TIM_OCIDLE_STATE(STATE) (((STATE) == TIM_OCIdleState_Set) || \ + ((STATE) == TIM_OCIdleState_Reset)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_Idle_State + * @{ + */ + +#define TIM_OCNIdleState_Set ((uint16_t)0x0200) +#define TIM_OCNIdleState_Reset ((uint16_t)0x0000) +#define IS_TIM_OCNIDLE_STATE(STATE) (((STATE) == TIM_OCNIdleState_Set) || \ + ((STATE) == TIM_OCNIdleState_Reset)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Polarity + * @{ + */ + +#define TIM_ICPolarity_Rising ((uint16_t)0x0000) +#define TIM_ICPolarity_Falling ((uint16_t)0x0002) +#define TIM_ICPolarity_BothEdge ((uint16_t)0x000A) +#define IS_TIM_IC_POLARITY(POLARITY) (((POLARITY) == TIM_ICPolarity_Rising) || \ + ((POLARITY) == TIM_ICPolarity_Falling)|| \ + ((POLARITY) == TIM_ICPolarity_BothEdge)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Selection + * @{ + */ + +#define TIM_ICSelection_DirectTI ((uint16_t)0x0001) /*!< TIM Input 1, 2, 3 or 4 is selected to be + connected to IC1, IC2, IC3 or IC4, respectively */ +#define TIM_ICSelection_IndirectTI ((uint16_t)0x0002) /*!< TIM Input 1, 2, 3 or 4 is selected to be + connected to IC2, IC1, IC4 or IC3, respectively. */ +#define TIM_ICSelection_TRC ((uint16_t)0x0003) /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to TRC. */ +#define IS_TIM_IC_SELECTION(SELECTION) (((SELECTION) == TIM_ICSelection_DirectTI) || \ + ((SELECTION) == TIM_ICSelection_IndirectTI) || \ + ((SELECTION) == TIM_ICSelection_TRC)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Prescaler + * @{ + */ + +#define TIM_ICPSC_DIV1 ((uint16_t)0x0000) /*!< Capture performed each time an edge is detected on the capture input. */ +#define TIM_ICPSC_DIV2 ((uint16_t)0x0004) /*!< Capture performed once every 2 events. */ +#define TIM_ICPSC_DIV4 ((uint16_t)0x0008) /*!< Capture performed once every 4 events. */ +#define TIM_ICPSC_DIV8 ((uint16_t)0x000C) /*!< Capture performed once every 8 events. */ +#define IS_TIM_IC_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ICPSC_DIV1) || \ + ((PRESCALER) == TIM_ICPSC_DIV2) || \ + ((PRESCALER) == TIM_ICPSC_DIV4) || \ + ((PRESCALER) == TIM_ICPSC_DIV8)) +/** + * @} + */ + +/** @defgroup TIM_interrupt_sources + * @{ + */ + +#define TIM_IT_Update ((uint16_t)0x0001) +#define TIM_IT_CC1 ((uint16_t)0x0002) +#define TIM_IT_CC2 ((uint16_t)0x0004) +#define TIM_IT_CC3 ((uint16_t)0x0008) +#define TIM_IT_CC4 ((uint16_t)0x0010) +#define TIM_IT_COM ((uint16_t)0x0020) +#define TIM_IT_Trigger ((uint16_t)0x0040) +#define TIM_IT_Break ((uint16_t)0x0080) +#define IS_TIM_IT(IT) ((((IT) & (uint16_t)0xFF00) == 0x0000) && ((IT) != 0x0000)) + +#define IS_TIM_GET_IT(IT) (((IT) == TIM_IT_Update) || \ + ((IT) == TIM_IT_CC1) || \ + ((IT) == TIM_IT_CC2) || \ + ((IT) == TIM_IT_CC3) || \ + ((IT) == TIM_IT_CC4) || \ + ((IT) == TIM_IT_COM) || \ + ((IT) == TIM_IT_Trigger) || \ + ((IT) == TIM_IT_Break)) +/** + * @} + */ + +/** @defgroup TIM_DMA_Base_address + * @{ + */ + +#define TIM_DMABase_CR1 ((uint16_t)0x0000) +#define TIM_DMABase_CR2 ((uint16_t)0x0001) +#define TIM_DMABase_SMCR ((uint16_t)0x0002) +#define TIM_DMABase_DIER ((uint16_t)0x0003) +#define TIM_DMABase_SR ((uint16_t)0x0004) +#define TIM_DMABase_EGR ((uint16_t)0x0005) +#define TIM_DMABase_CCMR1 ((uint16_t)0x0006) +#define TIM_DMABase_CCMR2 ((uint16_t)0x0007) +#define TIM_DMABase_CCER ((uint16_t)0x0008) +#define TIM_DMABase_CNT ((uint16_t)0x0009) +#define TIM_DMABase_PSC ((uint16_t)0x000A) +#define TIM_DMABase_ARR ((uint16_t)0x000B) +#define TIM_DMABase_RCR ((uint16_t)0x000C) +#define TIM_DMABase_CCR1 ((uint16_t)0x000D) +#define TIM_DMABase_CCR2 ((uint16_t)0x000E) +#define TIM_DMABase_CCR3 ((uint16_t)0x000F) +#define TIM_DMABase_CCR4 ((uint16_t)0x0010) +#define TIM_DMABase_BDTR ((uint16_t)0x0011) +#define TIM_DMABase_DCR ((uint16_t)0x0012) +#define TIM_DMABase_OR ((uint16_t)0x0013) +#define TIM_DMABase_CCMR3 ((uint16_t)0x0014) +#define TIM_DMABase_CCR5 ((uint16_t)0x0015) +#define TIM_DMABase_CCR6 ((uint16_t)0x0016) +#define IS_TIM_DMA_BASE(BASE) (((BASE) == TIM_DMABase_CR1) || \ + ((BASE) == TIM_DMABase_CR2) || \ + ((BASE) == TIM_DMABase_SMCR) || \ + ((BASE) == TIM_DMABase_DIER) || \ + ((BASE) == TIM_DMABase_SR) || \ + ((BASE) == TIM_DMABase_EGR) || \ + ((BASE) == TIM_DMABase_CCMR1) || \ + ((BASE) == TIM_DMABase_CCMR2) || \ + ((BASE) == TIM_DMABase_CCER) || \ + ((BASE) == TIM_DMABase_CNT) || \ + ((BASE) == TIM_DMABase_PSC) || \ + ((BASE) == TIM_DMABase_ARR) || \ + ((BASE) == TIM_DMABase_RCR) || \ + ((BASE) == TIM_DMABase_CCR1) || \ + ((BASE) == TIM_DMABase_CCR2) || \ + ((BASE) == TIM_DMABase_CCR3) || \ + ((BASE) == TIM_DMABase_CCR4) || \ + ((BASE) == TIM_DMABase_BDTR) || \ + ((BASE) == TIM_DMABase_DCR) || \ + ((BASE) == TIM_DMABase_OR) || \ + ((BASE) == TIM_DMABase_CCMR3) || \ + ((BASE) == TIM_DMABase_CCR5) || \ + ((BASE) == TIM_DMABase_CCR6)) +/** + * @} + */ + +/** @defgroup TIM_DMA_Burst_Length + * @{ + */ + +#define TIM_DMABurstLength_1Transfer ((uint16_t)0x0000) +#define TIM_DMABurstLength_2Transfers ((uint16_t)0x0100) +#define TIM_DMABurstLength_3Transfers ((uint16_t)0x0200) +#define TIM_DMABurstLength_4Transfers ((uint16_t)0x0300) +#define TIM_DMABurstLength_5Transfers ((uint16_t)0x0400) +#define TIM_DMABurstLength_6Transfers ((uint16_t)0x0500) +#define TIM_DMABurstLength_7Transfers ((uint16_t)0x0600) +#define TIM_DMABurstLength_8Transfers ((uint16_t)0x0700) +#define TIM_DMABurstLength_9Transfers ((uint16_t)0x0800) +#define TIM_DMABurstLength_10Transfers ((uint16_t)0x0900) +#define TIM_DMABurstLength_11Transfers ((uint16_t)0x0A00) +#define TIM_DMABurstLength_12Transfers ((uint16_t)0x0B00) +#define TIM_DMABurstLength_13Transfers ((uint16_t)0x0C00) +#define TIM_DMABurstLength_14Transfers ((uint16_t)0x0D00) +#define TIM_DMABurstLength_15Transfers ((uint16_t)0x0E00) +#define TIM_DMABurstLength_16Transfers ((uint16_t)0x0F00) +#define TIM_DMABurstLength_17Transfers ((uint16_t)0x1000) +#define TIM_DMABurstLength_18Transfers ((uint16_t)0x1100) +#define IS_TIM_DMA_LENGTH(LENGTH) (((LENGTH) == TIM_DMABurstLength_1Transfer) || \ + ((LENGTH) == TIM_DMABurstLength_2Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_3Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_4Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_5Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_6Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_7Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_8Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_9Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_10Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_11Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_12Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_13Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_14Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_15Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_16Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_17Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_18Transfers)) +/** + * @} + */ + +/** @defgroup TIM_DMA_sources + * @{ + */ + +#define TIM_DMA_Update ((uint16_t)0x0100) +#define TIM_DMA_CC1 ((uint16_t)0x0200) +#define TIM_DMA_CC2 ((uint16_t)0x0400) +#define TIM_DMA_CC3 ((uint16_t)0x0800) +#define TIM_DMA_CC4 ((uint16_t)0x1000) +#define TIM_DMA_COM ((uint16_t)0x2000) +#define TIM_DMA_Trigger ((uint16_t)0x4000) +#define IS_TIM_DMA_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0x80FF) == 0x0000) && ((SOURCE) != 0x0000)) + +/** + * @} + */ + +/** @defgroup TIM_External_Trigger_Prescaler + * @{ + */ + +#define TIM_ExtTRGPSC_OFF ((uint16_t)0x0000) +#define TIM_ExtTRGPSC_DIV2 ((uint16_t)0x1000) +#define TIM_ExtTRGPSC_DIV4 ((uint16_t)0x2000) +#define TIM_ExtTRGPSC_DIV8 ((uint16_t)0x3000) +#define IS_TIM_EXT_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ExtTRGPSC_OFF) || \ + ((PRESCALER) == TIM_ExtTRGPSC_DIV2) || \ + ((PRESCALER) == TIM_ExtTRGPSC_DIV4) || \ + ((PRESCALER) == TIM_ExtTRGPSC_DIV8)) +/** + * @} + */ + +/** @defgroup TIM_Internal_Trigger_Selection + * @{ + */ + +#define TIM_TS_ITR0 ((uint16_t)0x0000) +#define TIM_TS_ITR1 ((uint16_t)0x0010) +#define TIM_TS_ITR2 ((uint16_t)0x0020) +#define TIM_TS_ITR3 ((uint16_t)0x0030) +#define TIM_TS_TI1F_ED ((uint16_t)0x0040) +#define TIM_TS_TI1FP1 ((uint16_t)0x0050) +#define TIM_TS_TI2FP2 ((uint16_t)0x0060) +#define TIM_TS_ETRF ((uint16_t)0x0070) +#define IS_TIM_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \ + ((SELECTION) == TIM_TS_ITR1) || \ + ((SELECTION) == TIM_TS_ITR2) || \ + ((SELECTION) == TIM_TS_ITR3) || \ + ((SELECTION) == TIM_TS_TI1F_ED) || \ + ((SELECTION) == TIM_TS_TI1FP1) || \ + ((SELECTION) == TIM_TS_TI2FP2) || \ + ((SELECTION) == TIM_TS_ETRF)) +#define IS_TIM_INTERNAL_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \ + ((SELECTION) == TIM_TS_ITR1) || \ + ((SELECTION) == TIM_TS_ITR2) || \ + ((SELECTION) == TIM_TS_ITR3)) +/** + * @} + */ + +/** @defgroup TIM_TIx_External_Clock_Source + * @{ + */ + +#define TIM_TIxExternalCLK1Source_TI1 ((uint16_t)0x0050) +#define TIM_TIxExternalCLK1Source_TI2 ((uint16_t)0x0060) +#define TIM_TIxExternalCLK1Source_TI1ED ((uint16_t)0x0040) + +/** + * @} + */ + +/** @defgroup TIM_External_Trigger_Polarity + * @{ + */ +#define TIM_ExtTRGPolarity_Inverted ((uint16_t)0x8000) +#define TIM_ExtTRGPolarity_NonInverted ((uint16_t)0x0000) +#define IS_TIM_EXT_POLARITY(POLARITY) (((POLARITY) == TIM_ExtTRGPolarity_Inverted) || \ + ((POLARITY) == TIM_ExtTRGPolarity_NonInverted)) +/** + * @} + */ + +/** @defgroup TIM_Prescaler_Reload_Mode + * @{ + */ + +#define TIM_PSCReloadMode_Update ((uint16_t)0x0000) +#define TIM_PSCReloadMode_Immediate ((uint16_t)0x0001) +#define IS_TIM_PRESCALER_RELOAD(RELOAD) (((RELOAD) == TIM_PSCReloadMode_Update) || \ + ((RELOAD) == TIM_PSCReloadMode_Immediate)) +/** + * @} + */ + +/** @defgroup TIM_Forced_Action + * @{ + */ + +#define TIM_ForcedAction_Active ((uint16_t)0x0050) +#define TIM_ForcedAction_InActive ((uint16_t)0x0040) +#define IS_TIM_FORCED_ACTION(ACTION) (((ACTION) == TIM_ForcedAction_Active) || \ + ((ACTION) == TIM_ForcedAction_InActive)) +/** + * @} + */ + +/** @defgroup TIM_Encoder_Mode + * @{ + */ + +#define TIM_EncoderMode_TI1 ((uint16_t)0x0001) +#define TIM_EncoderMode_TI2 ((uint16_t)0x0002) +#define TIM_EncoderMode_TI12 ((uint16_t)0x0003) +#define IS_TIM_ENCODER_MODE(MODE) (((MODE) == TIM_EncoderMode_TI1) || \ + ((MODE) == TIM_EncoderMode_TI2) || \ + ((MODE) == TIM_EncoderMode_TI12)) +/** + * @} + */ + + +/** @defgroup TIM_Event_Source + * @{ + */ + +#define TIM_EventSource_Update ((uint16_t)0x0001) +#define TIM_EventSource_CC1 ((uint16_t)0x0002) +#define TIM_EventSource_CC2 ((uint16_t)0x0004) +#define TIM_EventSource_CC3 ((uint16_t)0x0008) +#define TIM_EventSource_CC4 ((uint16_t)0x0010) +#define TIM_EventSource_COM ((uint16_t)0x0020) +#define TIM_EventSource_Trigger ((uint16_t)0x0040) +#define TIM_EventSource_Break ((uint16_t)0x0080) +#define TIM_EventSource_Break2 ((uint16_t)0x0100) +#define IS_TIM_EVENT_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0xFE00) == 0x0000) && ((SOURCE) != 0x0000)) + +/** + * @} + */ + +/** @defgroup TIM_Update_Source + * @{ + */ + +#define TIM_UpdateSource_Global ((uint16_t)0x0000) /*!< Source of update is the counter overflow/underflow + or the setting of UG bit, or an update generation + through the slave mode controller. */ +#define TIM_UpdateSource_Regular ((uint16_t)0x0001) /*!< Source of update is counter overflow/underflow. */ +#define IS_TIM_UPDATE_SOURCE(SOURCE) (((SOURCE) == TIM_UpdateSource_Global) || \ + ((SOURCE) == TIM_UpdateSource_Regular)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Preload_State + * @{ + */ + +#define TIM_OCPreload_Enable ((uint16_t)0x0008) +#define TIM_OCPreload_Disable ((uint16_t)0x0000) +#define IS_TIM_OCPRELOAD_STATE(STATE) (((STATE) == TIM_OCPreload_Enable) || \ + ((STATE) == TIM_OCPreload_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Fast_State + * @{ + */ + +#define TIM_OCFast_Enable ((uint16_t)0x0004) +#define TIM_OCFast_Disable ((uint16_t)0x0000) +#define IS_TIM_OCFAST_STATE(STATE) (((STATE) == TIM_OCFast_Enable) || \ + ((STATE) == TIM_OCFast_Disable)) + +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Clear_State + * @{ + */ + +#define TIM_OCClear_Enable ((uint16_t)0x0080) +#define TIM_OCClear_Disable ((uint16_t)0x0000) +#define IS_TIM_OCCLEAR_STATE(STATE) (((STATE) == TIM_OCClear_Enable) || \ + ((STATE) == TIM_OCClear_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Trigger_Output_Source + * @{ + */ + +#define TIM_TRGOSource_Reset ((uint16_t)0x0000) +#define TIM_TRGOSource_Enable ((uint16_t)0x0010) +#define TIM_TRGOSource_Update ((uint16_t)0x0020) +#define TIM_TRGOSource_OC1 ((uint16_t)0x0030) +#define TIM_TRGOSource_OC1Ref ((uint16_t)0x0040) +#define TIM_TRGOSource_OC2Ref ((uint16_t)0x0050) +#define TIM_TRGOSource_OC3Ref ((uint16_t)0x0060) +#define TIM_TRGOSource_OC4Ref ((uint16_t)0x0070) +#define IS_TIM_TRGO_SOURCE(SOURCE) (((SOURCE) == TIM_TRGOSource_Reset) || \ + ((SOURCE) == TIM_TRGOSource_Enable) || \ + ((SOURCE) == TIM_TRGOSource_Update) || \ + ((SOURCE) == TIM_TRGOSource_OC1) || \ + ((SOURCE) == TIM_TRGOSource_OC1Ref) || \ + ((SOURCE) == TIM_TRGOSource_OC2Ref) || \ + ((SOURCE) == TIM_TRGOSource_OC3Ref) || \ + ((SOURCE) == TIM_TRGOSource_OC4Ref)) + + +#define TIM_TRGO2Source_Reset ((uint32_t)0x00000000) +#define TIM_TRGO2Source_Enable ((uint32_t)0x00100000) +#define TIM_TRGO2Source_Update ((uint32_t)0x00200000) +#define TIM_TRGO2Source_OC1 ((uint32_t)0x00300000) +#define TIM_TRGO2Source_OC1Ref ((uint32_t)0x00400000) +#define TIM_TRGO2Source_OC2Ref ((uint32_t)0x00500000) +#define TIM_TRGO2Source_OC3Ref ((uint32_t)0x00600000) +#define TIM_TRGO2Source_OC4Ref ((uint32_t)0x00700000) +#define TIM_TRGO2Source_OC5Ref ((uint32_t)0x00800000) +#define TIM_TRGO2Source_OC6Ref ((uint32_t)0x00900000) +#define TIM_TRGO2Source_OC4Ref_RisingFalling ((uint32_t)0x00A00000) +#define TIM_TRGO2Source_OC6Ref_RisingFalling ((uint32_t)0x00B00000) +#define TIM_TRGO2Source_OC4RefRising_OC6RefRising ((uint32_t)0x00C00000) +#define TIM_TRGO2Source_OC4RefRising_OC6RefFalling ((uint32_t)0x00D00000) +#define TIM_TRGO2Source_OC5RefRising_OC6RefRising ((uint32_t)0x00E00000) +#define TIM_TRGO2Source_OC5RefRising_OC6RefFalling ((uint32_t)0x00F00000) +#define IS_TIM_TRGO2_SOURCE(SOURCE) (((SOURCE) == TIM_TRGO2Source_Reset) || \ + ((SOURCE) == TIM_TRGO2Source_Enable) || \ + ((SOURCE) == TIM_TRGO2Source_Update) || \ + ((SOURCE) == TIM_TRGO2Source_OC1) || \ + ((SOURCE) == TIM_TRGO2Source_OC1Ref) || \ + ((SOURCE) == TIM_TRGO2Source_OC2Ref) || \ + ((SOURCE) == TIM_TRGO2Source_OC3Ref) || \ + ((SOURCE) == TIM_TRGO2Source_OC4Ref) || \ + ((SOURCE) == TIM_TRGO2Source_OC5Ref) || \ + ((SOURCE) == TIM_TRGO2Source_OC6Ref) || \ + ((SOURCE) == TIM_TRGO2Source_OC4Ref_RisingFalling) || \ + ((SOURCE) == TIM_TRGO2Source_OC6Ref_RisingFalling) || \ + ((SOURCE) == TIM_TRGO2Source_OC4RefRising_OC6RefRising) || \ + ((SOURCE) == TIM_TRGO2Source_OC4RefRising_OC6RefFalling) || \ + ((SOURCE) == TIM_TRGO2Source_OC5RefRising_OC6RefRising) || \ + ((SOURCE) == TIM_TRGO2Source_OC5RefRising_OC6RefFalling)) +/** + * @} + */ + +/** @defgroup TIM_Slave_Mode + * @{ + */ + +#define TIM_SlaveMode_Reset ((uint32_t)0x00004) +#define TIM_SlaveMode_Gated ((uint32_t)0x00005) +#define TIM_SlaveMode_Trigger ((uint32_t)0x00006) +#define TIM_SlaveMode_External1 ((uint32_t)0x00007) +#define TIM_SlaveMode_Combined_ResetTrigger ((uint32_t)0x10000) +#define IS_TIM_SLAVE_MODE(MODE) (((MODE) == TIM_SlaveMode_Reset) || \ + ((MODE) == TIM_SlaveMode_Gated) || \ + ((MODE) == TIM_SlaveMode_Trigger) || \ + ((MODE) == TIM_SlaveMode_External1) || \ + ((MODE) == TIM_SlaveMode_Combined_ResetTrigger)) +/** + * @} + */ + +/** @defgroup TIM_Master_Slave_Mode + * @{ + */ + +#define TIM_MasterSlaveMode_Enable ((uint16_t)0x0080) +#define TIM_MasterSlaveMode_Disable ((uint16_t)0x0000) +#define IS_TIM_MSM_STATE(STATE) (((STATE) == TIM_MasterSlaveMode_Enable) || \ + ((STATE) == TIM_MasterSlaveMode_Disable)) +/** + * @} + */ +/** @defgroup TIM_Remap + * @{ + */ +#define TIM16_GPIO ((uint16_t)0x0000) +#define TIM16_RTC_CLK ((uint16_t)0x0001) +#define TIM16_HSEDiv32 ((uint16_t)0x0002) +#define TIM16_MCO ((uint16_t)0x0003) + +#define TIM1_ADC1_AWDG1 ((uint16_t)0x0001) +#define TIM1_ADC1_AWDG2 ((uint16_t)0x0002) +#define TIM1_ADC1_AWDG3 ((uint16_t)0x0003) +#define TIM1_ADC4_AWDG1 ((uint16_t)0x0004) +#define TIM1_ADC4_AWDG2 ((uint16_t)0x0008) +#define TIM1_ADC4_AWDG3 ((uint16_t)0x000C) + +#define TIM8_ADC2_AWDG1 ((uint16_t)0x0001) +#define TIM8_ADC2_AWDG2 ((uint16_t)0x0002) +#define TIM8_ADC2_AWDG3 ((uint16_t)0x0003) +#define TIM8_ADC3_AWDG1 ((uint16_t)0x0004) +#define TIM8_ADC3_AWDG2 ((uint16_t)0x0008) +#define TIM8_ADC3_AWDG3 ((uint16_t)0x000C) + +#define IS_TIM_REMAP(TIM_REMAP) (((TIM_REMAP) == TIM16_GPIO)|| \ + ((TIM_REMAP) == TIM16_RTC_CLK) || \ + ((TIM_REMAP) == TIM16_HSEDiv32) || \ + ((TIM_REMAP) == TIM16_MCO) ||\ + ((TIM_REMAP) == TIM1_ADC1_AWDG1) ||\ + ((TIM_REMAP) == TIM1_ADC1_AWDG2) ||\ + ((TIM_REMAP) == TIM1_ADC1_AWDG3) ||\ + ((TIM_REMAP) == TIM1_ADC4_AWDG1) ||\ + ((TIM_REMAP) == TIM1_ADC4_AWDG2) ||\ + ((TIM_REMAP) == TIM1_ADC4_AWDG3) ||\ + ((TIM_REMAP) == TIM8_ADC2_AWDG1) ||\ + ((TIM_REMAP) == TIM8_ADC2_AWDG2) ||\ + ((TIM_REMAP) == TIM8_ADC2_AWDG3) ||\ + ((TIM_REMAP) == TIM8_ADC3_AWDG1) ||\ + ((TIM_REMAP) == TIM8_ADC3_AWDG2) ||\ + ((TIM_REMAP) == TIM8_ADC3_AWDG3)) + +/** + * @} + */ +/** @defgroup TIM_Flags + * @{ + */ + +#define TIM_FLAG_Update ((uint32_t)0x00001) +#define TIM_FLAG_CC1 ((uint32_t)0x00002) +#define TIM_FLAG_CC2 ((uint32_t)0x00004) +#define TIM_FLAG_CC3 ((uint32_t)0x00008) +#define TIM_FLAG_CC4 ((uint32_t)0x00010) +#define TIM_FLAG_COM ((uint32_t)0x00020) +#define TIM_FLAG_Trigger ((uint32_t)0x00040) +#define TIM_FLAG_Break ((uint32_t)0x00080) +#define TIM_FLAG_Break2 ((uint32_t)0x00100) +#define TIM_FLAG_CC1OF ((uint32_t)0x00200) +#define TIM_FLAG_CC2OF ((uint32_t)0x00400) +#define TIM_FLAG_CC3OF ((uint32_t)0x00800) +#define TIM_FLAG_CC4OF ((uint32_t)0x01000) +#define TIM_FLAG_CC5 ((uint32_t)0x10000) +#define TIM_FLAG_CC6 ((uint32_t)0x20000) +#define IS_TIM_GET_FLAG(FLAG) (((FLAG) == TIM_FLAG_Update) || \ + ((FLAG) == TIM_FLAG_CC1) || \ + ((FLAG) == TIM_FLAG_CC2) || \ + ((FLAG) == TIM_FLAG_CC3) || \ + ((FLAG) == TIM_FLAG_CC4) || \ + ((FLAG) == TIM_FLAG_COM) || \ + ((FLAG) == TIM_FLAG_Trigger) || \ + ((FLAG) == TIM_FLAG_Break) || \ + ((FLAG) == TIM_FLAG_Break2) || \ + ((FLAG) == TIM_FLAG_CC1OF) || \ + ((FLAG) == TIM_FLAG_CC2OF) || \ + ((FLAG) == TIM_FLAG_CC3OF) || \ + ((FLAG) == TIM_FLAG_CC4OF) ||\ + ((FLAG) == TIM_FLAG_CC5) ||\ + ((FLAG) == TIM_FLAG_CC6)) + +#define IS_TIM_CLEAR_FLAG(TIM_FLAG) ((((TIM_FLAG) & (uint32_t)0xE000) == 0x0000) && ((TIM_FLAG) != 0x0000)) +/** + * @} + */ + +/** @defgroup TIM_OCReferenceClear + * @{ + */ +#define TIM_OCReferenceClear_ETRF ((uint16_t)0x0008) +#define TIM_OCReferenceClear_OCREFCLR ((uint16_t)0x0000) +#define TIM_OCREFERENCECECLEAR_SOURCE(SOURCE) (((SOURCE) == TIM_OCReferenceClear_ETRF) || \ + ((SOURCE) == TIM_OCReferenceClear_OCREFCLR)) + +/** @defgroup TIM_Input_Capture_Filer_Value + * @{ + */ + +#define IS_TIM_IC_FILTER(ICFILTER) ((ICFILTER) <= 0xF) +/** + * @} + */ + +/** @defgroup TIM_External_Trigger_Filter + * @{ + */ + +#define IS_TIM_EXT_FILTER(EXTFILTER) ((EXTFILTER) <= 0xF) +/** + * @} + */ + +/** @defgroup TIM_Legacy + * @{ + */ + +#define TIM_DMABurstLength_1Byte TIM_DMABurstLength_1Transfer +#define TIM_DMABurstLength_2Bytes TIM_DMABurstLength_2Transfers +#define TIM_DMABurstLength_3Bytes TIM_DMABurstLength_3Transfers +#define TIM_DMABurstLength_4Bytes TIM_DMABurstLength_4Transfers +#define TIM_DMABurstLength_5Bytes TIM_DMABurstLength_5Transfers +#define TIM_DMABurstLength_6Bytes TIM_DMABurstLength_6Transfers +#define TIM_DMABurstLength_7Bytes TIM_DMABurstLength_7Transfers +#define TIM_DMABurstLength_8Bytes TIM_DMABurstLength_8Transfers +#define TIM_DMABurstLength_9Bytes TIM_DMABurstLength_9Transfers +#define TIM_DMABurstLength_10Bytes TIM_DMABurstLength_10Transfers +#define TIM_DMABurstLength_11Bytes TIM_DMABurstLength_11Transfers +#define TIM_DMABurstLength_12Bytes TIM_DMABurstLength_12Transfers +#define TIM_DMABurstLength_13Bytes TIM_DMABurstLength_13Transfers +#define TIM_DMABurstLength_14Bytes TIM_DMABurstLength_14Transfers +#define TIM_DMABurstLength_15Bytes TIM_DMABurstLength_15Transfers +#define TIM_DMABurstLength_16Bytes TIM_DMABurstLength_16Transfers +#define TIM_DMABurstLength_17Bytes TIM_DMABurstLength_17Transfers +#define TIM_DMABurstLength_18Bytes TIM_DMABurstLength_18Transfers +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions --------------------------------------------------------*/ + +/* TimeBase management ********************************************************/ +void TIM_DeInit(TIM_TypeDef* TIMx); +void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); +void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); +void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode); +void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode); +void TIM_SetCounter(TIM_TypeDef* TIMx, uint32_t Counter); +void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint32_t Autoreload); +uint32_t TIM_GetCounter(TIM_TypeDef* TIMx); +uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx); +void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource); +void TIM_UIFRemap(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode); +void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD); +void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState); + +/* Output Compare management **************************************************/ +void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC5Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC6Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_SelectGC5C1(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_SelectGC5C2(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_SelectGC5C3(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t TIM_OCMode); +void TIM_SetCompare1(TIM_TypeDef* TIMx, uint32_t Compare1); +void TIM_SetCompare2(TIM_TypeDef* TIMx, uint32_t Compare2); +void TIM_SetCompare3(TIM_TypeDef* TIMx, uint32_t Compare3); +void TIM_SetCompare4(TIM_TypeDef* TIMx, uint32_t Compare4); +void TIM_SetCompare5(TIM_TypeDef* TIMx, uint32_t Compare5); +void TIM_SetCompare6(TIM_TypeDef* TIMx, uint32_t Compare6); +void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC5Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC6Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC5PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC6PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC5Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC6Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_SelectOCREFClear(TIM_TypeDef* TIMx, uint16_t TIM_OCReferenceClear); +void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); +void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); +void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); +void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC5PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC6PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx); +void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN); + +/* Input Capture management ***************************************************/ +void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct); +void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct); +void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct); +uint32_t TIM_GetCapture1(TIM_TypeDef* TIMx); +uint32_t TIM_GetCapture2(TIM_TypeDef* TIMx); +uint32_t TIM_GetCapture3(TIM_TypeDef* TIMx); +uint32_t TIM_GetCapture4(TIM_TypeDef* TIMx); +void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); + +/* Advanced-control timers (TIM1 and TIM8) specific features ******************/ +void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct); +void TIM_Break1Config(TIM_TypeDef* TIMx, uint32_t TIM_Break1Polarity, uint8_t TIM_Break1Filter); +void TIM_Break2Config(TIM_TypeDef* TIMx, uint32_t TIM_Break2Polarity, uint8_t TIM_Break2Filter); +void TIM_Break1Cmd(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_Break2Cmd(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct); +void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState); + +/* Interrupts, DMA and flags management ***************************************/ +void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState); +void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource); +FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint32_t TIM_FLAG); +void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG); +ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT); +void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT); +void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength); +void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState); +void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState); + +/* Clocks management **********************************************************/ +void TIM_InternalClockConfig(TIM_TypeDef* TIMx); +void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); +void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource, + uint16_t TIM_ICPolarity, uint16_t ICFilter); +void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter); +void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, + uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter); + +/* Synchronization management *************************************************/ +void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); +void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource); +void TIM_SelectOutputTrigger2(TIM_TypeDef* TIMx, uint32_t TIM_TRGO2Source); +void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint32_t TIM_SlaveMode); +void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode); +void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter); + +/* Specific interface management **********************************************/ +void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode, + uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity); +void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState); + +/* Specific remapping management **********************************************/ +void TIM_RemapConfig(TIM_TypeDef* TIMx, uint16_t TIM_Remap); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F30x_TIM_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_usart.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_usart.h new file mode 100644 index 0000000..2d2690a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_usart.h @@ -0,0 +1,607 @@ +/** + ****************************************************************************** + * @file stm32f30x_usart.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the USART + * firmware library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_USART_H +#define __STM32F30x_USART_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup USART + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ + + + +/** + * @brief USART Init Structure definition + */ + +typedef struct +{ + uint32_t USART_BaudRate; /*!< This member configures the USART communication baud rate. + The baud rate is computed using the following formula: + - IntegerDivider = ((PCLKx) / (16 * (USART_InitStruct->USART_BaudRate))) + - FractionalDivider = ((IntegerDivider - ((uint32_t) IntegerDivider)) * 16) + 0.5 */ + + uint32_t USART_WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. + This parameter can be a value of @ref USART_Word_Length */ + + uint32_t USART_StopBits; /*!< Specifies the number of stop bits transmitted. + This parameter can be a value of @ref USART_Stop_Bits */ + + uint32_t USART_Parity; /*!< Specifies the parity mode. + This parameter can be a value of @ref USART_Parity + @note When parity is enabled, the computed parity is inserted + at the MSB position of the transmitted data (9th bit when + the word length is set to 9 data bits; 8th bit when the + word length is set to 8 data bits). */ + + uint32_t USART_Mode; /*!< Specifies wether the Receive or Transmit mode is enabled or disabled. + This parameter can be a value of @ref USART_Mode */ + + uint32_t USART_HardwareFlowControl; /*!< Specifies wether the hardware flow control mode is enabled + or disabled. + This parameter can be a value of @ref USART_Hardware_Flow_Control*/ +} USART_InitTypeDef; + +/** + * @brief USART Clock Init Structure definition + */ + +typedef struct +{ + uint32_t USART_Clock; /*!< Specifies whether the USART clock is enabled or disabled. + This parameter can be a value of @ref USART_Clock */ + + uint32_t USART_CPOL; /*!< Specifies the steady state of the serial clock. + This parameter can be a value of @ref USART_Clock_Polarity */ + + uint32_t USART_CPHA; /*!< Specifies the clock transition on which the bit capture is made. + This parameter can be a value of @ref USART_Clock_Phase */ + + uint32_t USART_LastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted + data bit (MSB) has to be output on the SCLK pin in synchronous mode. + This parameter can be a value of @ref USART_Last_Bit */ +} USART_ClockInitTypeDef; + +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup USART_Exported_Constants + * @{ + */ + +#define IS_USART_ALL_PERIPH(PERIPH) (((PERIPH) == USART1) || \ + ((PERIPH) == USART2) || \ + ((PERIPH) == USART3) || \ + ((PERIPH) == UART4) || \ + ((PERIPH) == UART5)) + +#define IS_USART_123_PERIPH(PERIPH) (((PERIPH) == USART1) || \ + ((PERIPH) == USART2) || \ + ((PERIPH) == USART3)) + +#define IS_USART_1234_PERIPH(PERIPH) (((PERIPH) == USART1) || \ + ((PERIPH) == USART2) || \ + ((PERIPH) == USART3) || \ + ((PERIPH) == UART4)) + + +/** @defgroup USART_Word_Length + * @{ + */ + +#define USART_WordLength_8b ((uint32_t)0x00000000) +#define USART_WordLength_9b USART_CR1_M +#define IS_USART_WORD_LENGTH(LENGTH) (((LENGTH) == USART_WordLength_8b) || \ + ((LENGTH) == USART_WordLength_9b)) +/** + * @} + */ + +/** @defgroup USART_Stop_Bits + * @{ + */ + +#define USART_StopBits_1 ((uint32_t)0x00000000) +#define USART_StopBits_2 USART_CR2_STOP_1 +#define USART_StopBits_1_5 (USART_CR2_STOP_0 | USART_CR2_STOP_1) +#define IS_USART_STOPBITS(STOPBITS) (((STOPBITS) == USART_StopBits_1) || \ + ((STOPBITS) == USART_StopBits_2) || \ + ((STOPBITS) == USART_StopBits_1_5)) +/** + * @} + */ + +/** @defgroup USART_Parity + * @{ + */ + +#define USART_Parity_No ((uint32_t)0x00000000) +#define USART_Parity_Even USART_CR1_PCE +#define USART_Parity_Odd (USART_CR1_PCE | USART_CR1_PS) +#define IS_USART_PARITY(PARITY) (((PARITY) == USART_Parity_No) || \ + ((PARITY) == USART_Parity_Even) || \ + ((PARITY) == USART_Parity_Odd)) +/** + * @} + */ + +/** @defgroup USART_Mode + * @{ + */ + +#define USART_Mode_Rx USART_CR1_RE +#define USART_Mode_Tx USART_CR1_TE +#define IS_USART_MODE(MODE) ((((MODE) & (uint32_t)0xFFFFFFF3) == 0x00) && \ + ((MODE) != (uint32_t)0x00)) +/** + * @} + */ + +/** @defgroup USART_Hardware_Flow_Control + * @{ + */ + +#define USART_HardwareFlowControl_None ((uint32_t)0x00000000) +#define USART_HardwareFlowControl_RTS USART_CR3_RTSE +#define USART_HardwareFlowControl_CTS USART_CR3_CTSE +#define USART_HardwareFlowControl_RTS_CTS (USART_CR3_RTSE | USART_CR3_CTSE) +#define IS_USART_HARDWARE_FLOW_CONTROL(CONTROL)\ + (((CONTROL) == USART_HardwareFlowControl_None) || \ + ((CONTROL) == USART_HardwareFlowControl_RTS) || \ + ((CONTROL) == USART_HardwareFlowControl_CTS) || \ + ((CONTROL) == USART_HardwareFlowControl_RTS_CTS)) +/** + * @} + */ + +/** @defgroup USART_Clock + * @{ + */ + +#define USART_Clock_Disable ((uint32_t)0x00000000) +#define USART_Clock_Enable USART_CR2_CLKEN +#define IS_USART_CLOCK(CLOCK) (((CLOCK) == USART_Clock_Disable) || \ + ((CLOCK) == USART_Clock_Enable)) +/** + * @} + */ + +/** @defgroup USART_Clock_Polarity + * @{ + */ + +#define USART_CPOL_Low ((uint32_t)0x00000000) +#define USART_CPOL_High USART_CR2_CPOL +#define IS_USART_CPOL(CPOL) (((CPOL) == USART_CPOL_Low) || ((CPOL) == USART_CPOL_High)) + +/** + * @} + */ + +/** @defgroup USART_Clock_Phase + * @{ + */ + +#define USART_CPHA_1Edge ((uint32_t)0x00000000) +#define USART_CPHA_2Edge USART_CR2_CPHA +#define IS_USART_CPHA(CPHA) (((CPHA) == USART_CPHA_1Edge) || ((CPHA) == USART_CPHA_2Edge)) + +/** + * @} + */ + +/** @defgroup USART_Last_Bit + * @{ + */ + +#define USART_LastBit_Disable ((uint32_t)0x00000000) +#define USART_LastBit_Enable USART_CR2_LBCL +#define IS_USART_LASTBIT(LASTBIT) (((LASTBIT) == USART_LastBit_Disable) || \ + ((LASTBIT) == USART_LastBit_Enable)) +/** + * @} + */ + +/** @defgroup USART_DMA_Requests + * @{ + */ + +#define USART_DMAReq_Tx USART_CR3_DMAT +#define USART_DMAReq_Rx USART_CR3_DMAR +#define IS_USART_DMAREQ(DMAREQ) ((((DMAREQ) & (uint32_t)0xFFFFFF3F) == 0x00) && \ + ((DMAREQ) != (uint32_t)0x00)) + +/** + * @} + */ + +/** @defgroup USART_DMA_Recception_Error + * @{ + */ + +#define USART_DMAOnError_Enable ((uint32_t)0x00000000) +#define USART_DMAOnError_Disable USART_CR3_DDRE +#define IS_USART_DMAONERROR(DMAERROR) (((DMAERROR) == USART_DMAOnError_Disable)|| \ + ((DMAERROR) == USART_DMAOnError_Enable)) +/** + * @} + */ + +/** @defgroup USART_MuteMode_WakeUp_methods + * @{ + */ + +#define USART_WakeUp_IdleLine ((uint32_t)0x00000000) +#define USART_WakeUp_AddressMark USART_CR1_WAKE +#define IS_USART_MUTEMODE_WAKEUP(WAKEUP) (((WAKEUP) == USART_WakeUp_IdleLine) || \ + ((WAKEUP) == USART_WakeUp_AddressMark)) +/** + * @} + */ + +/** @defgroup USART_Address_Detection + * @{ + */ + +#define USART_AddressLength_4b ((uint32_t)0x00000000) +#define USART_AddressLength_7b USART_CR2_ADDM7 +#define IS_USART_ADDRESS_DETECTION(ADDRESS) (((ADDRESS) == USART_AddressLength_4b) || \ + ((ADDRESS) == USART_AddressLength_7b)) +/** + * @} + */ + +/** @defgroup USART_StopMode_WakeUp_methods + * @{ + */ + +#define USART_WakeUpSource_AddressMatch ((uint32_t)0x00000000) +#define USART_WakeUpSource_StartBit USART_CR3_WUS_1 +#define USART_WakeUpSource_RXNE (uint32_t)(USART_CR3_WUS_0 | USART_CR3_WUS_1) +#define IS_USART_STOPMODE_WAKEUPSOURCE(SOURCE) (((SOURCE) == USART_WakeUpSource_AddressMatch) || \ + ((SOURCE) == USART_WakeUpSource_StartBit) || \ + ((SOURCE) == USART_WakeUpSource_RXNE)) +/** + * @} + */ + +/** @defgroup USART_LIN_Break_Detection_Length + * @{ + */ + +#define USART_LINBreakDetectLength_10b ((uint32_t)0x00000000) +#define USART_LINBreakDetectLength_11b USART_CR2_LBDL +#define IS_USART_LIN_BREAK_DETECT_LENGTH(LENGTH) \ + (((LENGTH) == USART_LINBreakDetectLength_10b) || \ + ((LENGTH) == USART_LINBreakDetectLength_11b)) +/** + * @} + */ + +/** @defgroup USART_IrDA_Low_Power + * @{ + */ + +#define USART_IrDAMode_LowPower USART_CR3_IRLP +#define USART_IrDAMode_Normal ((uint32_t)0x00000000) +#define IS_USART_IRDA_MODE(MODE) (((MODE) == USART_IrDAMode_LowPower) || \ + ((MODE) == USART_IrDAMode_Normal)) +/** + * @} + */ + +/** @defgroup USART_DE_Polarity + * @{ + */ + +#define USART_DEPolarity_High ((uint32_t)0x00000000) +#define USART_DEPolarity_Low USART_CR3_DEP +#define IS_USART_DE_POLARITY(POLARITY) (((POLARITY) == USART_DEPolarity_Low) || \ + ((POLARITY) == USART_DEPolarity_High)) +/** + * @} + */ + +/** @defgroup USART_Inversion_Pins + * @{ + */ + +#define USART_InvPin_Tx USART_CR2_TXINV +#define USART_InvPin_Rx USART_CR2_RXINV +#define IS_USART_INVERSTION_PIN(PIN) ((((PIN) & (uint32_t)0xFFFCFFFF) == 0x00) && \ + ((PIN) != (uint32_t)0x00)) + +/** + * @} + */ + +/** @defgroup USART_AutoBaudRate_Mode + * @{ + */ + +#define USART_AutoBaudRate_StartBit ((uint32_t)0x00000000) +#define USART_AutoBaudRate_FallingEdge USART_CR2_ABRMODE_0 +#define USART_AutoBaudRate_0x7FFrame USART_CR2_ABRMODE_1 +#define USART_AutoBaudRate_0x55Frame (USART_CR2_ABRMODE_0 | USART_CR2_ABRMODE_1) +#define IS_USART_AUTOBAUDRATE_MODE(MODE) (((MODE) == USART_AutoBaudRate_StartBit) || \ + ((MODE) == USART_AutoBaudRate_FallingEdge) || \ + ((MODE) == USART_AutoBaudRate_0x7FFrame) || \ + ((MODE) == USART_AutoBaudRate_0x55Frame)) +/** + * @} + */ + +/** @defgroup USART_OVR_DETECTION + * @{ + */ + +#define USART_OVRDetection_Enable ((uint32_t)0x00000000) +#define USART_OVRDetection_Disable USART_CR3_OVRDIS +#define IS_USART_OVRDETECTION(OVR) (((OVR) == USART_OVRDetection_Enable)|| \ + ((OVR) == USART_OVRDetection_Disable)) +/** + * @} + */ +/** @defgroup USART_Request + * @{ + */ + +#define USART_Request_ABRRQ USART_RQR_ABRRQ +#define USART_Request_SBKRQ USART_RQR_SBKRQ +#define USART_Request_MMRQ USART_RQR_MMRQ +#define USART_Request_RXFRQ USART_RQR_RXFRQ +#define USART_Request_TXFRQ USART_RQR_TXFRQ + +#define IS_USART_REQUEST(REQUEST) (((REQUEST) == USART_Request_TXFRQ) || \ + ((REQUEST) == USART_Request_RXFRQ) || \ + ((REQUEST) == USART_Request_MMRQ) || \ + ((REQUEST) == USART_Request_SBKRQ) || \ + ((REQUEST) == USART_Request_ABRRQ)) +/** + * @} + */ + +/** @defgroup USART_Flags + * @{ + */ +#define USART_FLAG_REACK USART_ISR_REACK +#define USART_FLAG_TEACK USART_ISR_TEACK +#define USART_FLAG_WU USART_ISR_WUF +#define USART_FLAG_RWU USART_ISR_RWU +#define USART_FLAG_SBK USART_ISR_SBKF +#define USART_FLAG_CM USART_ISR_CMF +#define USART_FLAG_BUSY USART_ISR_BUSY +#define USART_FLAG_ABRF USART_ISR_ABRF +#define USART_FLAG_ABRE USART_ISR_ABRE +#define USART_FLAG_EOB USART_ISR_EOBF +#define USART_FLAG_RTO USART_ISR_RTOF +#define USART_FLAG_nCTSS USART_ISR_CTS +#define USART_FLAG_CTS USART_ISR_CTSIF +#define USART_FLAG_LBD USART_ISR_LBD +#define USART_FLAG_TXE USART_ISR_TXE +#define USART_FLAG_TC USART_ISR_TC +#define USART_FLAG_RXNE USART_ISR_RXNE +#define USART_FLAG_IDLE USART_ISR_IDLE +#define USART_FLAG_ORE USART_ISR_ORE +#define USART_FLAG_NE USART_ISR_NE +#define USART_FLAG_FE USART_ISR_FE +#define USART_FLAG_PE USART_ISR_PE +#define IS_USART_FLAG(FLAG) (((FLAG) == USART_FLAG_PE) || ((FLAG) == USART_FLAG_TXE) || \ + ((FLAG) == USART_FLAG_TC) || ((FLAG) == USART_FLAG_RXNE) || \ + ((FLAG) == USART_FLAG_IDLE) || ((FLAG) == USART_FLAG_LBD) || \ + ((FLAG) == USART_FLAG_CTS) || ((FLAG) == USART_FLAG_ORE) || \ + ((FLAG) == USART_FLAG_NE) || ((FLAG) == USART_FLAG_FE) || \ + ((FLAG) == USART_FLAG_nCTSS) || ((FLAG) == USART_FLAG_RTO) || \ + ((FLAG) == USART_FLAG_EOB) || ((FLAG) == USART_FLAG_ABRE) || \ + ((FLAG) == USART_FLAG_ABRF) || ((FLAG) == USART_FLAG_BUSY) || \ + ((FLAG) == USART_FLAG_CM) || ((FLAG) == USART_FLAG_SBK) || \ + ((FLAG) == USART_FLAG_RWU) || ((FLAG) == USART_FLAG_WU) || \ + ((FLAG) == USART_FLAG_TEACK)|| ((FLAG) == USART_FLAG_REACK)) + +#define IS_USART_CLEAR_FLAG(FLAG) (((FLAG) == USART_FLAG_WU) || ((FLAG) == USART_FLAG_TC) || \ + ((FLAG) == USART_FLAG_IDLE) || ((FLAG) == USART_FLAG_ORE) || \ + ((FLAG) == USART_FLAG_NE) || ((FLAG) == USART_FLAG_FE) || \ + ((FLAG) == USART_FLAG_LBD) || ((FLAG) == USART_FLAG_CTS) || \ + ((FLAG) == USART_FLAG_RTO) || ((FLAG) == USART_FLAG_EOB) || \ + ((FLAG) == USART_FLAG_CM) || ((FLAG) == USART_FLAG_PE)) +/** + * @} + */ + +/** @defgroup USART_Interrupt_definition + * @brief USART Interrupt definition + * USART_IT possible values + * Elements values convention: 0xZZZZYYXX + * XX: Position of the corresponding Interrupt + * YY: Register index + * ZZZZ: Flag position + * @{ + */ + +#define USART_IT_WU ((uint32_t)0x00140316) +#define USART_IT_CM ((uint32_t)0x0011010E) +#define USART_IT_EOB ((uint32_t)0x000C011B) +#define USART_IT_RTO ((uint32_t)0x000B011A) +#define USART_IT_PE ((uint32_t)0x00000108) +#define USART_IT_TXE ((uint32_t)0x00070107) +#define USART_IT_TC ((uint32_t)0x00060106) +#define USART_IT_RXNE ((uint32_t)0x00050105) +#define USART_IT_IDLE ((uint32_t)0x00040104) +#define USART_IT_LBD ((uint32_t)0x00080206) +#define USART_IT_CTS ((uint32_t)0x0009030A) +#define USART_IT_ERR ((uint32_t)0x00000300) +#define USART_IT_ORE ((uint32_t)0x00030300) +#define USART_IT_NE ((uint32_t)0x00020300) +#define USART_IT_FE ((uint32_t)0x00010300) + +#define IS_USART_CONFIG_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \ + ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ + ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \ + ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ERR) || \ + ((IT) == USART_IT_RTO) || ((IT) == USART_IT_EOB) || \ + ((IT) == USART_IT_CM) || ((IT) == USART_IT_WU)) + +#define IS_USART_GET_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \ + ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ + ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \ + ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ORE) || \ + ((IT) == USART_IT_NE) || ((IT) == USART_IT_FE) || \ + ((IT) == USART_IT_RTO) || ((IT) == USART_IT_EOB) || \ + ((IT) == USART_IT_CM) || ((IT) == USART_IT_WU)) + +#define IS_USART_CLEAR_IT(IT) (((IT) == USART_IT_TC) || ((IT) == USART_IT_PE) || \ + ((IT) == USART_IT_FE) || ((IT) == USART_IT_NE) || \ + ((IT) == USART_IT_ORE) || ((IT) == USART_IT_IDLE) || \ + ((IT) == USART_IT_LBD) || ((IT) == USART_IT_CTS) || \ + ((IT) == USART_IT_RTO) || ((IT) == USART_IT_EOB) || \ + ((IT) == USART_IT_CM) || ((IT) == USART_IT_WU)) +/** + * @} + */ + +/** @defgroup USART_Global_definition + * @{ + */ + +#define IS_USART_BAUDRATE(BAUDRATE) (((BAUDRATE) > 0) && ((BAUDRATE) < 0x005B8D81)) +#define IS_USART_DE_ASSERTION_DEASSERTION_TIME(TIME) ((TIME) <= 0x1F) +#define IS_USART_AUTO_RETRY_COUNTER(COUNTER) ((COUNTER) <= 0x7) +#define IS_USART_TIMEOUT(TIMEOUT) ((TIMEOUT) <= 0x00FFFFFF) +#define IS_USART_DATA(DATA) ((DATA) <= 0x1FF) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +/* Initialization and Configuration functions *********************************/ +void USART_DeInit(USART_TypeDef* USARTx); +void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct); +void USART_StructInit(USART_InitTypeDef* USART_InitStruct); +void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct); +void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct); +void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_DirectionModeCmd(USART_TypeDef* USARTx, uint32_t USART_DirectionMode, FunctionalState NewState); +void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler); +void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_MSBFirstCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_DataInvCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_InvPinCmd(USART_TypeDef* USARTx, uint32_t USART_InvPin, FunctionalState NewState); +void USART_SWAPPinCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_ReceiverTimeOutCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_SetReceiverTimeOut(USART_TypeDef* USARTx, uint32_t USART_ReceiverTimeOut); + +/* STOP Mode functions ********************************************************/ +void USART_STOPModeCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_StopModeWakeUpSourceConfig(USART_TypeDef* USARTx, uint32_t USART_WakeUpSource); + +/* AutoBaudRate functions *****************************************************/ +void USART_AutoBaudRateCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_AutoBaudRateConfig(USART_TypeDef* USARTx, uint32_t USART_AutoBaudRate); + +/* Data transfers functions ***************************************************/ +void USART_SendData(USART_TypeDef* USARTx, uint16_t Data); +uint16_t USART_ReceiveData(USART_TypeDef* USARTx); + +/* Multi-Processor Communication functions ************************************/ +void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address); +void USART_MuteModeWakeUpConfig(USART_TypeDef* USARTx, uint32_t USART_WakeUp); +void USART_MuteModeCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_AddressDetectionConfig(USART_TypeDef* USARTx, uint32_t USART_AddressLength); +/* LIN mode functions *********************************************************/ +void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint32_t USART_LINBreakDetectLength); +void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState); + +/* Half-duplex mode function **************************************************/ +void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState); + +/* Smartcard mode functions ***************************************************/ +void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime); +void USART_SetAutoRetryCount(USART_TypeDef* USARTx, uint8_t USART_AutoCount); +void USART_SetBlockLength(USART_TypeDef* USARTx, uint8_t USART_BlockLength); + +/* IrDA mode functions ********************************************************/ +void USART_IrDAConfig(USART_TypeDef* USARTx, uint32_t USART_IrDAMode); +void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState); + +/* RS485 mode functions *******************************************************/ +void USART_DECmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_DEPolarityConfig(USART_TypeDef* USARTx, uint32_t USART_DEPolarity); +void USART_SetDEAssertionTime(USART_TypeDef* USARTx, uint32_t USART_DEAssertionTime); +void USART_SetDEDeassertionTime(USART_TypeDef* USARTx, uint32_t USART_DEDeassertionTime); + +/* DMA transfers management functions *****************************************/ +void USART_DMACmd(USART_TypeDef* USARTx, uint32_t USART_DMAReq, FunctionalState NewState); +void USART_DMAReceptionErrorConfig(USART_TypeDef* USARTx, uint32_t USART_DMAOnError); + +/* Interrupts and flags management functions **********************************/ +void USART_ITConfig(USART_TypeDef* USARTx, uint32_t USART_IT, FunctionalState NewState); +void USART_RequestCmd(USART_TypeDef* USARTx, uint32_t USART_Request, FunctionalState NewState); +void USART_OverrunDetectionConfig(USART_TypeDef* USARTx, uint32_t USART_OVRDetection); +FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint32_t USART_FLAG); +void USART_ClearFlag(USART_TypeDef* USARTx, uint32_t USART_FLAG); +ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint32_t USART_IT); +void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint32_t USART_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F30x_USART_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_wwdg.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_wwdg.h new file mode 100644 index 0000000..4c694bf --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/inc/stm32f30x_wwdg.h @@ -0,0 +1,109 @@ +/** + ****************************************************************************** + * @file stm32f30x_wwdg.h + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file contains all the functions prototypes for the WWDG + * firmware library. + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F30x_WWDG_H +#define __STM32F30x_WWDG_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup WWDG + * @{ + */ +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/** @defgroup WWDG_Exported_Constants + * @{ + */ + +/** @defgroup WWDG_Prescaler + * @{ + */ + +#define WWDG_Prescaler_1 ((uint32_t)0x00000000) +#define WWDG_Prescaler_2 ((uint32_t)0x00000080) +#define WWDG_Prescaler_4 ((uint32_t)0x00000100) +#define WWDG_Prescaler_8 ((uint32_t)0x00000180) +#define IS_WWDG_PRESCALER(PRESCALER) (((PRESCALER) == WWDG_Prescaler_1) || \ + ((PRESCALER) == WWDG_Prescaler_2) || \ + ((PRESCALER) == WWDG_Prescaler_4) || \ + ((PRESCALER) == WWDG_Prescaler_8)) +#define IS_WWDG_WINDOW_VALUE(VALUE) ((VALUE) <= 0x7F) +#define IS_WWDG_COUNTER(COUNTER) (((COUNTER) >= 0x40) && ((COUNTER) <= 0x7F)) + +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +/* Function used to set the WWDG configuration to the default reset state ****/ +void WWDG_DeInit(void); + +/* Prescaler, Refresh window and Counter configuration functions **************/ +void WWDG_SetPrescaler(uint32_t WWDG_Prescaler); +void WWDG_SetWindowValue(uint8_t WindowValue); +void WWDG_EnableIT(void); +void WWDG_SetCounter(uint8_t Counter); + +/* WWDG activation functions **************************************************/ +void WWDG_Enable(uint8_t Counter); + +/* Interrupts and flags management functions **********************************/ +FlagStatus WWDG_GetFlagStatus(void); +void WWDG_ClearFlag(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F30x_WWDG_H */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_adc.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_adc.c new file mode 100644 index 0000000..d262e8e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_adc.c @@ -0,0 +1,2414 @@ +/** + ****************************************************************************** + * @file stm32f30x_adc.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the Analog to Digital Convertor (ADC) peripheral: + * + Initialization and Configuration + * + Analog Watchdog configuration + * + Temperature Sensor, Vbat & Vrefint (Internal Reference Voltage) management + * + Regular Channels Configuration + * + Regular Channels DMA Configuration + * + Injected channels Configuration + * + Interrupts and flags management + * + Dual mode configuration + * + @verbatim + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] + (#) select the ADC clock using the function RCC_ADCCLKConfig() + (#) Enable the ADC interface clock using RCC_AHBPeriphClockCmd(); + (#) ADC pins configuration + (++) Enable the clock for the ADC GPIOs using the following function: + RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOx, ENABLE); + (++) Configure these ADC pins in analog mode using GPIO_Init(); + (#) Configure the ADC conversion resolution, data alignment, external + trigger and edge, sequencer lenght and Enable/Disable the continuous mode + using the ADC_Init() function. + (#) Activate the ADC peripheral using ADC_Cmd() function. + + *** ADC channels group configuration *** + ======================================== + [..] + (+) To configure the ADC channels features, use ADC_Init(), ADC_InjectedInit() + and/or ADC_RegularChannelConfig() functions. + (+) To activate the continuous mode, use the ADC_ContinuousModeCmd() + function. + (+) To activate the Discontinuous mode, use the ADC_DiscModeCmd() functions. + (+) To activate the overrun mode, use the ADC_OverrunModeCmd() functions. + (+) To activate the calibration mode, use the ADC_StartCalibration() functions. + (+) To read the ADC converted values, use the ADC_GetConversionValue() + function. + + *** DMA for ADC channels features configuration *** + =================================================== + [..] + (+) To enable the DMA mode for ADC channels group, use the ADC_DMACmd() function. + (+) To configure the DMA transfer request, use ADC_DMAConfig() function. + + @endverbatim + * + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_adc.h" +#include "stm32f30x_rcc.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup ADC + * @brief ADC driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* CFGR register Mask */ +#define CFGR_CLEAR_Mask ((uint32_t)0xFDFFC007) + +/* JSQR register Mask */ +#define JSQR_CLEAR_Mask ((uint32_t)0x00000000) + +/* ADC ADON mask */ +#define CCR_CLEAR_MASK ((uint32_t)0xFFFC10E0) + +/* ADC JDRx registers offset */ +#define JDR_Offset ((uint8_t)0x80) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup ADC_Private_Functions + * @{ + */ + +/** @defgroup ADC_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] + This section provides functions allowing to: + (#) Initialize and configure the ADC injected and/or regular channels and dual mode. + (#) Management of the calibration process + (#) ADC Power-on Power-off + (#) Single ended or differential mode + (#) Enabling the queue of context and the auto delay mode + (#) The number of ADC conversions that will be done using the sequencer for regular + channel group + (#) Enable or disable the ADC peripheral + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the ADCx peripheral registers to their default reset values. + * @param ADCx: where x can be 1, 2,3 or 4 to select the ADC peripheral. + * @retval None + */ +void ADC_DeInit(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + + if((ADCx == ADC1) || (ADCx == ADC2)) + { + /* Enable ADC1/ADC2 reset state */ + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_ADC12, ENABLE); + /* Release ADC1/ADC2 from reset state */ + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_ADC12, DISABLE); + } + else if((ADCx == ADC3) || (ADCx == ADC4)) + { + /* Enable ADC3/ADC4 reset state */ + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_ADC34, ENABLE); + /* Release ADC3/ADC4 from reset state */ + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_ADC34, DISABLE); + } +} +/** + * @brief Initializes the ADCx peripheral according to the specified parameters + * in the ADC_InitStruct. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_InitStruct: pointer to an ADC_InitTypeDef structure that contains + * the configuration information for the specified ADC peripheral. + * @retval None + */ +void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct) +{ + uint32_t tmpreg1 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CONVMODE(ADC_InitStruct->ADC_ContinuousConvMode)); + assert_param(IS_ADC_RESOLUTION(ADC_InitStruct->ADC_Resolution)); + assert_param(IS_ADC_EXT_TRIG(ADC_InitStruct->ADC_ExternalTrigConvEvent)); + assert_param(IS_EXTERNALTRIG_EDGE(ADC_InitStruct->ADC_ExternalTrigEventEdge)); + assert_param(IS_ADC_DATA_ALIGN(ADC_InitStruct->ADC_DataAlign)); + assert_param(IS_ADC_OVRUNMODE(ADC_InitStruct->ADC_OverrunMode)); + assert_param(IS_ADC_AUTOINJECMODE(ADC_InitStruct->ADC_AutoInjMode)); + assert_param(IS_ADC_REGULAR_LENGTH(ADC_InitStruct->ADC_NbrOfRegChannel)); + + /*---------------------------- ADCx CFGR Configuration -----------------*/ + /* Get the ADCx CFGR value */ + tmpreg1 = ADCx->CFGR; + /* Clear SCAN bit */ + tmpreg1 &= CFGR_CLEAR_Mask; + /* Configure ADCx: scan conversion mode */ + /* Set SCAN bit according to ADC_ScanConvMode value */ + tmpreg1 |= (uint32_t)ADC_InitStruct->ADC_ContinuousConvMode | + ADC_InitStruct->ADC_Resolution| + ADC_InitStruct->ADC_ExternalTrigConvEvent| + ADC_InitStruct->ADC_ExternalTrigEventEdge| + ADC_InitStruct->ADC_DataAlign| + ADC_InitStruct->ADC_OverrunMode| + ADC_InitStruct->ADC_AutoInjMode; + + /* Write to ADCx CFGR */ + ADCx->CFGR = tmpreg1; + + /*---------------------------- ADCx SQR1 Configuration -----------------*/ + /* Get the ADCx SQR1 value */ + tmpreg1 = ADCx->SQR1; + /* Clear L bits */ + tmpreg1 &= ~(uint32_t)(ADC_SQR1_L); + /* Configure ADCx: regular channel sequence length */ + /* Set L bits according to ADC_NbrOfRegChannel value */ + tmpreg1 |= (uint32_t) (ADC_InitStruct->ADC_NbrOfRegChannel - 1); + /* Write to ADCx SQR1 */ + ADCx->SQR1 = tmpreg1; + +} + +/** + * @brief Fills each ADC_InitStruct member with its default value. + * @param ADC_InitStruct : pointer to an ADC_InitTypeDef structure which will be initialized. + * @retval None + */ +void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct) +{ + /* Reset ADC init structure parameters values */ + ADC_InitStruct->ADC_ContinuousConvMode = DISABLE; + ADC_InitStruct->ADC_Resolution = ADC_Resolution_12b; + ADC_InitStruct->ADC_ExternalTrigConvEvent = ADC_ExternalTrigConvEvent_0; + ADC_InitStruct->ADC_ExternalTrigEventEdge = ADC_ExternalTrigEventEdge_None; + ADC_InitStruct->ADC_DataAlign = ADC_DataAlign_Right; + ADC_InitStruct->ADC_OverrunMode = DISABLE; + ADC_InitStruct->ADC_AutoInjMode = DISABLE; + ADC_InitStruct->ADC_NbrOfRegChannel = 1; +} + +/** + * @brief Initializes the ADCx peripheral according to the specified parameters + * in the ADC_InitStruct. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_InjectInitStruct: pointer to an ADC_InjecInitTypeDef structure that contains + * the configuration information for the specified ADC injected channel. + * @retval None + */ +void ADC_InjectedInit(ADC_TypeDef* ADCx, ADC_InjectedInitTypeDef* ADC_InjectedInitStruct) +{ + uint32_t tmpreg1 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_EXT_INJEC_TRIG(ADC_InjectedInitStruct->ADC_ExternalTrigInjecConvEvent)); + assert_param(IS_EXTERNALTRIGINJ_EDGE(ADC_InjectedInitStruct->ADC_ExternalTrigInjecEventEdge)); + assert_param(IS_ADC_INJECTED_LENGTH(ADC_InjectedInitStruct->ADC_NbrOfInjecChannel)); + assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedInitStruct->ADC_InjecSequence1)); + assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedInitStruct->ADC_InjecSequence2)); + assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedInitStruct->ADC_InjecSequence3)); + assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedInitStruct->ADC_InjecSequence4)); + + /*---------------------------- ADCx JSQR Configuration -----------------*/ + /* Get the ADCx JSQR value */ + tmpreg1 = ADCx->JSQR; + /* Clear L bits */ + tmpreg1 &= JSQR_CLEAR_Mask; + /* Configure ADCx: Injected channel sequence length, external trigger, + external trigger edge and sequences + */ + tmpreg1 = (uint32_t) ((ADC_InjectedInitStruct->ADC_NbrOfInjecChannel - (uint8_t)1) | + ADC_InjectedInitStruct->ADC_ExternalTrigInjecConvEvent | + ADC_InjectedInitStruct->ADC_ExternalTrigInjecEventEdge | + (uint32_t)((ADC_InjectedInitStruct->ADC_InjecSequence1) << 8) | + (uint32_t)((ADC_InjectedInitStruct->ADC_InjecSequence2) << 14) | + (uint32_t)((ADC_InjectedInitStruct->ADC_InjecSequence3) << 20) | + (uint32_t)((ADC_InjectedInitStruct->ADC_InjecSequence4) << 26)); + /* Write to ADCx SQR1 */ + ADCx->JSQR = tmpreg1; +} + +/** + * @brief Fills each ADC_InjectedInitStruct member with its default value. + * @param ADC_InjectedInitStruct : pointer to an ADC_InjectedInitTypeDef structure which will be initialized. + * @retval None + */ +void ADC_InjectedStructInit(ADC_InjectedInitTypeDef* ADC_InjectedInitStruct) +{ + ADC_InjectedInitStruct->ADC_ExternalTrigInjecConvEvent = ADC_ExternalTrigInjecConvEvent_0; + ADC_InjectedInitStruct->ADC_ExternalTrigInjecEventEdge = ADC_ExternalTrigInjecEventEdge_None; + ADC_InjectedInitStruct->ADC_NbrOfInjecChannel = 1; + ADC_InjectedInitStruct->ADC_InjecSequence1 = ADC_InjectedChannel_1; + ADC_InjectedInitStruct->ADC_InjecSequence2 = ADC_InjectedChannel_1; + ADC_InjectedInitStruct->ADC_InjecSequence3 = ADC_InjectedChannel_1; + ADC_InjectedInitStruct->ADC_InjecSequence4 = ADC_InjectedChannel_1; +} + +/** + * @brief Initializes the ADCs peripherals according to the specified parameters + * in the ADC_CommonInitStruct. + * @param ADCx: where x can be 1 or 4 to select the ADC peripheral. + * @param ADC_CommonInitStruct: pointer to an ADC_CommonInitTypeDef structure + * that contains the configuration information for All ADCs peripherals. + * @retval None + */ +void ADC_CommonInit(ADC_TypeDef* ADCx, ADC_CommonInitTypeDef* ADC_CommonInitStruct) +{ + uint32_t tmpreg1 = 0; + /* Check the parameters */ + assert_param(IS_ADC_MODE(ADC_CommonInitStruct->ADC_Mode)); + assert_param(IS_ADC_CLOCKMODE(ADC_CommonInitStruct->ADC_Clock)); + assert_param(IS_ADC_DMA_MODE(ADC_CommonInitStruct->ADC_DMAMode)); + assert_param(IS_ADC_DMA_ACCESS_MODE(ADC_CommonInitStruct->ADC_DMAAccessMode)); + assert_param(IS_ADC_TWOSAMPLING_DELAY(ADC_CommonInitStruct->ADC_TwoSamplingDelay)); + + if((ADCx == ADC1) || (ADCx == ADC2)) + { + /* Get the ADC CCR value */ + tmpreg1 = ADC1_2->CCR; + + /* Clear MULTI, DELAY, DMA and ADCPRE bits */ + tmpreg1 &= CCR_CLEAR_MASK; + } + else + { + /* Get the ADC CCR value */ + tmpreg1 = ADC3_4->CCR; + + /* Clear MULTI, DELAY, DMA and ADCPRE bits */ + tmpreg1 &= CCR_CLEAR_MASK; + } + /*---------------------------- ADC CCR Configuration -----------------*/ + /* Configure ADCx: Multi mode, Delay between two sampling time, ADC clock, DMA mode + and DMA access mode for dual mode */ + /* Set MULTI bits according to ADC_Mode value */ + /* Set CKMODE bits according to ADC_Clock value */ + /* Set MDMA bits according to ADC_DMAAccessMode value */ + /* Set DMACFG bits according to ADC_DMAMode value */ + /* Set DELAY bits according to ADC_TwoSamplingDelay value */ + tmpreg1 |= (uint32_t)(ADC_CommonInitStruct->ADC_Mode | + ADC_CommonInitStruct->ADC_Clock | + ADC_CommonInitStruct->ADC_DMAAccessMode | + (uint32_t)(ADC_CommonInitStruct->ADC_DMAMode << 12) | + (uint32_t)((uint32_t)ADC_CommonInitStruct->ADC_TwoSamplingDelay << 8)); + + if((ADCx == ADC1) || (ADCx == ADC2)) + { + /* Write to ADC CCR */ + ADC1_2->CCR = tmpreg1; + } + else + { + /* Write to ADC CCR */ + ADC3_4->CCR = tmpreg1; + } +} + +/** + * @brief Fills each ADC_CommonInitStruct member with its default value. + * @param ADC_CommonInitStruct: pointer to an ADC_CommonInitTypeDef structure + * which will be initialized. + * @retval None + */ +void ADC_CommonStructInit(ADC_CommonInitTypeDef* ADC_CommonInitStruct) +{ + /* Initialize the ADC_Mode member */ + ADC_CommonInitStruct->ADC_Mode = ADC_Mode_Independent; + + /* initialize the ADC_Clock member */ + ADC_CommonInitStruct->ADC_Clock = ADC_Clock_AsynClkMode; + + /* Initialize the ADC_DMAAccessMode member */ + ADC_CommonInitStruct->ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled; + + /* Initialize the ADC_DMAMode member */ + ADC_CommonInitStruct->ADC_DMAMode = ADC_DMAMode_OneShot; + + /* Initialize the ADC_TwoSamplingDelay member */ + ADC_CommonInitStruct->ADC_TwoSamplingDelay = 0; + +} + +/** + * @brief Enables or disables the specified ADC peripheral. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param NewState: new state of the ADCx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the ADEN bit */ + ADCx->CR |= ADC_CR_ADEN; + } + else + { + /* Disable the selected ADC peripheral: Set the ADDIS bit */ + ADCx->CR |= ADC_CR_ADDIS; + } +} + +/** + * @brief Starts the selected ADC calibration process. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @retval None + */ +void ADC_StartCalibration(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Set the ADCAL bit */ + ADCx->CR |= ADC_CR_ADCAL; +} + +/** + * @brief Returns the ADCx calibration value. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @retval None + */ +uint32_t ADC_GetCalibrationValue(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Return the selected ADC calibration value */ + return (uint32_t)ADCx->CALFACT; +} + +/** + * @brief Sets the ADCx calibration register. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @retval None + */ +void ADC_SetCalibrationValue(ADC_TypeDef* ADCx, uint32_t ADC_Calibration) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Set the ADC calibration register value */ + ADCx->CALFACT = ADC_Calibration; +} + +/** + * @brief Select the ADC calibration mode. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_CalibrationMode: the ADC calibration mode. + * This parameter can be one of the following values: + * @arg ADC_CalibrationMode_Single: to select the calibration for single channel + * @arg ADC_CalibrationMode_Differential: to select the calibration for differential channel + * @retval None + */ +void ADC_SelectCalibrationMode(ADC_TypeDef* ADCx, uint32_t ADC_CalibrationMode) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CALIBRATION_MODE(ADC_CalibrationMode)); + /* Set or Reset the ADCALDIF bit */ + ADCx->CR &= (~ADC_CR_ADCALDIF); + ADCx->CR |= ADC_CalibrationMode; + +} + +/** + * @brief Gets the selected ADC calibration status. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @retval The new state of ADC calibration (SET or RESET). + */ +FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Check the status of CAL bit */ + if ((ADCx->CR & ADC_CR_ADCAL) != (uint32_t)RESET) + { + /* CAL bit is set: calibration on going */ + bitstatus = SET; + } + else + { + /* CAL bit is reset: end of calibration */ + bitstatus = RESET; + } + /* Return the CAL bit status */ + return bitstatus; +} + +/** + * @brief ADC Disable Command. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @retval None + */ +void ADC_DisableCmd(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Set the ADDIS bit */ + ADCx->CR |= ADC_CR_ADDIS; +} + + +/** + * @brief Gets the selected ADC disable command Status. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @retval The new state of ADC ADC disable command (SET or RESET). + */ +FlagStatus ADC_GetDisableCmdStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Check the status of ADDIS bit */ + if ((ADCx->CR & ADC_CR_ADDIS) != (uint32_t)RESET) + { + /* ADDIS bit is set */ + bitstatus = SET; + } + else + { + /* ADDIS bit is reset */ + bitstatus = RESET; + } + /* Return the ADDIS bit status */ + return bitstatus; +} + +/** + * @brief Enables or disables the specified ADC Voltage Regulator. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param NewState: new state of the ADCx Voltage Regulator. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_VoltageRegulatorCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* set the intermediate state before moving the ADC voltage regulator + from enable state to disable state or from disable state to enable state */ + ADCx->CR &= ~(ADC_CR_ADVREGEN); + + if (NewState != DISABLE) + { + /* Set the ADVREGEN bit 0 */ + ADCx->CR |= ADC_CR_ADVREGEN_0; + } + else + { + /* Set the ADVREGEN bit 1 */ + ADCx->CR |=ADC_CR_ADVREGEN_1; + } +} + +/** + * @brief Selectes the differential mode for a specific channel + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure for the analog watchdog. + * This parameter can be one of the following values: + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @note : Channel 15, 16 and 17 are fixed to single-ended inputs mode. + * @retval None + */ +void ADC_SelectDifferentialMode(ADC_TypeDef* ADCx, uint8_t ADC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_DIFFCHANNEL(ADC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the DIFSEL bit */ + ADCx->DIFSEL |= (uint32_t)(1 << ADC_Channel ); + } + else + { + /* Reset the DIFSEL bit */ + ADCx->DIFSEL &= ~(uint32_t)(1 << ADC_Channel); + } +} + +/** + * @brief Selects the Queue Of Context Mode for injected channels. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param NewState: new state of the Queue Of Context Mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_SelectQueueOfContextMode(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the JQM bit */ + ADCx->CFGR |= (uint32_t)(ADC_CFGR_JQM ); + } + else + { + /* Reset the JQM bit */ + ADCx->CFGR &= ~(uint32_t)(ADC_CFGR_JQM); + } +} + +/** + * @brief Selects the ADC Delayed Conversion Mode. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param NewState: new state of the ADC Delayed Conversion Mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_AutoDelayCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the AUTDLY bit */ + ADCx->CFGR |= (uint32_t)(ADC_CFGR_AUTDLY ); + } + else + { + /* Reset the AUTDLY bit */ + ADCx->CFGR &= ~(uint32_t)(ADC_CFGR_AUTDLY); + } +} + +/** + * @} + */ + +/** @defgroup ADC_Group2 Analog Watchdog configuration functions + * @brief Analog Watchdog configuration functions + * +@verbatim + =============================================================================== + ##### Analog Watchdog configuration functions ##### + =============================================================================== + + [..] This section provides functions allowing to configure the 3 Analog Watchdogs + (AWDG1, AWDG2 and AWDG3) in the ADC. + + [..] A typical configuration Analog Watchdog is done following these steps : + (#) The ADC guarded channel(s) is (are) selected using the functions: + (++) ADC_AnalogWatchdog1SingleChannelConfig(). + (++) ADC_AnalogWatchdog2SingleChannelConfig(). + (++) ADC_AnalogWatchdog3SingleChannelConfig(). + + (#) The Analog watchdog lower and higher threshold are configured using the functions: + (++) ADC_AnalogWatchdog1ThresholdsConfig(). + (++) ADC_AnalogWatchdog2ThresholdsConfig(). + (++) ADC_AnalogWatchdog3ThresholdsConfig(). + + (#) The Analog watchdog is enabled and configured to enable the check, on one + or more channels, using the function: + (++) ADC_AnalogWatchdogCmd(). + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the analog watchdog on single/all regular + * or injected channels + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_AnalogWatchdog: the ADC analog watchdog configuration. + * This parameter can be one of the following values: + * @arg ADC_AnalogWatchdog_SingleRegEnable: Analog watchdog on a single regular channel + * @arg ADC_AnalogWatchdog_SingleInjecEnable: Analog watchdog on a single injected channel + * @arg ADC_AnalogWatchdog_SingleRegOrInjecEnable: Analog watchdog on a single regular or injected channel + * @arg ADC_AnalogWatchdog_AllRegEnable: Analog watchdog on all regular channel + * @arg ADC_AnalogWatchdog_AllInjecEnable: Analog watchdog on all injected channel + * @arg ADC_AnalogWatchdog_AllRegAllInjecEnable: Analog watchdog on all regular and injected channels + * @arg ADC_AnalogWatchdog_None: No channel guarded by the analog watchdog + * @retval None + */ +void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_ANALOG_WATCHDOG(ADC_AnalogWatchdog)); + /* Get the old register value */ + tmpreg = ADCx->CFGR; + /* Clear AWDEN, AWDENJ and AWDSGL bits */ + tmpreg &= ~(uint32_t)(ADC_CFGR_AWD1SGL|ADC_CFGR_AWD1EN|ADC_CFGR_JAWD1EN); + /* Set the analog watchdog enable mode */ + tmpreg |= ADC_AnalogWatchdog; + /* Store the new register value */ + ADCx->CFGR = tmpreg; +} + +/** + * @brief Configures the high and low thresholds of the analog watchdog1. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param HighThreshold: the ADC analog watchdog High threshold value. + * This parameter must be a 12bit value. + * @param LowThreshold: the ADC analog watchdog Low threshold value. + * This parameter must be a 12bit value. + * @retval None + */ +void ADC_AnalogWatchdog1ThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold, + uint16_t LowThreshold) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_THRESHOLD(HighThreshold)); + assert_param(IS_ADC_THRESHOLD(LowThreshold)); + /* Set the ADCx high threshold */ + ADCx->TR1 &= ~(uint32_t)ADC_TR1_HT1; + ADCx->TR1 |= (uint32_t)((uint32_t)HighThreshold << 16); + + /* Set the ADCx low threshold */ + ADCx->TR1 &= ~(uint32_t)ADC_TR1_LT1; + ADCx->TR1 |= LowThreshold; +} + +/** + * @brief Configures the high and low thresholds of the analog watchdog2. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param HighThreshold: the ADC analog watchdog High threshold value. + * This parameter must be a 8bit value. + * @param LowThreshold: the ADC analog watchdog Low threshold value. + * This parameter must be a 8bit value. + * @retval None + */ +void ADC_AnalogWatchdog2ThresholdsConfig(ADC_TypeDef* ADCx, uint8_t HighThreshold, + uint8_t LowThreshold) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Set the ADCx high threshold */ + ADCx->TR2 &= ~(uint32_t)ADC_TR2_HT2; + ADCx->TR2 |= (uint32_t)((uint32_t)HighThreshold << 16); + + /* Set the ADCx low threshold */ + ADCx->TR2 &= ~(uint32_t)ADC_TR2_LT2; + ADCx->TR2 |= LowThreshold; +} + +/** + * @brief Configures the high and low thresholds of the analog watchdog3. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param HighThreshold: the ADC analog watchdog High threshold value. + * This parameter must be a 8bit value. + * @param LowThreshold: the ADC analog watchdog Low threshold value. + * This parameter must be a 8bit value. + * @retval None + */ +void ADC_AnalogWatchdog3ThresholdsConfig(ADC_TypeDef* ADCx, uint8_t HighThreshold, + uint8_t LowThreshold) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Set the ADCx high threshold */ + ADCx->TR3 &= ~(uint32_t)ADC_TR3_HT3; + ADCx->TR3 |= (uint32_t)((uint32_t)HighThreshold << 16); + + /* Set the ADCx low threshold */ + ADCx->TR3 &= ~(uint32_t)ADC_TR3_LT3; + ADCx->TR3 |= LowThreshold; +} + +/** + * @brief Configures the analog watchdog 2 guarded single channel + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure for the analog watchdog. + * This parameter can be one of the following values: + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @arg ADC_Channel_18: ADC Channel18 selected + * @retval None + */ +void ADC_AnalogWatchdog1SingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + /* Get the old register value */ + tmpreg = ADCx->CFGR; + /* Clear the Analog watchdog channel select bits */ + tmpreg &= ~(uint32_t)ADC_CFGR_AWD1CH; + /* Set the Analog watchdog channel */ + tmpreg |= (uint32_t)((uint32_t)ADC_Channel << 26); + /* Store the new register value */ + ADCx->CFGR = tmpreg; +} + +/** + * @brief Configures the analog watchdog 2 guarded single channel + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure for the analog watchdog. + * This parameter can be one of the following values: + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @arg ADC_Channel_18: ADC Channel18 selected + * @retval None + */ +void ADC_AnalogWatchdog2SingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + /* Get the old register value */ + tmpreg = ADCx->AWD2CR; + /* Clear the Analog watchdog channel select bits */ + tmpreg &= ~(uint32_t)ADC_AWD2CR_AWD2CH; + /* Set the Analog watchdog channel */ + tmpreg |= (uint32_t)1 << (ADC_Channel); + /* Store the new register value */ + ADCx->AWD2CR |= tmpreg; +} + +/** + * @brief Configures the analog watchdog 3 guarded single channel + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure for the analog watchdog. + * This parameter can be one of the following values: + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @arg ADC_Channel_18: ADC Channel18 selected + * @retval None + */ +void ADC_AnalogWatchdog3SingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + /* Get the old register value */ + tmpreg = ADCx->AWD3CR; + /* Clear the Analog watchdog channel select bits */ + tmpreg &= ~(uint32_t)ADC_AWD3CR_AWD3CH; + /* Set the Analog watchdog channel */ + tmpreg |= (uint32_t)1 << (ADC_Channel); + /* Store the new register value */ + ADCx->AWD3CR |= tmpreg; +} + +/** + * @} + */ + +/** @defgroup ADC_Group3 Temperature Sensor - Vrefint (Internal Reference Voltage) and VBAT management functions + * @brief Vbat, Temperature Sensor & Vrefint (Internal Reference Voltage) management function + * +@verbatim + ==================================================================================================== + ##### Temperature Sensor - Vrefint (Internal Reference Voltage) and VBAT management functions ##### + ==================================================================================================== + + [..] This section provides a function allowing to enable/ disable the internal + connections between the ADC and the Vbat/2, Temperature Sensor and the Vrefint source. + + [..] A typical configuration to get the Temperature sensor and Vrefint channels + voltages is done following these steps : + (#) Enable the internal connection of Vbat/2, Temperature sensor and Vrefint sources + with the ADC channels using: + (++) ADC_TempSensorCmd() + (++) ADC_VrefintCmd() + (++) ADC_VbatCmd() + + (#) select the ADC_Channel_TempSensor and/or ADC_Channel_Vrefint and/or ADC_Channel_Vbat using + (++) ADC_RegularChannelConfig() or + (++) ADC_InjectedInit() functions + + (#) Get the voltage values, using: + (++) ADC_GetConversionValue() or + (++) ADC_GetInjectedConversionValue(). + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the temperature sensor channel. + * @param ADCx: where x can be 1 to select the ADC peripheral. + * @param NewState: new state of the temperature sensor. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +#ifdef __GNUC__ +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wunused-parameter" +#endif +void ADC_TempSensorCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the temperature sensor channel*/ + ADC1_2->CCR |= ADC12_CCR_TSEN; + } + else + { + /* Disable the temperature sensor channel*/ + ADC1_2->CCR &= ~(uint32_t)ADC12_CCR_TSEN; + } +} +#ifdef __GNUC__ +# pragma GCC diagnostic pop +#endif + +/** + * @brief Enables or disables the Vrefint channel. + * @param ADCx: where x can be 1 or 4 to select the ADC peripheral. + * @param NewState: new state of the Vrefint. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_VrefintCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if((ADCx == ADC1) || (ADCx == ADC2)) + { + if (NewState != DISABLE) + { + /* Enable the Vrefint channel*/ + ADC1_2->CCR |= ADC12_CCR_VREFEN; + } + else + { + /* Disable the Vrefint channel*/ + ADC1_2->CCR &= ~(uint32_t)ADC12_CCR_VREFEN; + } + } + else + { + if (NewState != DISABLE) + { + /* Enable the Vrefint channel*/ + ADC3_4->CCR |= ADC34_CCR_VREFEN; + } + else + { + /* Disable the Vrefint channel*/ + ADC3_4->CCR &= ~(uint32_t)ADC34_CCR_VREFEN; + } + } +} + +/** + * @brief Enables or disables the Vbat channel. + * @param ADCx: where x can be 1 to select the ADC peripheral. + * @param NewState: new state of the Vbat. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +#ifdef __GNUC__ +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wunused-parameter" +#endif +void ADC_VbatCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Vbat channel*/ + ADC1_2->CCR |= ADC12_CCR_VBATEN; + } + else + { + /* Disable the Vbat channel*/ + ADC1_2->CCR &= ~(uint32_t)ADC12_CCR_VBATEN; + } +} +#ifdef __GNUC__ +# pragma GCC diagnostic pop +#endif +/** + * @} + */ + +/** @defgroup ADC_Group4 Regular Channels Configuration functions + * @brief Regular Channels Configuration functions + * +@verbatim + =============================================================================== + ##### Channels Configuration functions ##### + =============================================================================== + + [..] This section provides functions allowing to manage the ADC regular channels. + + [..] To configure a regular sequence of channels use: + (#) ADC_RegularChannelConfig() + this fuction allows: + (++) Configure the rank in the regular group sequencer for each channel + (++) Configure the sampling time for each channel + + (#) ADC_RegularChannelSequencerLengthConfig() to set the length of the regular sequencer + + [..] The regular trigger is configured using the following functions: + (#) ADC_SelectExternalTrigger() + (#) ADC_ExternalTriggerPolarityConfig() + + [..] The start and the stop conversion are controlled by: + (#) ADC_StartConversion() + (#) ADC_StopConversion() + + [..] + (@)Please Note that the following features for regular channels are configurated + using the ADC_Init() function : + (++) continuous mode activation + (++) Resolution + (++) Data Alignement + (++) Overrun Mode. + + [..] Get the conversion data: This subsection provides an important function in + the ADC peripheral since it returns the converted data of the current + regular channel. When the Conversion value is read, the EOC Flag is + automatically cleared. + + [..] To configure the discontinous mode, the following functions should be used: + (#) ADC_DiscModeChannelCountConfig() to configure the number of discontinuous channel to be converted. + (#) ADC_DiscModeCmd() to enable the discontinuous mode. + + [..] To configure and enable/disable the Channel offset use the functions: + (++) ADC_SetChannelOffset1() + (++) ADC_SetChannelOffset2() + (++) ADC_SetChannelOffset3() + (++) ADC_SetChannelOffset4() + (++) ADC_ChannelOffset1Cmd() + (++) ADC_ChannelOffset2Cmd() + (++) ADC_ChannelOffset3Cmd() + (++) ADC_ChannelOffset4Cmd() + +@endverbatim + * @{ + */ + +/** + * @brief Configures for the selected ADC regular channel its corresponding + * rank in the sequencer and its sample time. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure. + * This parameter can be one of the following values: + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @arg ADC_Channel_18: ADC Channel18 selected + * @param Rank: The rank in the regular group sequencer. This parameter must be between 1 to 16. + * @param ADC_SampleTime: The sample time value to be set for the selected channel. + * This parameter can be one of the following values: + * @arg ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles + * @arg ADC_SampleTime_2Cycles5: Sample time equal to 2.5 cycles + * @arg ADC_SampleTime_4Cycles5: Sample time equal to 4.5 cycles + * @arg ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles + * @arg ADC_SampleTime_19Cycles5: Sample time equal to 19.5 cycles + * @arg ADC_SampleTime_61Cycles5: Sample time equal to 61.5 cycles + * @arg ADC_SampleTime_181Cycles5: Sample time equal to 181.5 cycles + * @arg ADC_SampleTime_601Cycles5: Sample time equal to 601.5 cycles + * @retval None + */ +void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime) +{ + uint32_t tmpreg1 = 0, tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime)); + + /* Regular sequence configuration */ + /* For Rank 1 to 4 */ + if (Rank < 5) + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR1; + /* Calculate the mask to clear */ + tmpreg2 = 0x1F << (6 * (Rank )); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)(ADC_Channel) << (6 * (Rank)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SQR1 = tmpreg1; + } + /* For Rank 5 to 9 */ + else if (Rank < 10) + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR2; + /* Calculate the mask to clear */ + tmpreg2 = ADC_SQR2_SQ5 << (6 * (Rank - 5)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)(ADC_Channel) << (6 * (Rank - 5)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SQR2 = tmpreg1; + } + /* For Rank 10 to 14 */ + else if (Rank < 15) + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR3; + /* Calculate the mask to clear */ + tmpreg2 = ADC_SQR3_SQ10 << (6 * (Rank - 10)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)(ADC_Channel) << (6 * (Rank - 10)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SQR3 = tmpreg1; + } + else + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR4; + /* Calculate the mask to clear */ + tmpreg2 = ADC_SQR3_SQ15 << (6 * (Rank - 15)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)(ADC_Channel) << (6 * (Rank - 15)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SQR4 = tmpreg1; + } + + /* Channel sampling configuration */ + /* if ADC_Channel_10 ... ADC_Channel_18 is selected */ + if (ADC_Channel > ADC_Channel_9) + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR2; + /* Calculate the mask to clear */ + tmpreg2 = ADC_SMPR2_SMP10 << (3 * (ADC_Channel - 10)); + /* Clear the old channel sample time */ + ADCx->SMPR2 &= ~tmpreg2; + /* Calculate the mask to set */ + ADCx->SMPR2 |= (uint32_t)ADC_SampleTime << (3 * (ADC_Channel - 10)); + + } + else /* ADC_Channel include in ADC_Channel_[0..9] */ + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR1; + /* Calculate the mask to clear */ + tmpreg2 = ADC_SMPR1_SMP1 << (3 * (ADC_Channel - 1)); + /* Clear the old channel sample time */ + ADCx->SMPR1 &= ~tmpreg2; + /* Calculate the mask to set */ + ADCx->SMPR1 |= (uint32_t)ADC_SampleTime << (3 * (ADC_Channel)); + } +} + +/** + * @brief Sets the ADC regular channel sequence lenght. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param SequenceLength: The Regular sequence length. This parameter must be between 1 to 16. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_RegularChannelSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t SequencerLength) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Configure the ADC sequence lenght */ + ADCx->SQR1 &= ~(uint32_t)ADC_SQR1_L; + ADCx->SQR1 |= (uint32_t)(SequencerLength - 1); +} + +/** + * @brief External Trigger Enable and Polarity Selection for regular channels. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_ExternalTrigConvEvent: ADC external Trigger source. + * This parameter can be one of the following values: + * @arg ADC_ExternalTrigger_Event0: External trigger event 0 + * @arg ADC_ExternalTrigger_Event1: External trigger event 1 + * @arg ADC_ExternalTrigger_Event2: External trigger event 2 + * @arg ADC_ExternalTrigger_Event3: External trigger event 3 + * @arg ADC_ExternalTrigger_Event4: External trigger event 4 + * @arg ADC_ExternalTrigger_Event5: External trigger event 5 + * @arg ADC_ExternalTrigger_Event6: External trigger event 6 + * @arg ADC_ExternalTrigger_Event7: External trigger event 7 + * @arg ADC_ExternalTrigger_Event8: External trigger event 8 + * @arg ADC_ExternalTrigger_Event9: External trigger event 9 + * @arg ADC_ExternalTrigger_Event10: External trigger event 10 + * @arg ADC_ExternalTrigger_Event11: External trigger event 11 + * @arg ADC_ExternalTrigger_Event12: External trigger event 12 + * @arg ADC_ExternalTrigger_Event13: External trigger event 13 + * @arg ADC_ExternalTrigger_Event14: External trigger event 14 + * @arg ADC_ExternalTrigger_Event15: External trigger event 15 + * @param ADC_ExternalTrigEventEdge: ADC external Trigger Polarity. + * This parameter can be one of the following values: + * @arg ADC_ExternalTrigEventEdge_OFF: Hardware trigger detection disabled + * (conversions can be launched by software) + * @arg ADC_ExternalTrigEventEdge_RisingEdge: Hardware trigger detection on the rising edge + * @arg ADC_ExternalTrigEventEdge_FallingEdge: Hardware trigger detection on the falling edge + * @arg ADC_ExternalTrigEventEdge_BothEdge: Hardware trigger detection on both the rising and falling edges + * @retval None + */ +void ADC_ExternalTriggerConfig(ADC_TypeDef* ADCx, uint16_t ADC_ExternalTrigConvEvent, uint16_t ADC_ExternalTrigEventEdge) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_EXT_TRIG(ADC_ExternalTrigConvEvent)); + assert_param(IS_EXTERNALTRIG_EDGE(ADC_ExternalTrigEventEdge)); + + /* Disable the selected ADC conversion on external event */ + ADCx->CFGR &= ~(ADC_CFGR_EXTEN | ADC_CFGR_EXTSEL); + ADCx->CFGR |= (uint32_t)(ADC_ExternalTrigEventEdge | ADC_ExternalTrigConvEvent); +} + +/** + * @brief Enables or disables the selected ADC start conversion . + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @retval None + */ +void ADC_StartConversion(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Set the ADSTART bit */ + ADCx->CR |= ADC_CR_ADSTART; +} + +/** + * @brief Gets the selected ADC start conversion Status. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @retval The new state of ADC start conversion (SET or RESET). + */ +FlagStatus ADC_GetStartConversionStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Check the status of ADSTART bit */ + if ((ADCx->CR & ADC_CR_ADSTART) != (uint32_t)RESET) + { + /* ADSTART bit is set */ + bitstatus = SET; + } + else + { + /* ADSTART bit is reset */ + bitstatus = RESET; + } + /* Return the ADSTART bit status */ + return bitstatus; +} + +/** + * @brief Stops the selected ADC ongoing conversion. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @retval None + */ +void ADC_StopConversion(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Set the ADSTP bit */ + ADCx->CR |= ADC_CR_ADSTP; +} + + +/** + * @brief Configures the discontinuous mode for the selected ADC regular + * group channel. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param Number: specifies the discontinuous mode regular channel + * count value. This number must be between 1 and 8. + * @retval None + */ +void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number) +{ + uint32_t tmpreg1 = 0; + uint32_t tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_REGULAR_DISC_NUMBER(Number)); + /* Get the old register value */ + tmpreg1 = ADCx->CFGR; + /* Clear the old discontinuous mode channel count */ + tmpreg1 &= ~(uint32_t)(ADC_CFGR_DISCNUM); + /* Set the discontinuous mode channel count */ + tmpreg2 = Number - 1; + tmpreg1 |= tmpreg2 << 17; + /* Store the new register value */ + ADCx->CFGR = tmpreg1; +} + +/** + * @brief Enables or disables the discontinuous mode on regular group + * channel for the specified ADC + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param NewState: new state of the selected ADC discontinuous mode + * on regular group channel. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC regular discontinuous mode */ + ADCx->CFGR |= ADC_CFGR_DISCEN; + } + else + { + /* Disable the selected ADC regular discontinuous mode */ + ADCx->CFGR &= ~(uint32_t)(ADC_CFGR_DISCEN); + } +} + +/** + * @brief Returns the last ADCx conversion result data for regular channel. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @retval The Data conversion value. + */ +uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Return the selected ADC conversion value */ + return (uint16_t) ADCx->DR; +} + +/** + * @brief Returns the last ADC1, ADC2, ADC3 and ADC4 regular conversions results + * data in the selected dual mode. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @retval The Data conversion value. + * @note In dual mode, the value returned by this function is as following + * Data[15:0] : these bits contain the regular data of the Master ADC. + * Data[31:16]: these bits contain the regular data of the Slave ADC. + */ +uint32_t ADC_GetDualModeConversionValue(ADC_TypeDef* ADCx) +{ + uint32_t tmpreg1 = 0; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + if((ADCx == ADC1) || (ADCx== ADC2)) + { + /* Get the dual mode conversion value */ + tmpreg1 = ADC1_2->CDR; + } + else + { + /* Get the dual mode conversion value */ + tmpreg1 = ADC3_4->CDR; + } + /* Return the dual mode conversion value */ + return (uint32_t) tmpreg1; +} + +/** + * @brief Set the ADC channels conversion value offset1 + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure. + * This parameter can be one of the following values: + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @arg ADC_Channel_18: ADC Channel18 selected + * @param Offset: the offset value for the selected ADC Channel + * This parameter must be a 12bit value. + * @retval None + */ +void ADC_SetChannelOffset1(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint16_t Offset) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + assert_param(IS_ADC_OFFSET(Offset)); + + /* Select the Channel */ + ADCx->OFR1 &= ~ (uint32_t) ADC_OFR1_OFFSET1_CH; + ADCx->OFR1 |= (uint32_t)((uint32_t)ADC_Channel << 26); + + /* Set the data offset */ + ADCx->OFR1 &= ~ (uint32_t) ADC_OFR1_OFFSET1; + ADCx->OFR1 |= (uint32_t)Offset; +} + +/** + * @brief Set the ADC channels conversion value offset2 + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure. + * This parameter can be one of the following values: + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @arg ADC_Channel_18: ADC Channel18 selected + * @param Offset: the offset value for the selected ADC Channel + * This parameter must be a 12bit value. + * @retval None + */ +void ADC_SetChannelOffset2(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint16_t Offset) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + assert_param(IS_ADC_OFFSET(Offset)); + + /* Select the Channel */ + ADCx->OFR2 &= ~ (uint32_t) ADC_OFR2_OFFSET2_CH; + ADCx->OFR2 |= (uint32_t)((uint32_t)ADC_Channel << 26); + + /* Set the data offset */ + ADCx->OFR2 &= ~ (uint32_t) ADC_OFR2_OFFSET2; + ADCx->OFR2 |= (uint32_t)Offset; +} + +/** + * @brief Set the ADC channels conversion value offset3 + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure. + * This parameter can be one of the following values: + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @arg ADC_Channel_18: ADC Channel18 selected + * @param Offset: the offset value for the selected ADC Channel + * This parameter must be a 12bit value. + * @retval None + */ +void ADC_SetChannelOffset3(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint16_t Offset) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + assert_param(IS_ADC_OFFSET(Offset)); + + /* Select the Channel */ + ADCx->OFR3 &= ~ (uint32_t) ADC_OFR3_OFFSET3_CH; + ADCx->OFR3 |= (uint32_t)((uint32_t)ADC_Channel << 26); + + /* Set the data offset */ + ADCx->OFR3 &= ~ (uint32_t) ADC_OFR3_OFFSET3; + ADCx->OFR3 |= (uint32_t)Offset; +} + +/** + * @brief Set the ADC channels conversion value offset4 + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure. + * This parameter can be one of the following values: + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @arg ADC_Channel_18: ADC Channel18 selected + * @param Offset: the offset value for the selected ADC Channel + * This parameter must be a 12bit value. + * @retval None + */ +void ADC_SetChannelOffset4(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint16_t Offset) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + assert_param(IS_ADC_OFFSET(Offset)); + + /* Select the Channel */ + ADCx->OFR4 &= ~ (uint32_t) ADC_OFR4_OFFSET4_CH; + ADCx->OFR4 |= (uint32_t)((uint32_t)ADC_Channel << 26); + + /* Set the data offset */ + ADCx->OFR4 &= ~ (uint32_t) ADC_OFR4_OFFSET4; + ADCx->OFR4 |= (uint32_t)Offset; +} + +/** + * @brief Enables or disables the Offset1. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param NewState: new state of the ADCx offset1. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ChannelOffset1Cmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the OFFSET1_EN bit */ + ADCx->OFR1 |= ADC_OFR1_OFFSET1_EN; + } + else + { + /* Reset the OFFSET1_EN bit */ + ADCx->OFR1 &= ~(ADC_OFR1_OFFSET1_EN); + } +} + +/** + * @brief Enables or disables the Offset2. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param NewState: new state of the ADCx offset2. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ChannelOffset2Cmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the OFFSET1_EN bit */ + ADCx->OFR2 |= ADC_OFR2_OFFSET2_EN; + } + else + { + /* Reset the OFFSET1_EN bit */ + ADCx->OFR2 &= ~(ADC_OFR2_OFFSET2_EN); + } +} + +/** + * @brief Enables or disables the Offset3. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param NewState: new state of the ADCx offset3. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ChannelOffset3Cmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the OFFSET1_EN bit */ + ADCx->OFR3 |= ADC_OFR3_OFFSET3_EN; + } + else + { + /* Reset the OFFSET1_EN bit */ + ADCx->OFR3 &= ~(ADC_OFR3_OFFSET3_EN); + } +} + +/** + * @brief Enables or disables the Offset4. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param NewState: new state of the ADCx offset4. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ChannelOffset4Cmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the OFFSET1_EN bit */ + ADCx->OFR4 |= ADC_OFR4_OFFSET4_EN; + } + else + { + /* Reset the OFFSET1_EN bit */ + ADCx->OFR4 &= ~(ADC_OFR4_OFFSET4_EN); + } +} + +/** + * @} + */ + +/** @defgroup ADC_Group5 Regular Channels DMA Configuration functions + * @brief Regular Channels DMA Configuration functions + * +@verbatim + =============================================================================== + ##### Regular Channels DMA Configuration functions ##### + =============================================================================== + + [..] This section provides functions allowing to configure the DMA for ADC regular + channels. Since converted regular channel values are stored into a unique data register, + it is useful to use DMA for conversion of more than one regular channel. This + avoids the loss of the data already stored in the ADC Data register. + + (#) ADC_DMACmd() function is used to enable the ADC DMA mode, after each + conversion of a regular channel, a DMA request is generated. + (#) ADC_DMAConfig() function is used to select between the one shot DMA mode + or the circular DMA mode + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified ADC DMA request. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param NewState: new state of the selected ADC DMA transfer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_DMA_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC DMA request */ + ADCx->CFGR |= ADC_CFGR_DMAEN; + } + else + { + /* Disable the selected ADC DMA request */ + ADCx->CFGR &= ~(uint32_t)ADC_CFGR_DMAEN; + } +} + +/** + * @brief Configure ADC DMA mode. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_DMAMode: select the ADC DMA mode. + * This parameter can be one of the following values: + * @arg ADC_DMAMode_OneShot: ADC DMA Oneshot mode + * @arg ADC_DMAMode_Circular: ADC DMA circular mode + * @retval None + */ +void ADC_DMAConfig(ADC_TypeDef* ADCx, uint32_t ADC_DMAMode) +{ + /* Check the parameters */ + assert_param(IS_ADC_DMA_PERIPH(ADCx)); + assert_param(IS_ADC_DMA_MODE(ADC_DMAMode)); + + /* Set or reset the DMACFG bit */ + ADCx->CFGR &= ~(uint32_t)ADC_CFGR_DMACFG; + ADCx->CFGR |= ADC_DMAMode; +} + +/** + * @} + */ + +/** @defgroup ADC_Group6 Injected channels Configuration functions + * @brief Injected channels Configuration functions + * +@verbatim + =============================================================================== + ##### Injected channels Configuration functions ##### + =============================================================================== + + [..] This section provide functions allowing to manage the ADC Injected channels, + it is composed of : + + (#) Configuration functions for Injected channels sample time + (#) Functions to start and stop the injected conversion + (#) unction to select the discontinuous mode + (#) Function to get the Specified Injected channel conversion data: This subsection + provides an important function in the ADC peripheral since it returns the + converted data of the specific injected channel. + +@endverbatim + * @{ + */ + +/** + * @brief Configures for the selected ADC injected channel its corresponding + * sample time. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure. + * This parameter can be one of the following values: + * @arg ADC_InjectedChannel_1: ADC Channel1 selected + * @arg ADC_InjectedChannel_2: ADC Channel2 selected + * @arg ADC_InjectedChannel_3: ADC Channel3 selected + * @arg ADC_InjectedChannel_4: ADC Channel4 selected + * @arg ADC_InjectedChannel_5: ADC Channel5 selected + * @arg ADC_InjectedChannel_6: ADC Channel6 selected + * @arg ADC_InjectedChannel_7: ADC Channel7 selected + * @arg ADC_InjectedChannel_8: ADC Channel8 selected + * @arg ADC_InjectedChannel_9: ADC Channel9 selected + * @arg ADC_InjectedChannel_10: ADC Channel10 selected + * @arg ADC_InjectedChannel_11: ADC Channel11 selected + * @arg ADC_InjectedChannel_12: ADC Channel12 selected + * @arg ADC_InjectedChannel_13: ADC Channel13 selected + * @arg ADC_InjectedChannel_14: ADC Channel14 selected + * @arg ADC_InjectedChannel_15: ADC Channel15 selected + * @arg ADC_InjectedChannel_16: ADC Channel16 selected + * @arg ADC_InjectedChannel_17: ADC Channel17 selected + * @arg ADC_InjectedChannel_18: ADC Channel18 selected + * @param ADC_SampleTime: The sample time value to be set for the selected channel. + * This parameter can be one of the following values: + * @arg ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles + * @arg ADC_SampleTime_2Cycles5: Sample time equal to 2.5 cycles + * @arg ADC_SampleTime_4Cycles5: Sample time equal to 4.5 cycles + * @arg ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles + * @arg ADC_SampleTime_19Cycles5: Sample time equal to 19.5 cycles + * @arg ADC_SampleTime_61Cycles5: Sample time equal to 61.5 cycles + * @arg ADC_SampleTime_181Cycles5: Sample time equal to 181.5 cycles + * @arg ADC_SampleTime_601Cycles5: Sample time equal to 601.5 cycles + * @retval None + */ +void ADC_InjectedChannelSampleTimeConfig(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint8_t ADC_SampleTime) +{ + uint32_t tmpreg1 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel)); + assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime)); + + /* Channel sampling configuration */ + /* if ADC_InjectedChannel_10 ... ADC_InjectedChannel_18 is selected */ + if (ADC_InjectedChannel > ADC_InjectedChannel_9) + { + /* Calculate the mask to clear */ + tmpreg1 = ADC_SMPR2_SMP10 << (3 * (ADC_InjectedChannel - 10)); + /* Clear the old channel sample time */ + ADCx->SMPR2 &= ~tmpreg1; + /* Calculate the mask to set */ + ADCx->SMPR2 |= (uint32_t)ADC_SampleTime << (3 * (ADC_InjectedChannel - 10)); + + } + else /* ADC_InjectedChannel include in ADC_InjectedChannel_[0..9] */ + { + /* Calculate the mask to clear */ + tmpreg1 = ADC_SMPR1_SMP1 << (3 * (ADC_InjectedChannel - 1)); + /* Clear the old channel sample time */ + ADCx->SMPR1 &= ~tmpreg1; + /* Calculate the mask to set */ + ADCx->SMPR1 |= (uint32_t)ADC_SampleTime << (3 * (ADC_InjectedChannel)); + } +} + +/** + * @brief Enables or disables the selected ADC start of the injected + * channels conversion. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param NewState: new state of the selected ADC software start injected conversion. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_StartInjectedConversion(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Enable the selected ADC conversion for injected group on external event and start the selected + ADC injected conversion */ + ADCx->CR |= ADC_CR_JADSTART; +} + +/** + * @brief Stops the selected ADC ongoing injected conversion. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @retval None + */ +void ADC_StopInjectedConversion(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Set the JADSTP bit */ + ADCx->CR |= ADC_CR_JADSTP; +} + +/** + * @brief Gets the selected ADC Software start injected conversion Status. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @retval The new state of ADC start injected conversion (SET or RESET). + */ +FlagStatus ADC_GetStartInjectedConversionStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + /* Check the status of JADSTART bit */ + if ((ADCx->CR & ADC_CR_JADSTART) != (uint32_t)RESET) + { + /* JADSTART bit is set */ + bitstatus = SET; + } + else + { + /* JADSTART bit is reset */ + bitstatus = RESET; + } + /* Return the JADSTART bit status */ + return bitstatus; +} + +/** + * @brief Enables or disables the selected ADC automatic injected group + * conversion after regular one. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param NewState: new state of the selected ADC auto injected conversion + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC automatic injected group conversion */ + ADCx->CFGR |= ADC_CFGR_JAUTO; + } + else + { + /* Disable the selected ADC automatic injected group conversion */ + ADCx->CFGR &= ~ADC_CFGR_JAUTO; + } +} + +/** + * @brief Enables or disables the discontinuous mode for injected group + * channel for the specified ADC + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param NewState: new state of the selected ADC discontinuous mode + * on injected group channel. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC injected discontinuous mode */ + ADCx->CFGR |= ADC_CFGR_JDISCEN; + } + else + { + /* Disable the selected ADC injected discontinuous mode */ + ADCx->CFGR &= ~ADC_CFGR_JDISCEN; + } +} + +/** + * @brief Returns the ADC injected channel conversion result + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_InjectedSequence: the converted ADC injected sequence. + * This parameter can be one of the following values: + * @arg ADC_InjectedSequence_1: Injected Sequence1 selected + * @arg ADC_InjectedSequence_2: Injected Sequence2 selected + * @arg ADC_InjectedSequence_3: Injected Sequence3 selected + * @arg ADC_InjectedSequence_4: Injected Sequence4 selected + * @retval The Data conversion value. + */ +uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedSequence) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_INJECTED_SEQUENCE(ADC_InjectedSequence)); + + tmp = (uint32_t)ADCx; + tmp += ((ADC_InjectedSequence - 1 )<< 2) + JDR_Offset; + + /* Returns the selected injected channel conversion data value */ + return (uint16_t) (*(__IO uint32_t*) tmp); +} + +/** + * @} + */ + +/** @defgroup ADC_Group7 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + ##### Interrupts and flags management functions ##### + =============================================================================== + + [..] This section provides functions allowing to configure the ADC Interrupts, get + the status and clear flags and Interrupts pending bits. + + [..] The ADC provide 11 Interrupts sources and 11 Flags which can be divided into 3 groups: + + (#) Flags and Interrupts for ADC regular channels + (##)Flags + (+) ADC_FLAG_RDY: ADC Ready flag + (+) ADC_FLAG_EOSMP: ADC End of Sampling flag + (+) ADC_FLAG_EOC: ADC End of Regular Conversion flag. + (+) ADC_FLAG_EOS: ADC End of Regular sequence of Conversions flag + (+) ADC_FLAG_OVR: ADC overrun flag + + (##) Interrupts + (+) ADC_IT_RDY: ADC Ready interrupt source + (+) ADC_IT_EOSMP: ADC End of Sampling interrupt source + (+) ADC_IT_EOC: ADC End of Regular Conversion interrupt source + (+) ADC_IT_EOS: ADC End of Regular sequence of Conversions interrupt + (+) ADC_IT_OVR: ADC overrun interrupt source + + + (#) Flags and Interrupts for ADC regular channels + (##)Flags + (+) ADC_FLAG_JEOC: ADC Ready flag + (+) ADC_FLAG_JEOS: ADC End of Sampling flag + (+) ADC_FLAG_JQOVF: ADC End of Regular Conversion flag. + + (##) Interrupts + (+) ADC_IT_JEOC: ADC End of Injected Conversion interrupt source + (+) ADC_IT_JEOS: ADC End of Injected sequence of Conversions interrupt source + (+) ADC_IT_JQOVF: ADC Injected Context Queue Overflow interrupt source + + (#) General Flags and Interrupts for the ADC + (##)Flags + (+) ADC_FLAG_AWD1: ADC Analog watchdog 1 flag + (+) ADC_FLAG_AWD2: ADC Analog watchdog 2 flag + (+) ADC_FLAG_AWD3: ADC Analog watchdog 3 flag + + (##)Flags + (+) ADC_IT_AWD1: ADC Analog watchdog 1 interrupt source + (+) ADC_IT_AWD2: ADC Analog watchdog 2 interrupt source + (+) ADC_IT_AWD3: ADC Analog watchdog 3 interrupt source + + (#) Flags for ADC dual mode + (##)Flags for Master + (+) ADC_FLAG_MSTRDY: ADC master Ready (ADRDY) flag + (+) ADC_FLAG_MSTEOSMP: ADC master End of Sampling flag + (+) ADC_FLAG_MSTEOC: ADC master End of Regular Conversion flag + (+) ADC_FLAG_MSTEOS: ADC master End of Regular sequence of Conversions flag + (+) ADC_FLAG_MSTOVR: ADC master overrun flag + (+) ADC_FLAG_MSTJEOC: ADC master End of Injected Conversion flag + (+) ADC_FLAG_MSTJEOS: ADC master End of Injected sequence of Conversions flag + (+) ADC_FLAG_MSTAWD1: ADC master Analog watchdog 1 flag + (+) ADC_FLAG_MSTAWD2: ADC master Analog watchdog 2 flag + (+) ADC_FLAG_MSTAWD3: ADC master Analog watchdog 3 flag + (+) ADC_FLAG_MSTJQOVF: ADC master Injected Context Queue Overflow flag + + (##) Flags for Slave + (+) ADC_FLAG_SLVRDY: ADC slave Ready (ADRDY) flag + (+) ADC_FLAG_SLVEOSMP: ADC slave End of Sampling flag + (+) ADC_FLAG_SLVEOC: ADC slave End of Regular Conversion flag + (+) ADC_FLAG_SLVEOS: ADC slave End of Regular sequence of Conversions flag + (+) ADC_FLAG_SLVOVR: ADC slave overrun flag + (+) ADC_FLAG_SLVJEOC: ADC slave End of Injected Conversion flag + (+) ADC_FLAG_SLVJEOS: ADC slave End of Injected sequence of Conversions flag + (+) ADC_FLAG_SLVAWD1: ADC slave Analog watchdog 1 flag + (+) ADC_FLAG_SLVAWD2: ADC slave Analog watchdog 2 flag + (+) ADC_FLAG_SLVAWD3: ADC slave Analog watchdog 3 flag + (+) ADC_FLAG_SLVJQOVF: ADC slave Injected Context Queue Overflow flag + + The user should identify which mode will be used in his application to manage + the ADC controller events: Polling mode or Interrupt mode. + + In the Polling Mode it is advised to use the following functions: + - ADC_GetFlagStatus() : to check if flags events occur. + - ADC_ClearFlag() : to clear the flags events. + + In the Interrupt Mode it is advised to use the following functions: + - ADC_ITConfig() : to enable or disable the interrupt source. + - ADC_GetITStatus() : to check if Interrupt occurs. + - ADC_ClearITPendingBit() : to clear the Interrupt pending Bit + (corresponding Flag). +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified ADC interrupts. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_IT: specifies the ADC interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg ADC_IT_RDY: ADC Ready (ADRDY) interrupt source + * @arg ADC_IT_EOSMP: ADC End of Sampling interrupt source + * @arg ADC_IT_EOC: ADC End of Regular Conversion interrupt source + * @arg ADC_IT_EOS: ADC End of Regular sequence of Conversions interrupt source + * @arg ADC_IT_OVR: ADC overrun interrupt source + * @arg ADC_IT_JEOC: ADC End of Injected Conversion interrupt source + * @arg ADC_IT_JEOS: ADC End of Injected sequence of Conversions interrupt source + * @arg ADC_IT_AWD1: ADC Analog watchdog 1 interrupt source + * @arg ADC_IT_AWD2: ADC Analog watchdog 2 interrupt source + * @arg ADC_IT_AWD3: ADC Analog watchdog 3 interrupt source + * @arg ADC_IT_JQOVF: ADC Injected Context Queue Overflow interrupt source + * @param NewState: new state of the specified ADC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ITConfig(ADC_TypeDef* ADCx, uint32_t ADC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_ADC_IT(ADC_IT)); + + if (NewState != DISABLE) + { + /* Enable the selected ADC interrupts */ + ADCx->IER |= ADC_IT; + } + else + { + /* Disable the selected ADC interrupts */ + ADCx->IER &= (~(uint32_t)ADC_IT); + } +} + +/** + * @brief Checks whether the specified ADC flag is set or not. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg ADC_FLAG_RDY: ADC Ready (ADRDY) flag + * @arg ADC_FLAG_EOSMP: ADC End of Sampling flag + * @arg ADC_FLAG_EOC: ADC End of Regular Conversion flag + * @arg ADC_FLAG_EOS: ADC End of Regular sequence of Conversions flag + * @arg ADC_FLAG_OVR: ADC overrun flag + * @arg ADC_FLAG_JEOC: ADC End of Injected Conversion flag + * @arg ADC_FLAG_JEOS: ADC End of Injected sequence of Conversions flag + * @arg ADC_FLAG_AWD1: ADC Analog watchdog 1 flag + * @arg ADC_FLAG_AWD2: ADC Analog watchdog 2 flag + * @arg ADC_FLAG_AWD3: ADC Analog watchdog 3 flag + * @arg ADC_FLAG_JQOVF: ADC Injected Context Queue Overflow flag + * @retval The new state of ADC_FLAG (SET or RESET). + */ +FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint32_t ADC_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_GET_FLAG(ADC_FLAG)); + + /* Check the status of the specified ADC flag */ + if ((ADCx->ISR & ADC_FLAG) != (uint32_t)RESET) + { + /* ADC_FLAG is set */ + bitstatus = SET; + } + else + { + /* ADC_FLAG is reset */ + bitstatus = RESET; + } + /* Return the ADC_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the ADCx's pending flags. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg ADC_FLAG_RDY: ADC Ready (ADRDY) flag + * @arg ADC_FLAG_EOSMP: ADC End of Sampling flag + * @arg ADC_FLAG_EOC: ADC End of Regular Conversion flag + * @arg ADC_FLAG_EOS: ADC End of Regular sequence of Conversions flag + * @arg ADC_FLAG_OVR: ADC overrun flag + * @arg ADC_FLAG_JEOC: ADC End of Injected Conversion flag + * @arg ADC_FLAG_JEOS: ADC End of Injected sequence of Conversions flag + * @arg ADC_FLAG_AWD1: ADC Analog watchdog 1 flag + * @arg ADC_FLAG_AWD2: ADC Analog watchdog 2 flag + * @arg ADC_FLAG_AWD3: ADC Analog watchdog 3 flag + * @arg ADC_FLAG_JQOVF: ADC Injected Context Queue Overflow flag + * @retval None + */ +void ADC_ClearFlag(ADC_TypeDef* ADCx, uint32_t ADC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CLEAR_FLAG(ADC_FLAG)); + /* Clear the selected ADC flags */ + ADCx->ISR = (uint32_t)ADC_FLAG; +} + +/** + * @brief Checks whether the specified ADC flag is set or not. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_FLAG: specifies the master or slave flag to check. + * This parameter can be one of the following values: + * @arg ADC_FLAG_MSTRDY: ADC master Ready (ADRDY) flag + * @arg ADC_FLAG_MSTEOSMP: ADC master End of Sampling flag + * @arg ADC_FLAG_MSTEOC: ADC master End of Regular Conversion flag + * @arg ADC_FLAG_MSTEOS: ADC master End of Regular sequence of Conversions flag + * @arg ADC_FLAG_MSTOVR: ADC master overrun flag + * @arg ADC_FLAG_MSTJEOC: ADC master End of Injected Conversion flag + * @arg ADC_FLAG_MSTJEOS: ADC master End of Injected sequence of Conversions flag + * @arg ADC_FLAG_MSTAWD1: ADC master Analog watchdog 1 flag + * @arg ADC_FLAG_MSTAWD2: ADC master Analog watchdog 2 flag + * @arg ADC_FLAG_MSTAWD3: ADC master Analog watchdog 3 flag + * @arg ADC_FLAG_MSTJQOVF: ADC master Injected Context Queue Overflow flag + * @arg ADC_FLAG_SLVRDY: ADC slave Ready (ADRDY) flag + * @arg ADC_FLAG_SLVEOSMP: ADC slave End of Sampling flag + * @arg ADC_FLAG_SLVEOC: ADC slave End of Regular Conversion flag + * @arg ADC_FLAG_SLVEOS: ADC slave End of Regular sequence of Conversions flag + * @arg ADC_FLAG_SLVOVR: ADC slave overrun flag + * @arg ADC_FLAG_SLVJEOC: ADC slave End of Injected Conversion flag + * @arg ADC_FLAG_SLVJEOS: ADC slave End of Injected sequence of Conversions flag + * @arg ADC_FLAG_SLVAWD1: ADC slave Analog watchdog 1 flag + * @arg ADC_FLAG_SLVAWD2: ADC slave Analog watchdog 2 flag + * @arg ADC_FLAG_SLVAWD3: ADC slave Analog watchdog 3 flag + * @arg ADC_FLAG_SLVJQOVF: ADC slave Injected Context Queue Overflow flag + * @retval The new state of ADC_FLAG (SET or RESET). + */ +FlagStatus ADC_GetCommonFlagStatus(ADC_TypeDef* ADCx, uint32_t ADC_FLAG) +{ + uint32_t tmpreg1 = 0; + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_GET_COMMONFLAG(ADC_FLAG)); + + if((ADCx == ADC1) || (ADCx == ADC2)) + { + tmpreg1 = ADC1_2->CSR; + } + else + { + tmpreg1 = ADC3_4->CSR; + } + /* Check the status of the specified ADC flag */ + if ((tmpreg1 & ADC_FLAG) != (uint32_t)RESET) + { + /* ADC_FLAG is set */ + bitstatus = SET; + } + else + { + /* ADC_FLAG is reset */ + bitstatus = RESET; + } + /* Return the ADC_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the ADCx's pending flags. + * @param ADCx: where x can be 1, 2, 3 or 4 to select the ADC peripheral. + * @param ADC_FLAG: specifies the master or slave flag to clear. + * This parameter can be one of the following values: + * @arg ADC_FLAG_MSTRDY: ADC master Ready (ADRDY) flag + * @arg ADC_FLAG_MSTEOSMP: ADC master End of Sampling flag + * @arg ADC_FLAG_MSTEOC: ADC master End of Regular Conversion flag + * @arg ADC_FLAG_MSTEOS: ADC master End of Regular sequence of Conversions flag + * @arg ADC_FLAG_MSTOVR: ADC master overrun flag + * @arg ADC_FLAG_MSTJEOC: ADC master End of Injected Conversion flag + * @arg ADC_FLAG_MSTJEOS: ADC master End of Injected sequence of Conversions flag + * @arg ADC_FLAG_MSTAWD1: ADC master Analog watchdog 1 flag + * @arg ADC_FLAG_MSTAWD2: ADC master Analog watchdog 2 flag + * @arg ADC_FLAG_MSTAWD3: ADC master Analog watchdog 3 flag + * @arg ADC_FLAG_MSTJQOVF: ADC master Injected Context Queue Overflow flag + * @arg ADC_FLAG_SLVRDY: ADC slave Ready (ADRDY) flag + * @arg ADC_FLAG_SLVEOSMP: ADC slave End of Sampling flag + * @arg ADC_FLAG_SLVEOC: ADC slave End of Regular Conversion flag + * @arg ADC_FLAG_SLVEOS: ADC slave End of Regular sequence of Conversions flag + * @arg ADC_FLAG_SLVOVR: ADC slave overrun flag + * @arg ADC_FLAG_SLVJEOC: ADC slave End of Injected Conversion flag + * @arg ADC_FLAG_SLVJEOS: ADC slave End of Injected sequence of Conversions flag + * @arg ADC_FLAG_SLVAWD1: ADC slave Analog watchdog 1 flag + * @arg ADC_FLAG_SLVAWD2: ADC slave Analog watchdog 2 flag + * @arg ADC_FLAG_SLVAWD3: ADC slave Analog watchdog 3 flag + * @arg ADC_FLAG_SLVJQOVF: ADC slave Injected Context Queue Overflow flag + * @retval None + */ +void ADC_ClearCommonFlag(ADC_TypeDef* ADCx, uint32_t ADC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CLEAR_COMMONFLAG(ADC_FLAG)); + + if((ADCx == ADC1) || (ADCx == ADC2)) + { + /* Clear the selected ADC flags */ + ADC1_2->CSR |= (uint32_t)ADC_FLAG; + } + else + { + /* Clear the selected ADC flags */ + ADC3_4->CSR |= (uint32_t)ADC_FLAG; + } +} + +/** + * @brief Checks whether the specified ADC interrupt has occurred or not. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_IT: specifies the ADC interrupt source to check. + * This parameter can be one of the following values: + * @arg ADC_IT_RDY: ADC Ready (ADRDY) interrupt source + * @arg ADC_IT_EOSMP: ADC End of Sampling interrupt source + * @arg ADC_IT_EOC: ADC End of Regular Conversion interrupt source + * @arg ADC_IT_EOS: ADC End of Regular sequence of Conversions interrupt source + * @arg ADC_IT_OVR: ADC overrun interrupt source + * @arg ADC_IT_JEOC: ADC End of Injected Conversion interrupt source + * @arg ADC_IT_JEOS: ADC End of Injected sequence of Conversions interrupt source + * @arg ADC_IT_AWD1: ADC Analog watchdog 1 interrupt source + * @arg ADC_IT_AWD2: ADC Analog watchdog 2 interrupt source + * @arg ADC_IT_AWD3: ADC Analog watchdog 3 interrupt source + * @arg ADC_IT_JQOVF: ADC Injected Context Queue Overflow interrupt source + * @retval The new state of ADC_IT (SET or RESET). + */ +ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint32_t ADC_IT) +{ + ITStatus bitstatus = RESET; + uint16_t itstatus = 0x0, itenable = 0x0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_GET_IT(ADC_IT)); + + itstatus = ADCx->ISR & ADC_IT; + + itenable = ADCx->IER & ADC_IT; + if ((itstatus != (uint32_t)RESET) && (itenable != (uint32_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the ADCx's interrupt pending bits. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_IT: specifies the ADC interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg ADC_IT_RDY: ADC Ready (ADRDY) interrupt source + * @arg ADC_IT_EOSMP: ADC End of Sampling interrupt source + * @arg ADC_IT_EOC: ADC End of Regular Conversion interrupt source + * @arg ADC_IT_EOS: ADC End of Regular sequence of Conversions interrupt source + * @arg ADC_IT_OVR: ADC overrun interrupt source + * @arg ADC_IT_JEOC: ADC End of Injected Conversion interrupt source + * @arg ADC_IT_JEOS: ADC End of Injected sequence of Conversions interrupt source + * @arg ADC_IT_AWD1: ADC Analog watchdog 1 interrupt source + * @arg ADC_IT_AWD2: ADC Analog watchdog 2 interrupt source + * @arg ADC_IT_AWD3: ADC Analog watchdog 3 interrupt source + * @arg ADC_IT_JQOVF: ADC Injected Context Queue Overflow interrupt source + * @retval None + */ +void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint32_t ADC_IT) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_IT(ADC_IT)); + /* Clear the selected ADC interrupt pending bit */ + ADCx->ISR = (uint32_t)ADC_IT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_can.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_can.c new file mode 100644 index 0000000..978d604 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_can.c @@ -0,0 +1,1629 @@ +/** + ****************************************************************************** + * @file stm32f30x_can.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the Controller area network (CAN) peripheral: + * + Initialization and Configuration + * + CAN Frames Transmission + * + CAN Frames Reception + * + Operation modes switch + * + Error management + * + Interrupts and flags + * + @verbatim + + =============================================================================== + ##### How to use this driver ##### + =============================================================================== + [..] + (#) Enable the CAN controller interface clock using + RCC_APB1PeriphClockCmd(RCC_APB1Periph_CAN1, ENABLE); + (#) CAN pins configuration: + (++) Enable the clock for the CAN GPIOs using the following function: + RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOx, ENABLE); + (++) Connect the involved CAN pins to AF9 using the following function + GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_CANx); + (++) Configure these CAN pins in alternate function mode by calling + the function GPIO_Init(); + (#) Initialise and configure the CAN using CAN_Init() and + CAN_FilterInit() functions. + (#) Transmit the desired CAN frame using CAN_Transmit() function. + (#) Check the transmission of a CAN frame using CAN_TransmitStatus() function. + (#) Cancel the transmission of a CAN frame using CAN_CancelTransmit() function. + (#) Receive a CAN frame using CAN_Recieve() function. + (#) Release the receive FIFOs using CAN_FIFORelease() function. + (#) Return the number of pending received frames using CAN_MessagePending() function. + (#) To control CAN events you can use one of the following two methods: + (++) Check on CAN flags using the CAN_GetFlagStatus() function. + (++) Use CAN interrupts through the function CAN_ITConfig() at initialization + phase and CAN_GetITStatus() function into interrupt routines to check + if the event has occurred or not. + After checking on a flag you should clear it using CAN_ClearFlag() + function. And after checking on an interrupt event you should clear it + using CAN_ClearITPendingBit() function. + + @endverbatim + * + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_can.h" +#include "stm32f30x_rcc.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup CAN + * @brief CAN driver modules + * @{ + */ +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* CAN Master Control Register bits */ +#define MCR_DBF ((uint32_t)0x00010000) /* software master reset */ + +/* CAN Mailbox Transmit Request */ +#define TMIDxR_TXRQ ((uint32_t)0x00000001) /* Transmit mailbox request */ + +/* CAN Filter Master Register bits */ +#define FMR_FINIT ((uint32_t)0x00000001) /* Filter init mode */ + +/* Time out for INAK bit */ +#define INAK_TIMEOUT ((uint32_t)0x00FFFFFF) +/* Time out for SLAK bit */ +#define SLAK_TIMEOUT ((uint32_t)0x00FFFFFF) + +/* Flags in TSR register */ +#define CAN_FLAGS_TSR ((uint32_t)0x08000000) +/* Flags in RF1R register */ +#define CAN_FLAGS_RF1R ((uint32_t)0x04000000) +/* Flags in RF0R register */ +#define CAN_FLAGS_RF0R ((uint32_t)0x02000000) +/* Flags in MSR register */ +#define CAN_FLAGS_MSR ((uint32_t)0x01000000) +/* Flags in ESR register */ +#define CAN_FLAGS_ESR ((uint32_t)0x00F00000) + +/* Mailboxes definition */ +#define CAN_TXMAILBOX_0 ((uint8_t)0x00) +#define CAN_TXMAILBOX_1 ((uint8_t)0x01) +#define CAN_TXMAILBOX_2 ((uint8_t)0x02) + +#define CAN_MODE_MASK ((uint32_t) 0x00000003) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit); + +/** @defgroup CAN_Private_Functions + * @{ + */ + +/** @defgroup CAN_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] This section provides functions allowing to: + (+) Initialize the CAN peripherals : Prescaler, operating mode, the maximum + number of time quanta to perform resynchronization, the number of time + quanta in Bit Segment 1 and 2 and many other modes. + (+) Configure the CAN reception filter. + (+) Select the start bank filter for slave CAN. + (+) Enable or disable the Debug Freeze mode for CAN. + (+) Enable or disable the CAN Time Trigger Operation communication mode. + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the CAN peripheral registers to their default reset values. + * @param CANx: where x can be 1 to select the CAN1 peripheral. + * @retval None. + */ +void CAN_DeInit(CAN_TypeDef* CANx) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Enable CAN1 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, ENABLE); + /* Release CAN1 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, DISABLE); +} + +/** + * @brief Initializes the CAN peripheral according to the specified + * parameters in the CAN_InitStruct. + * @param CANx: where x can be 1 to select the CAN1 peripheral. + * @param CAN_InitStruct: pointer to a CAN_InitTypeDef structure that contains + * the configuration information for the CAN peripheral. + * @retval Constant indicates initialization succeed which will be + * CAN_InitStatus_Failed or CAN_InitStatus_Success. + */ +uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct) +{ + uint8_t InitStatus = CAN_InitStatus_Failed; + __IO uint32_t wait_ack = 0x00000000; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TTCM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_ABOM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_AWUM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_NART)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_RFLM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TXFP)); + assert_param(IS_CAN_MODE(CAN_InitStruct->CAN_Mode)); + assert_param(IS_CAN_SJW(CAN_InitStruct->CAN_SJW)); + assert_param(IS_CAN_BS1(CAN_InitStruct->CAN_BS1)); + assert_param(IS_CAN_BS2(CAN_InitStruct->CAN_BS2)); + assert_param(IS_CAN_PRESCALER(CAN_InitStruct->CAN_Prescaler)); + + /* Exit from sleep mode */ + CANx->MCR &= (~(uint32_t)CAN_MCR_SLEEP); + + /* Request initialisation */ + CANx->MCR |= CAN_MCR_INRQ ; + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) && (wait_ack != INAK_TIMEOUT)) + { + wait_ack++; + } + + /* Check acknowledge */ + if ((CANx->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) + { + InitStatus = CAN_InitStatus_Failed; + } + else + { + /* Set the time triggered communication mode */ + if (CAN_InitStruct->CAN_TTCM == ENABLE) + { + CANx->MCR |= CAN_MCR_TTCM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_TTCM; + } + + /* Set the automatic bus-off management */ + if (CAN_InitStruct->CAN_ABOM == ENABLE) + { + CANx->MCR |= CAN_MCR_ABOM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_ABOM; + } + + /* Set the automatic wake-up mode */ + if (CAN_InitStruct->CAN_AWUM == ENABLE) + { + CANx->MCR |= CAN_MCR_AWUM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_AWUM; + } + + /* Set the no automatic retransmission */ + if (CAN_InitStruct->CAN_NART == ENABLE) + { + CANx->MCR |= CAN_MCR_NART; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_NART; + } + + /* Set the receive FIFO locked mode */ + if (CAN_InitStruct->CAN_RFLM == ENABLE) + { + CANx->MCR |= CAN_MCR_RFLM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_RFLM; + } + + /* Set the transmit FIFO priority */ + if (CAN_InitStruct->CAN_TXFP == ENABLE) + { + CANx->MCR |= CAN_MCR_TXFP; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_TXFP; + } + + /* Set the bit timing register */ + CANx->BTR = (uint32_t)((uint32_t)CAN_InitStruct->CAN_Mode << 30) | \ + ((uint32_t)CAN_InitStruct->CAN_SJW << 24) | \ + ((uint32_t)CAN_InitStruct->CAN_BS1 << 16) | \ + ((uint32_t)CAN_InitStruct->CAN_BS2 << 20) | \ + ((uint32_t)CAN_InitStruct->CAN_Prescaler - 1); + + /* Request leave initialisation */ + CANx->MCR &= ~(uint32_t)CAN_MCR_INRQ; + + /* Wait the acknowledge */ + wait_ack = 0; + + while (((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) && (wait_ack != INAK_TIMEOUT)) + { + wait_ack++; + } + + /* ...and check acknowledged */ + if ((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) + { + InitStatus = CAN_InitStatus_Failed; + } + else + { + InitStatus = CAN_InitStatus_Success ; + } + } + + /* At this step, return the status of initialization */ + return InitStatus; +} + +/** + * @brief Configures the CAN reception filter according to the specified + * parameters in the CAN_FilterInitStruct. + * @param CAN_FilterInitStruct: pointer to a CAN_FilterInitTypeDef structure that + * contains the configuration information. + * @retval None + */ +void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct) +{ + uint32_t filter_number_bit_pos = 0; + /* Check the parameters */ + assert_param(IS_CAN_FILTER_NUMBER(CAN_FilterInitStruct->CAN_FilterNumber)); + assert_param(IS_CAN_FILTER_MODE(CAN_FilterInitStruct->CAN_FilterMode)); + assert_param(IS_CAN_FILTER_SCALE(CAN_FilterInitStruct->CAN_FilterScale)); + assert_param(IS_CAN_FILTER_FIFO(CAN_FilterInitStruct->CAN_FilterFIFOAssignment)); + assert_param(IS_FUNCTIONAL_STATE(CAN_FilterInitStruct->CAN_FilterActivation)); + + filter_number_bit_pos = ((uint32_t)1) << CAN_FilterInitStruct->CAN_FilterNumber; + + /* Initialisation mode for the filter */ + CAN1->FMR |= FMR_FINIT; + + /* Filter Deactivation */ + CAN1->FA1R &= ~(uint32_t)filter_number_bit_pos; + + /* Filter Scale */ + if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_16bit) + { + /* 16-bit scale for the filter */ + CAN1->FS1R &= ~(uint32_t)filter_number_bit_pos; + + /* First 16-bit identifier and First 16-bit mask */ + /* Or First 16-bit identifier and Second 16-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow); + + /* Second 16-bit identifier and Second 16-bit mask */ + /* Or Third 16-bit identifier and Fourth 16-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh); + } + + if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_32bit) + { + /* 32-bit scale for the filter */ + CAN1->FS1R |= filter_number_bit_pos; + /* 32-bit identifier or First 32-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow); + /* 32-bit mask or Second 32-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow); + } + + /* Filter Mode */ + if (CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdMask) + { + /*Id/Mask mode for the filter*/ + CAN1->FM1R &= ~(uint32_t)filter_number_bit_pos; + } + else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */ + { + /*Identifier list mode for the filter*/ + CAN1->FM1R |= (uint32_t)filter_number_bit_pos; + } + + /* Filter FIFO assignment */ + if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_Filter_FIFO0) + { + /* FIFO 0 assignation for the filter */ + CAN1->FFA1R &= ~(uint32_t)filter_number_bit_pos; + } + + if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_Filter_FIFO1) + { + /* FIFO 1 assignation for the filter */ + CAN1->FFA1R |= (uint32_t)filter_number_bit_pos; + } + + /* Filter activation */ + if (CAN_FilterInitStruct->CAN_FilterActivation == ENABLE) + { + CAN1->FA1R |= filter_number_bit_pos; + } + + /* Leave the initialisation mode for the filter */ + CAN1->FMR &= ~FMR_FINIT; +} + +/** + * @brief Fills each CAN_InitStruct member with its default value. + * @param CAN_InitStruct: pointer to a CAN_InitTypeDef structure which ill be initialized. + * @retval None + */ +void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct) +{ + /* Reset CAN init structure parameters values */ + + /* Initialize the time triggered communication mode */ + CAN_InitStruct->CAN_TTCM = DISABLE; + + /* Initialize the automatic bus-off management */ + CAN_InitStruct->CAN_ABOM = DISABLE; + + /* Initialize the automatic wake-up mode */ + CAN_InitStruct->CAN_AWUM = DISABLE; + + /* Initialize the no automatic retransmission */ + CAN_InitStruct->CAN_NART = DISABLE; + + /* Initialize the receive FIFO locked mode */ + CAN_InitStruct->CAN_RFLM = DISABLE; + + /* Initialize the transmit FIFO priority */ + CAN_InitStruct->CAN_TXFP = DISABLE; + + /* Initialize the CAN_Mode member */ + CAN_InitStruct->CAN_Mode = CAN_Mode_Normal; + + /* Initialize the CAN_SJW member */ + CAN_InitStruct->CAN_SJW = CAN_SJW_1tq; + + /* Initialize the CAN_BS1 member */ + CAN_InitStruct->CAN_BS1 = CAN_BS1_4tq; + + /* Initialize the CAN_BS2 member */ + CAN_InitStruct->CAN_BS2 = CAN_BS2_3tq; + + /* Initialize the CAN_Prescaler member */ + CAN_InitStruct->CAN_Prescaler = 1; +} + +/** + * @brief Select the start bank filter for slave CAN. + * @param CAN_BankNumber: Select the start slave bank filter from 1..27. + * @retval None + */ +void CAN_SlaveStartBank(uint8_t CAN_BankNumber) +{ + /* Check the parameters */ + assert_param(IS_CAN_BANKNUMBER(CAN_BankNumber)); + + /* Enter Initialisation mode for the filter */ + CAN1->FMR |= FMR_FINIT; + + /* Select the start slave bank */ + CAN1->FMR &= (uint32_t)0xFFFFC0F1 ; + CAN1->FMR |= (uint32_t)(CAN_BankNumber)<<8; + + /* Leave Initialisation mode for the filter */ + CAN1->FMR &= ~FMR_FINIT; +} + +/** + * @brief Enables or disables the DBG Freeze for CAN. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param NewState: new state of the CAN peripheral. + * This parameter can be: ENABLE (CAN reception/transmission is frozen + * during debug. Reception FIFOs can still be accessed/controlled normally) + * or DISABLE (CAN is working during debug). + * @retval None + */ +void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable Debug Freeze */ + CANx->MCR |= MCR_DBF; + } + else + { + /* Disable Debug Freeze */ + CANx->MCR &= ~MCR_DBF; + } +} + +/** + * @brief Enables or disables the CAN Time TriggerOperation communication mode. + * @note DLC must be programmed as 8 in order Time Stamp (2 bytes) to be + * sent over the CAN bus. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param NewState: Mode new state. This parameter can be: ENABLE or DISABLE. + * When enabled, Time stamp (TIME[15:0]) value is sent in the last two + * data bytes of the 8-byte message: TIME[7:0] in data byte 6 and TIME[15:8] + * in data byte 7. + * @retval None + */ +void CAN_TTComModeCmd(CAN_TypeDef* CANx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the TTCM mode */ + CANx->MCR |= CAN_MCR_TTCM; + + /* Set TGT bits */ + CANx->sTxMailBox[0].TDTR |= ((uint32_t)CAN_TDT0R_TGT); + CANx->sTxMailBox[1].TDTR |= ((uint32_t)CAN_TDT1R_TGT); + CANx->sTxMailBox[2].TDTR |= ((uint32_t)CAN_TDT2R_TGT); + } + else + { + /* Disable the TTCM mode */ + CANx->MCR &= (uint32_t)(~(uint32_t)CAN_MCR_TTCM); + + /* Reset TGT bits */ + CANx->sTxMailBox[0].TDTR &= ((uint32_t)~CAN_TDT0R_TGT); + CANx->sTxMailBox[1].TDTR &= ((uint32_t)~CAN_TDT1R_TGT); + CANx->sTxMailBox[2].TDTR &= ((uint32_t)~CAN_TDT2R_TGT); + } +} +/** + * @} + */ + + +/** @defgroup CAN_Group2 CAN Frames Transmission functions + * @brief CAN Frames Transmission functions + * +@verbatim + =============================================================================== + ##### CAN Frames Transmission functions ##### + =============================================================================== + [..] This section provides functions allowing to + (+) Initiate and transmit a CAN frame message (if there is an empty mailbox). + (+) Check the transmission status of a CAN Frame. + (+) Cancel a transmit request. + +@endverbatim + * @{ + */ + +/** + * @brief Initiates and transmits a CAN frame message. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param TxMessage: pointer to a structure which contains CAN Id, CAN DLC and CAN data. + * @retval The number of the mailbox that is used for transmission or + * CAN_TxStatus_NoMailBox if there is no empty mailbox. + */ +uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage) +{ + uint8_t transmit_mailbox = 0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_IDTYPE(TxMessage->IDE)); + assert_param(IS_CAN_RTR(TxMessage->RTR)); + assert_param(IS_CAN_DLC(TxMessage->DLC)); + + /* Select one empty transmit mailbox */ + if ((CANx->TSR&CAN_TSR_TME0) == CAN_TSR_TME0) + { + transmit_mailbox = 0; + } + else if ((CANx->TSR&CAN_TSR_TME1) == CAN_TSR_TME1) + { + transmit_mailbox = 1; + } + else if ((CANx->TSR&CAN_TSR_TME2) == CAN_TSR_TME2) + { + transmit_mailbox = 2; + } + else + { + transmit_mailbox = CAN_TxStatus_NoMailBox; + } + + if (transmit_mailbox != CAN_TxStatus_NoMailBox) + { + /* Set up the Id */ + CANx->sTxMailBox[transmit_mailbox].TIR &= TMIDxR_TXRQ; + if (TxMessage->IDE == CAN_Id_Standard) + { + assert_param(IS_CAN_STDID(TxMessage->StdId)); + CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->StdId << 21) | \ + TxMessage->RTR); + } + else + { + assert_param(IS_CAN_EXTID(TxMessage->ExtId)); + CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->ExtId << 3) | \ + TxMessage->IDE | \ + TxMessage->RTR); + } + + /* Set up the DLC */ + TxMessage->DLC &= (uint8_t)0x0000000F; + CANx->sTxMailBox[transmit_mailbox].TDTR &= (uint32_t)0xFFFFFFF0; + CANx->sTxMailBox[transmit_mailbox].TDTR |= TxMessage->DLC; + + /* Set up the data field */ + CANx->sTxMailBox[transmit_mailbox].TDLR = (((uint32_t)TxMessage->Data[3] << 24) | + ((uint32_t)TxMessage->Data[2] << 16) | + ((uint32_t)TxMessage->Data[1] << 8) | + ((uint32_t)TxMessage->Data[0])); + CANx->sTxMailBox[transmit_mailbox].TDHR = (((uint32_t)TxMessage->Data[7] << 24) | + ((uint32_t)TxMessage->Data[6] << 16) | + ((uint32_t)TxMessage->Data[5] << 8) | + ((uint32_t)TxMessage->Data[4])); + /* Request transmission */ + CANx->sTxMailBox[transmit_mailbox].TIR |= TMIDxR_TXRQ; + } + return transmit_mailbox; +} + +/** + * @brief Checks the transmission status of a CAN Frame. + * @param CANx: where x can be 1 to select the CAN1 peripheral. + * @param TransmitMailbox: the number of the mailbox that is used for transmission. + * @retval CAN_TxStatus_Ok if the CAN driver transmits the message, + * CAN_TxStatus_Failed in an other case. + */ +uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox) +{ + uint32_t state = 0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_TRANSMITMAILBOX(TransmitMailbox)); + + switch (TransmitMailbox) + { + case (CAN_TXMAILBOX_0): + state = CANx->TSR & (CAN_TSR_RQCP0 | CAN_TSR_TXOK0 | CAN_TSR_TME0); + break; + case (CAN_TXMAILBOX_1): + state = CANx->TSR & (CAN_TSR_RQCP1 | CAN_TSR_TXOK1 | CAN_TSR_TME1); + break; + case (CAN_TXMAILBOX_2): + state = CANx->TSR & (CAN_TSR_RQCP2 | CAN_TSR_TXOK2 | CAN_TSR_TME2); + break; + default: + state = CAN_TxStatus_Failed; + break; + } + switch (state) + { + /* transmit pending */ + case (0x0): state = CAN_TxStatus_Pending; + break; + /* transmit failed */ + case (CAN_TSR_RQCP0 | CAN_TSR_TME0): state = CAN_TxStatus_Failed; + break; + case (CAN_TSR_RQCP1 | CAN_TSR_TME1): state = CAN_TxStatus_Failed; + break; + case (CAN_TSR_RQCP2 | CAN_TSR_TME2): state = CAN_TxStatus_Failed; + break; + /* transmit succeeded */ + case (CAN_TSR_RQCP0 | CAN_TSR_TXOK0 | CAN_TSR_TME0):state = CAN_TxStatus_Ok; + break; + case (CAN_TSR_RQCP1 | CAN_TSR_TXOK1 | CAN_TSR_TME1):state = CAN_TxStatus_Ok; + break; + case (CAN_TSR_RQCP2 | CAN_TSR_TXOK2 | CAN_TSR_TME2):state = CAN_TxStatus_Ok; + break; + default: state = CAN_TxStatus_Failed; + break; + } + return (uint8_t) state; +} + +/** + * @brief Cancels a transmit request. + * @param CANx: where x can be 1 to select the CAN1 peripheral. + * @param Mailbox: Mailbox number. + * @retval None + */ +void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_TRANSMITMAILBOX(Mailbox)); + /* abort transmission */ + switch (Mailbox) + { + case (CAN_TXMAILBOX_0): CANx->TSR |= CAN_TSR_ABRQ0; + break; + case (CAN_TXMAILBOX_1): CANx->TSR |= CAN_TSR_ABRQ1; + break; + case (CAN_TXMAILBOX_2): CANx->TSR |= CAN_TSR_ABRQ2; + break; + default: + break; + } +} +/** + * @} + */ + + +/** @defgroup CAN_Group3 CAN Frames Reception functions + * @brief CAN Frames Reception functions + * +@verbatim + =============================================================================== + ##### CAN Frames Reception functions ##### + =============================================================================== + [..] This section provides functions allowing to + (+) Receive a correct CAN frame. + (+) Release a specified receive FIFO (2 FIFOs are available). + (+) Return the number of the pending received CAN frames. + +@endverbatim + * @{ + */ + +/** + * @brief Receives a correct CAN frame. + * @param CANx: where x can be 1 to select the CAN1 peripheral. + * @param FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. + * @param RxMessage: pointer to a structure receive frame which contains CAN Id, + * CAN DLC, CAN data and FMI number. + * @retval None + */ +void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_FIFO(FIFONumber)); + /* Get the Id */ + RxMessage->IDE = (uint8_t)0x04 & CANx->sFIFOMailBox[FIFONumber].RIR; + if (RxMessage->IDE == CAN_Id_Standard) + { + RxMessage->StdId = (uint32_t)0x000007FF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 21); + } + else + { + RxMessage->ExtId = (uint32_t)0x1FFFFFFF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 3); + } + + RxMessage->RTR = (uint8_t)0x02 & CANx->sFIFOMailBox[FIFONumber].RIR; + /* Get the DLC */ + RxMessage->DLC = (uint8_t)0x0F & CANx->sFIFOMailBox[FIFONumber].RDTR; + /* Get the FMI */ + RxMessage->FMI = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDTR >> 8); + /* Get the data field */ + RxMessage->Data[0] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDLR; + RxMessage->Data[1] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 8); + RxMessage->Data[2] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 16); + RxMessage->Data[3] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 24); + RxMessage->Data[4] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDHR; + RxMessage->Data[5] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 8); + RxMessage->Data[6] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 16); + RxMessage->Data[7] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 24); + /* Release the FIFO */ + /* Release FIFO0 */ + if (FIFONumber == CAN_FIFO0) + { + CANx->RF0R |= CAN_RF0R_RFOM0; + } + /* Release FIFO1 */ + else /* FIFONumber == CAN_FIFO1 */ + { + CANx->RF1R |= CAN_RF1R_RFOM1; + } +} + +/** + * @brief Releases the specified receive FIFO. + * @param CANx: where x can be 1 to select the CAN1 peripheral. + * @param FIFONumber: FIFO to release, CAN_FIFO0 or CAN_FIFO1. + * @retval None + */ +void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_FIFO(FIFONumber)); + /* Release FIFO0 */ + if (FIFONumber == CAN_FIFO0) + { + CANx->RF0R |= CAN_RF0R_RFOM0; + } + /* Release FIFO1 */ + else /* FIFONumber == CAN_FIFO1 */ + { + CANx->RF1R |= CAN_RF1R_RFOM1; + } +} + +/** + * @brief Returns the number of pending received messages. + * @param CANx: where x can be 1 to select the CAN1 peripheral. + * @param FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. + * @retval NbMessage : which is the number of pending message. + */ +uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber) +{ + uint8_t message_pending=0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_FIFO(FIFONumber)); + if (FIFONumber == CAN_FIFO0) + { + message_pending = (uint8_t)(CANx->RF0R&(uint32_t)0x03); + } + else if (FIFONumber == CAN_FIFO1) + { + message_pending = (uint8_t)(CANx->RF1R&(uint32_t)0x03); + } + else + { + message_pending = 0; + } + return message_pending; +} +/** + * @} + */ + + +/** @defgroup CAN_Group4 CAN Operation modes functions + * @brief CAN Operation modes functions + * +@verbatim + =============================================================================== + ##### CAN Operation modes functions ##### + =============================================================================== + [..] This section provides functions allowing to select the CAN Operation modes: + (+) sleep mode. + (+) normal mode. + (+) initialization mode. + +@endverbatim + * @{ + */ + + +/** + * @brief Selects the CAN Operation mode. + * @param CAN_OperatingMode: CAN Operating Mode. + * This parameter can be one of @ref CAN_OperatingMode_TypeDef enumeration. + * @retval status of the requested mode which can be: + * - CAN_ModeStatus_Failed: CAN failed entering the specific mode + * - CAN_ModeStatus_Success: CAN Succeed entering the specific mode + */ +uint8_t CAN_OperatingModeRequest(CAN_TypeDef* CANx, uint8_t CAN_OperatingMode) +{ + uint8_t status = CAN_ModeStatus_Failed; + + /* Timeout for INAK or also for SLAK bits*/ + uint32_t timeout = INAK_TIMEOUT; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_OPERATING_MODE(CAN_OperatingMode)); + + if (CAN_OperatingMode == CAN_OperatingMode_Initialization) + { + /* Request initialisation */ + CANx->MCR = (uint32_t)((CANx->MCR & (uint32_t)(~(uint32_t)CAN_MCR_SLEEP)) | CAN_MCR_INRQ); + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_INAK) && (timeout != 0)) + { + timeout--; + } + if ((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_INAK) + { + status = CAN_ModeStatus_Failed; + } + else + { + status = CAN_ModeStatus_Success; + } + } + else if (CAN_OperatingMode == CAN_OperatingMode_Normal) + { + /* Request leave initialisation and sleep mode and enter Normal mode */ + CANx->MCR &= (uint32_t)(~(CAN_MCR_SLEEP|CAN_MCR_INRQ)); + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MODE_MASK) != 0) && (timeout!=0)) + { + timeout--; + } + if ((CANx->MSR & CAN_MODE_MASK) != 0) + { + status = CAN_ModeStatus_Failed; + } + else + { + status = CAN_ModeStatus_Success; + } + } + else if (CAN_OperatingMode == CAN_OperatingMode_Sleep) + { + /* Request Sleep mode */ + CANx->MCR = (uint32_t)((CANx->MCR & (uint32_t)(~(uint32_t)CAN_MCR_INRQ)) | CAN_MCR_SLEEP); + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_SLAK) && (timeout!=0)) + { + timeout--; + } + if ((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_SLAK) + { + status = CAN_ModeStatus_Failed; + } + else + { + status = CAN_ModeStatus_Success; + } + } + else + { + status = CAN_ModeStatus_Failed; + } + + return (uint8_t) status; +} + +/** + * @brief Enters the Sleep (low power) mode. + * @param CANx: where x can be 1 to select the CAN1 peripheral. + * @retval CAN_Sleep_Ok if sleep entered, CAN_Sleep_Failed otherwise. + */ +uint8_t CAN_Sleep(CAN_TypeDef* CANx) +{ + uint8_t sleepstatus = CAN_Sleep_Failed; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Request Sleep mode */ + CANx->MCR = (((CANx->MCR) & (uint32_t)(~(uint32_t)CAN_MCR_INRQ)) | CAN_MCR_SLEEP); + + /* Sleep mode status */ + if ((CANx->MSR & (CAN_MSR_SLAK|CAN_MSR_INAK)) == CAN_MSR_SLAK) + { + /* Sleep mode not entered */ + sleepstatus = CAN_Sleep_Ok; + } + /* return sleep mode status */ + return (uint8_t)sleepstatus; +} + +/** + * @brief Wakes up the CAN peripheral from sleep mode . + * @param CANx: where x can be 1 to select the CAN1 peripheral. + * @retval CAN_WakeUp_Ok if sleep mode left, CAN_WakeUp_Failed otherwise. + */ +uint8_t CAN_WakeUp(CAN_TypeDef* CANx) +{ + uint32_t wait_slak = SLAK_TIMEOUT; + uint8_t wakeupstatus = CAN_WakeUp_Failed; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Wake up request */ + CANx->MCR &= ~(uint32_t)CAN_MCR_SLEEP; + + /* Sleep mode status */ + while(((CANx->MSR & CAN_MSR_SLAK) == CAN_MSR_SLAK)&&(wait_slak!=0x00)) + { + wait_slak--; + } + if((CANx->MSR & CAN_MSR_SLAK) != CAN_MSR_SLAK) + { + /* wake up done : Sleep mode exited */ + wakeupstatus = CAN_WakeUp_Ok; + } + /* return wakeup status */ + return (uint8_t)wakeupstatus; +} +/** + * @} + */ + + +/** @defgroup CAN_Group5 CAN Bus Error management functions + * @brief CAN Bus Error management functions + * +@verbatim + =============================================================================== + ##### CAN Bus Error management functions ##### + =============================================================================== + [..] This section provides functions allowing to + (+) Return the CANx's last error code (LEC). + (+) Return the CANx Receive Error Counter (REC). + (+) Return the LSB of the 9-bit CANx Transmit Error Counter(TEC). + [..] + (@) If TEC is greater than 255, The CAN is in bus-off state. + (@) If REC or TEC are greater than 96, an Error warning flag occurs. + (@) If REC or TEC are greater than 127, an Error Passive Flag occurs. + +@endverbatim + * @{ + */ + +/** + * @brief Returns the CANx's last error code (LEC). + * @param CANx: where x can be 1 to select the CAN1 peripheral. + * @retval Error code: + * - CAN_ERRORCODE_NoErr: No Error + * - CAN_ERRORCODE_StuffErr: Stuff Error + * - CAN_ERRORCODE_FormErr: Form Error + * - CAN_ERRORCODE_ACKErr : Acknowledgment Error + * - CAN_ERRORCODE_BitRecessiveErr: Bit Recessive Error + * - CAN_ERRORCODE_BitDominantErr: Bit Dominant Error + * - CAN_ERRORCODE_CRCErr: CRC Error + * - CAN_ERRORCODE_SoftwareSetErr: Software Set Error + */ +uint8_t CAN_GetLastErrorCode(CAN_TypeDef* CANx) +{ + uint8_t errorcode=0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Get the error code*/ + errorcode = (((uint8_t)CANx->ESR) & (uint8_t)CAN_ESR_LEC); + + /* Return the error code*/ + return errorcode; +} + +/** + * @brief Returns the CANx Receive Error Counter (REC). + * @note In case of an error during reception, this counter is incremented + * by 1 or by 8 depending on the error condition as defined by the CAN + * standard. After every successful reception, the counter is + * decremented by 1 or reset to 120 if its value was higher than 128. + * When the counter value exceeds 127, the CAN controller enters the + * error passive state. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval CAN Receive Error Counter. + */ +uint8_t CAN_GetReceiveErrorCounter(CAN_TypeDef* CANx) +{ + uint8_t counter=0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Get the Receive Error Counter*/ + counter = (uint8_t)((CANx->ESR & CAN_ESR_REC)>> 24); + + /* Return the Receive Error Counter*/ + return counter; +} + + +/** + * @brief Returns the LSB of the 9-bit CANx Transmit Error Counter(TEC). + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval LSB of the 9-bit CAN Transmit Error Counter. + */ +uint8_t CAN_GetLSBTransmitErrorCounter(CAN_TypeDef* CANx) +{ + uint8_t counter=0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Get the LSB of the 9-bit CANx Transmit Error Counter(TEC) */ + counter = (uint8_t)((CANx->ESR & CAN_ESR_TEC)>> 16); + + /* Return the LSB of the 9-bit CANx Transmit Error Counter(TEC) */ + return counter; +} +/** + * @} + */ + +/** @defgroup CAN_Group6 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + ##### Interrupts and flags management functions ##### + =============================================================================== + [..] This section provides functions allowing to configure the CAN Interrupts + and to get the status and clear flags and Interrupts pending bits. + [..] The CAN provides 14 Interrupts sources and 15 Flags: + + *** Flags *** + ============= + [..] The 15 flags can be divided on 4 groups: + (+) Transmit Flags: + (++) CAN_FLAG_RQCP0. + (++) CAN_FLAG_RQCP1. + (++) CAN_FLAG_RQCP2: Request completed MailBoxes 0, 1 and 2 Flags + Set when when the last request (transmit or abort) has + been performed. + (+) Receive Flags: + (++) CAN_FLAG_FMP0. + (++) CAN_FLAG_FMP1: FIFO 0 and 1 Message Pending Flags; + Set to signal that messages are pending in the receive FIFO. + These Flags are cleared only by hardware. + (++) CAN_FLAG_FF0. + (++) CAN_FLAG_FF1: FIFO 0 and 1 Full Flags; + Set when three messages are stored in the selected FIFO. + (++) CAN_FLAG_FOV0. + (++) CAN_FLAG_FOV1: FIFO 0 and 1 Overrun Flags; + Set when a new message has been received and passed the filter + while the FIFO was full. + (+) Operating Mode Flags: + (++) CAN_FLAG_WKU: Wake up Flag; + Set to signal that a SOF bit has been detected while the CAN + hardware was in Sleep mode. + (++) CAN_FLAG_SLAK: Sleep acknowledge Flag; + Set to signal that the CAN has entered Sleep Mode. + (+) Error Flags: + (++) CAN_FLAG_EWG: Error Warning Flag; + Set when the warning limit has been reached (Receive Error Counter + or Transmit Error Counter greater than 96). + This Flag is cleared only by hardware. + (++) CAN_FLAG_EPV: Error Passive Flag; + Set when the Error Passive limit has been reached (Receive Error + Counter or Transmit Error Counter greater than 127). + This Flag is cleared only by hardware. + (++) CAN_FLAG_BOF: Bus-Off Flag; + Set when CAN enters the bus-off state. The bus-off state is + entered on TEC overflow, greater than 255. + This Flag is cleared only by hardware. + (++) CAN_FLAG_LEC: Last error code Flag; + Set If a message has been transferred (reception or transmission) + with error, and the error code is hold. + + *** Interrupts *** + ================== + [..] The 14 interrupts can be divided on 4 groups: + (+) Transmit interrupt: + (++) CAN_IT_TME: Transmit mailbox empty Interrupt; + If enabled, this interrupt source is pending when no transmit + request are pending for Tx mailboxes. + (+) Receive Interrupts: + (++) CAN_IT_FMP0. + (++) CAN_IT_FMP1: FIFO 0 and FIFO1 message pending Interrupts; + If enabled, these interrupt sources are pending when messages + are pending in the receive FIFO. + The corresponding interrupt pending bits are cleared only by hardware. + (++) CAN_IT_FF0. + (++) CAN_IT_FF1: FIFO 0 and FIFO1 full Interrupts; + If enabled, these interrupt sources are pending when three messages + are stored in the selected FIFO. + (++) CAN_IT_FOV0. + (++) CAN_IT_FOV1: FIFO 0 and FIFO1 overrun Interrupts; + If enabled, these interrupt sources are pending when a new message + has been received and passed the filter while the FIFO was full. + (+) Operating Mode Interrupts: + (++) CAN_IT_WKU: Wake-up Interrupt; + If enabled, this interrupt source is pending when a SOF bit has + been detected while the CAN hardware was in Sleep mode. + (++) CAN_IT_SLK: Sleep acknowledge Interrupt: + If enabled, this interrupt source is pending when the CAN has + entered Sleep Mode. + (+) Error Interrupts: + (++) CAN_IT_EWG: Error warning Interrupt; + If enabled, this interrupt source is pending when the warning limit + has been reached (Receive Error Counter or Transmit Error Counter=96). + (++) CAN_IT_EPV: Error passive Interrupt; + If enabled, this interrupt source is pending when the Error Passive + limit has been reached (Receive Error Counter or Transmit Error Counter>127). + (++) CAN_IT_BOF: Bus-off Interrupt; + If enabled, this interrupt source is pending when CAN enters + the bus-off state. The bus-off state is entered on TEC overflow, + greater than 255. + This Flag is cleared only by hardware. + (++) CAN_IT_LEC: Last error code Interrupt; + If enabled, this interrupt source is pending when a message has + been transferred (reception or transmission) with error and the + error code is hold. + (++) CAN_IT_ERR: Error Interrupt; + If enabled, this interrupt source is pending when an error condition + is pending. + [..] Managing the CAN controller events: + The user should identify which mode will be used in his application to manage + the CAN controller events: Polling mode or Interrupt mode. + (+) In the Polling Mode it is advised to use the following functions: + (++) CAN_GetFlagStatus() : to check if flags events occur. + (++) CAN_ClearFlag() : to clear the flags events. + (+) In the Interrupt Mode it is advised to use the following functions: + (++) CAN_ITConfig() : to enable or disable the interrupt source. + (++) CAN_GetITStatus() : to check if Interrupt occurs. + (++) CAN_ClearITPendingBit() : to clear the Interrupt pending Bit + (corresponding Flag). + This function has no impact on CAN_IT_FMP0 and CAN_IT_FMP1 Interrupts + pending bits since there are cleared only by hardware. + +@endverbatim + * @{ + */ +/** + * @brief Enables or disables the specified CANx interrupts. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_IT: specifies the CAN interrupt sources to be enabled or disabled. + * This parameter can be: + * @arg CAN_IT_TME: Transmit mailbox empty Interrupt + * @arg CAN_IT_FMP0: FIFO 0 message pending Interrupt + * @arg CAN_IT_FF0: FIFO 0 full Interrupt + * @arg CAN_IT_FOV0: FIFO 0 overrun Interrupt + * @arg CAN_IT_FMP1: FIFO 1 message pending Interrupt + * @arg CAN_IT_FF1: FIFO 1 full Interrupt + * @arg CAN_IT_FOV1: FIFO 1 overrun Interrupt + * @arg CAN_IT_WKU: Wake-up Interrupt + * @arg CAN_IT_SLK: Sleep acknowledge Interrupt + * @arg CAN_IT_EWG: Error warning Interrupt + * @arg CAN_IT_EPV: Error passive Interrupt + * @arg CAN_IT_BOF: Bus-off Interrupt + * @arg CAN_IT_LEC: Last error code Interrupt + * @arg CAN_IT_ERR: Error Interrupt + * @param NewState: new state of the CAN interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_IT(CAN_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected CANx interrupt */ + CANx->IER |= CAN_IT; + } + else + { + /* Disable the selected CANx interrupt */ + CANx->IER &= ~CAN_IT; + } +} +/** + * @brief Checks whether the specified CAN flag is set or not. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg CAN_FLAG_RQCP0: Request MailBox0 Flag + * @arg CAN_FLAG_RQCP1: Request MailBox1 Flag + * @arg CAN_FLAG_RQCP2: Request MailBox2 Flag + * @arg CAN_FLAG_FMP0: FIFO 0 Message Pending Flag + * @arg CAN_FLAG_FF0: FIFO 0 Full Flag + * @arg CAN_FLAG_FOV0: FIFO 0 Overrun Flag + * @arg CAN_FLAG_FMP1: FIFO 1 Message Pending Flag + * @arg CAN_FLAG_FF1: FIFO 1 Full Flag + * @arg CAN_FLAG_FOV1: FIFO 1 Overrun Flag + * @arg CAN_FLAG_WKU: Wake up Flag + * @arg CAN_FLAG_SLAK: Sleep acknowledge Flag + * @arg CAN_FLAG_EWG: Error Warning Flag + * @arg CAN_FLAG_EPV: Error Passive Flag + * @arg CAN_FLAG_BOF: Bus-Off Flag + * @arg CAN_FLAG_LEC: Last error code Flag + * @retval The new state of CAN_FLAG (SET or RESET). + */ +FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_GET_FLAG(CAN_FLAG)); + + + if((CAN_FLAG & CAN_FLAGS_ESR) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->ESR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else if((CAN_FLAG & CAN_FLAGS_MSR) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->MSR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else if((CAN_FLAG & CAN_FLAGS_TSR) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->TSR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else if((CAN_FLAG & CAN_FLAGS_RF0R) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->RF0R & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else /* If(CAN_FLAG & CAN_FLAGS_RF1R != (uint32_t)RESET) */ + { + /* Check the status of the specified CAN flag */ + if ((uint32_t)(CANx->RF1R & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + /* Return the CAN_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the CAN's pending flags. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_FLAG: specifies the flag to clear. + * This parameter can be one of the following values: + * @arg CAN_FLAG_RQCP0: Request MailBox0 Flag + * @arg CAN_FLAG_RQCP1: Request MailBox1 Flag + * @arg CAN_FLAG_RQCP2: Request MailBox2 Flag + * @arg CAN_FLAG_FF0: FIFO 0 Full Flag + * @arg CAN_FLAG_FOV0: FIFO 0 Overrun Flag + * @arg CAN_FLAG_FF1: FIFO 1 Full Flag + * @arg CAN_FLAG_FOV1: FIFO 1 Overrun Flag + * @arg CAN_FLAG_WKU: Wake up Flag + * @arg CAN_FLAG_SLAK: Sleep acknowledge Flag + * @arg CAN_FLAG_LEC: Last error code Flag + * @retval None + */ +void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG) +{ + uint32_t flagtmp=0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_CLEAR_FLAG(CAN_FLAG)); + + if (CAN_FLAG == CAN_FLAG_LEC) /* ESR register */ + { + /* Clear the selected CAN flags */ + CANx->ESR = (uint32_t)RESET; + } + else /* MSR or TSR or RF0R or RF1R */ + { + flagtmp = CAN_FLAG & 0x000FFFFF; + + if ((CAN_FLAG & CAN_FLAGS_RF0R)!=(uint32_t)RESET) + { + /* Receive Flags */ + CANx->RF0R = (uint32_t)(flagtmp); + } + else if ((CAN_FLAG & CAN_FLAGS_RF1R)!=(uint32_t)RESET) + { + /* Receive Flags */ + CANx->RF1R = (uint32_t)(flagtmp); + } + else if ((CAN_FLAG & CAN_FLAGS_TSR)!=(uint32_t)RESET) + { + /* Transmit Flags */ + CANx->TSR = (uint32_t)(flagtmp); + } + else /* If((CAN_FLAG & CAN_FLAGS_MSR)!=(uint32_t)RESET) */ + { + /* Operating mode Flags */ + CANx->MSR = (uint32_t)(flagtmp); + } + } +} + +/** + * @brief Checks whether the specified CANx interrupt has occurred or not. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_IT: specifies the CAN interrupt source to check. + * This parameter can be one of the following values: + * @arg CAN_IT_TME: Transmit mailbox empty Interrupt + * @arg CAN_IT_FMP0: FIFO 0 message pending Interrupt + * @arg CAN_IT_FF0: FIFO 0 full Interrupt + * @arg CAN_IT_FOV0: FIFO 0 overrun Interrupt + * @arg CAN_IT_FMP1: FIFO 1 message pending Interrupt + * @arg CAN_IT_FF1: FIFO 1 full Interrupt + * @arg CAN_IT_FOV1: FIFO 1 overrun Interrupt + * @arg CAN_IT_WKU: Wake-up Interrupt + * @arg CAN_IT_SLK: Sleep acknowledge Interrupt + * @arg CAN_IT_EWG: Error warning Interrupt + * @arg CAN_IT_EPV: Error passive Interrupt + * @arg CAN_IT_BOF: Bus-off Interrupt + * @arg CAN_IT_LEC: Last error code Interrupt + * @arg CAN_IT_ERR: Error Interrupt + * @retval The current state of CAN_IT (SET or RESET). + */ +ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT) +{ + ITStatus itstatus = RESET; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_IT(CAN_IT)); + + /* check the interrupt enable bit */ + if((CANx->IER & CAN_IT) != RESET) + { + /* in case the Interrupt is enabled, .... */ + switch (CAN_IT) + { + case CAN_IT_TME: + /* Check CAN_TSR_RQCPx bits */ + itstatus = CheckITStatus(CANx->TSR, CAN_TSR_RQCP0|CAN_TSR_RQCP1|CAN_TSR_RQCP2); + break; + case CAN_IT_FMP0: + /* Check CAN_RF0R_FMP0 bit */ + itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FMP0); + break; + case CAN_IT_FF0: + /* Check CAN_RF0R_FULL0 bit */ + itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FULL0); + break; + case CAN_IT_FOV0: + /* Check CAN_RF0R_FOVR0 bit */ + itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FOVR0); + break; + case CAN_IT_FMP1: + /* Check CAN_RF1R_FMP1 bit */ + itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FMP1); + break; + case CAN_IT_FF1: + /* Check CAN_RF1R_FULL1 bit */ + itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FULL1); + break; + case CAN_IT_FOV1: + /* Check CAN_RF1R_FOVR1 bit */ + itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FOVR1); + break; + case CAN_IT_WKU: + /* Check CAN_MSR_WKUI bit */ + itstatus = CheckITStatus(CANx->MSR, CAN_MSR_WKUI); + break; + case CAN_IT_SLK: + /* Check CAN_MSR_SLAKI bit */ + itstatus = CheckITStatus(CANx->MSR, CAN_MSR_SLAKI); + break; + case CAN_IT_EWG: + /* Check CAN_ESR_EWGF bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EWGF); + break; + case CAN_IT_EPV: + /* Check CAN_ESR_EPVF bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EPVF); + break; + case CAN_IT_BOF: + /* Check CAN_ESR_BOFF bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_BOFF); + break; + case CAN_IT_LEC: + /* Check CAN_ESR_LEC bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_LEC); + break; + case CAN_IT_ERR: + /* Check CAN_MSR_ERRI bit */ + itstatus = CheckITStatus(CANx->MSR, CAN_MSR_ERRI); + break; + default: + /* in case of error, return RESET */ + itstatus = RESET; + break; + } + } + else + { + /* in case the Interrupt is not enabled, return RESET */ + itstatus = RESET; + } + + /* Return the CAN_IT status */ + return itstatus; +} + +/** + * @brief Clears the CANx's interrupt pending bits. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_IT: specifies the interrupt pending bit to clear. + * This parameter can be one of the following values: + * @arg CAN_IT_TME: Transmit mailbox empty Interrupt + * @arg CAN_IT_FF0: FIFO 0 full Interrupt + * @arg CAN_IT_FOV0: FIFO 0 overrun Interrupt + * @arg CAN_IT_FF1: FIFO 1 full Interrupt + * @arg CAN_IT_FOV1: FIFO 1 overrun Interrupt + * @arg CAN_IT_WKU: Wake-up Interrupt + * @arg CAN_IT_SLK: Sleep acknowledge Interrupt + * @arg CAN_IT_EWG: Error warning Interrupt + * @arg CAN_IT_EPV: Error passive Interrupt + * @arg CAN_IT_BOF: Bus-off Interrupt + * @arg CAN_IT_LEC: Last error code Interrupt + * @arg CAN_IT_ERR: Error Interrupt + * @retval None + */ +void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_CLEAR_IT(CAN_IT)); + + switch (CAN_IT) + { + case CAN_IT_TME: + /* Clear CAN_TSR_RQCPx (rc_w1)*/ + CANx->TSR = CAN_TSR_RQCP0|CAN_TSR_RQCP1|CAN_TSR_RQCP2; + break; + case CAN_IT_FF0: + /* Clear CAN_RF0R_FULL0 (rc_w1)*/ + CANx->RF0R = CAN_RF0R_FULL0; + break; + case CAN_IT_FOV0: + /* Clear CAN_RF0R_FOVR0 (rc_w1)*/ + CANx->RF0R = CAN_RF0R_FOVR0; + break; + case CAN_IT_FF1: + /* Clear CAN_RF1R_FULL1 (rc_w1)*/ + CANx->RF1R = CAN_RF1R_FULL1; + break; + case CAN_IT_FOV1: + /* Clear CAN_RF1R_FOVR1 (rc_w1)*/ + CANx->RF1R = CAN_RF1R_FOVR1; + break; + case CAN_IT_WKU: + /* Clear CAN_MSR_WKUI (rc_w1)*/ + CANx->MSR = CAN_MSR_WKUI; + break; + case CAN_IT_SLK: + /* Clear CAN_MSR_SLAKI (rc_w1)*/ + CANx->MSR = CAN_MSR_SLAKI; + break; + case CAN_IT_EWG: + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* @note the corresponding Flag is cleared by hardware depending on the CAN Bus status*/ + break; + case CAN_IT_EPV: + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* @note the corresponding Flag is cleared by hardware depending on the CAN Bus status*/ + break; + case CAN_IT_BOF: + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* @note the corresponding Flag is cleared by hardware depending on the CAN Bus status*/ + break; + case CAN_IT_LEC: + /* Clear LEC bits */ + CANx->ESR = RESET; + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + break; + case CAN_IT_ERR: + /*Clear LEC bits */ + CANx->ESR = RESET; + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* @note BOFF, EPVF and EWGF Flags are cleared by hardware depending on the CAN Bus status*/ + break; + default: + break; + } +} + /** + * @} + */ + +/** + * @brief Checks whether the CAN interrupt has occurred or not. + * @param CAN_Reg: specifies the CAN interrupt register to check. + * @param It_Bit: specifies the interrupt source bit to check. + * @retval The new state of the CAN Interrupt (SET or RESET). + */ +static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit) +{ + ITStatus pendingbitstatus = RESET; + + if ((CAN_Reg & It_Bit) != (uint32_t)RESET) + { + /* CAN_IT is set */ + pendingbitstatus = SET; + } + else + { + /* CAN_IT is reset */ + pendingbitstatus = RESET; + } + return pendingbitstatus; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_comp.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_comp.c new file mode 100644 index 0000000..588b2c4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_comp.c @@ -0,0 +1,504 @@ +/** + ****************************************************************************** + * @file stm32f30x_comp.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the 7 analog comparators (COMP1, COMP2...COMP7) peripheral: + * + Comparators configuration + * + Window mode control + * + @verbatim + + ============================================================================== + ##### COMP Peripheral features ##### + ============================================================================== + [..] + The device integrates 7 analog comparators COMP1, COMP2...COMP7: + (#) The non inverting input and inverting input can be set to GPIO pins + as shown in table1. COMP Inputs below. + + (#) The COMP output is internally is available using COMP_GetOutputLevel() + and can be set on GPIO pins. Refer to table 2. COMP Outputs below. + + (#) The COMP output can be redirected to embedded timers (TIM1, TIM2, TIM3...) + Refer to table 3. COMP Outputs redirection to embedded timers below. + + (#) The comparators COMP1 and COMP2, COMP3 and COMP4, COMP5 and COMP6 can be combined in window + mode and only COMP1, COMP3 and COMP5 non inverting input can be used as non-inverting input. + + (#) The seven comparators have interrupt capability with wake-up + from Sleep and Stop modes (through the EXTI controller): + (++) COMP1 is internally connected to EXTI Line 21 + (++) COMP2 is internally connected to EXTI Line 22 + (++) COMP3 is internally connected to EXTI Line 29 + (++) COMP4 is internally connected to EXTI Line 30 + (++) COMP5 is internally connected to EXTI Line 31 + (++) COMP6 is internally connected to EXTI Line 32 + (++) COMP7 is internally connected to EXTI Line 33 + + [..] Table 1. COMP Inputs + +------------------------------------------------------------------------------------------+ + | | | COMP1 | COMP2 | COMP3 | COMP4 | COMP5 | COMP6 | COMP7 | + |-----------------|----------------|---------------|---------------------------------------| + | | 1/4 VREFINT | OK | OK | OK | OK | OK | OK | OK | + | | 1/2 VREFINT | OK | OK | OK | OK | OK | OK | OK | + | | 3/4 VREFINT | OK | OK | OK | OK | OK | OK | OK | + | Inverting Input | VREFINT | OK | OK | OK | OK | OK | OK | OK | + | | DAC1 OUT1(PA4) | OK | OK | OK | OK | OK | OK | OK | + | | DAC1 OUT2(PA5) | OK | OK | OK | OK | OK | OK | OK | + | | IO1 | PA0 | PA2 | PD15 | PE8 | PD13 | PD10 | PC0 | + | | IO2 | --- | --- | PB12 | PB2 | PB10 | PB15 | --- | + | | DAC2 OUT1(PA6) | --- | OK | --- | OK | --- | OK | --- | + |-----------------|----------------|-------|-------|-------|-------|-------|-------|-------| + | Non Inverting | IO1 | PA1 | PA7 | PB14 | PB0 | PD12 | PD11 | PA0 | + | Input | IO2 | --- | PA3 | PD14 | PE7 | PB13 | PB11 | PC1 | + +------------------------------------------------------------------------------------------+ + + [..] Table 2. COMP Outputs + +-------------------------------------------------------+ + | COMP1 | COMP2 | COMP3 | COMP4 | COMP5 | COMP6 | COMP7 | + |-------|-------|-------|-------|-------|-------|-------| + | PA0 | PA2 | PB1 | PC8 | PC7 | PA10 | PC2 | + | PF4 | PA7 | --- | PA8 | PA9 | PC6 | --- | + | PA6 | PA12 | --- | --- | --- | --- | --- | + | PA11 | PB9 | --- | --- | --- | --- | --- | + | PB8 | --- | --- | --- | --- | --- | --- | + +-------------------------------------------------------+ + + [..] Table 3. COMP Outputs redirection to embedded timers + +----------------------------------------------------------------------------------------------------------------------+ + | COMP1 | COMP2 | COMP3 | COMP4 | COMP5 | COMP6 | COMP7 | + |----------------|----------------|----------------|----------------|----------------|----------------|----------------| + | TIM1 BKIN | TIM1 BKIN | TIM1 BKIN | TIM1 BKIN | TIM1 BKIN | TIM1 BKIN | TIM1 BKIN | + | | | | | | | | + | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | + | | | | | | | | + | TIM8 BKIN | TIM8 BKIN | TIM8 BKIN | TIM8 BKIN | TIM8 BKIN | TIM8 BKIN | TIM8 BKIN | + | | | | | | | | + | TIM8 BKIN2 | TIM8 BKIN2 | TIM8 BKIN2 | TIM8 BKIN2 | TIM8 BKIN2 | TIM8 BKIN2 | TIM8 BKIN2 | + | | | | | | | | + | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | TIM1 BKIN2 | + | + | + | + | + | + | + | + | + | TIM8BKIN2 | TIM8BKIN2 | TIM8BKIN2 | TIM8BKIN2 | TIM8BKIN2 | TIM8BKIN2 | TIM8BKIN2 | + | | | | | | | | + | TIM1 OCREFCLR | TIM1 OCREFCLR | TIM1 OCREFCLR | TIM8 OCREFCLR | TIM8 OCREFCLR | TIM8 OCREFCLR | TIM1 OCREFCLR | + | | | | | | | | + | TIM1 IC1 | TIM1 IC1 | TIM2 OCREFCLR | TIM3 IC3 | TIM2 IC1 | TIM2 IC2 | TIM8 OCREFCLR | + | | | | | | | | + | TIM2 IC4 | TIM2 IC4 | TIM3 IC2 | TIM3 OCREFCLR | TIM3 OCREFCLR | TIM2 OCREFCLR | TIM2 IC3 | + | | | | | | | | + | TIM2 OCREFCLR | TIM2 OCREFCLR | TIM4 IC1 | TIM4 IC2 | TIM4 IC3 | TIM16 OCREFCLR| TIM1 IC2 | + | | | | | | | | + | TIM3 IC1 | TIM3 IC1 | TIM15 IC1 | TIM15 OCREFCLR| TIM16 BKIN | TIM16 IC1 | TIM17 OCREFCLR| + | | | | | | | | + | TIM3 OCREFCLR | TIM3 OCREFCLR | TIM15 BKIN | TIM15 IC2 | TIM17 IC1 | TIM4 IC4 | TIM17 BKIN | + +----------------------------------------------------------------------------------------------------------------------+ + + [..] Table 4. COMP Outputs blanking sources + +----------------------------------------------------------------------------------------------------------------------+ + | COMP1 | COMP2 | COMP3 | COMP4 | COMP5 | COMP6 | COMP7 | + |----------------|----------------|----------------|----------------|----------------|----------------|----------------| + | TIM1 OC5 | TIM1 OC5 | TIM1 OC5 | TIM3 OC4 | TIM3 OC3 | TIM2 OC4 | TIM1 OC5 | + | | | | | | | | + | TIM2 OC3 | TIM2 OC3 | -------- | TIM8 OC5 | TIM8 OC5 | TIM8 OC5 | TIM8 OC5 | + | | | | | | | | + | TIM3 OC3 | TIM3 OC3 | TIM2 OC4 | TIM15 OC1 | TIM8 BKIN | TIM15 OC2 | TIM15 OC2 | + | | | | | | | | + +----------------------------------------------------------------------------------------------------------------------+ + + + ##### How to use this driver ##### + ============================================================================== + [..] + This driver provides functions to configure and program the Comparators + of all STM32F30x devices. + + To use the comparator, perform the following steps: + + (#) Enable the SYSCFG APB clock to get write access to comparator + register using RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); + + (#) Configure the comparator input in analog mode using GPIO_Init() + + (#) Configure the comparator output in alternate function mode + using GPIO_Init() and use GPIO_PinAFConfig() function to map the + comparator output to the GPIO pin + + (#) Configure the comparator using COMP_Init() function: + (++) Select the inverting input + (++) Select the non-inverting input + (++) Select the output polarity + (++) Select the output redirection + (++) Select the hysteresis level + (++) Select the power mode + + (#) Enable the comparator using COMP_Cmd() function + + (#) If required enable the COMP interrupt by configuring and enabling + EXTI line in Interrupt mode and selecting the desired sensitivity + level using EXTI_Init() function. After that enable the comparator + interrupt vector using NVIC_Init() function. + + @endverbatim + * + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_comp.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup COMP + * @brief COMP driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* CSR register Mask */ +#define COMP_CSR_CLEAR_MASK ((uint32_t)0x00000003) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup COMP_Private_Functions + * @{ + */ + +/** @defgroup COMP_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes COMP peripheral registers to their default reset values. + * @note Deinitialization can't be performed if the COMP configuration is locked. + * To unlock the configuration, perform a system reset. + * @param COMP_Selection: the selected comparator. + * This parameter can be COMP_Selection_COMPx where x can be 1 to 7 + * to select the COMP peripheral. + * @param None + * @retval None + */ +void COMP_DeInit(uint32_t COMP_Selection) +{ + /*!< Set COMP_CSR register to reset value */ + *(__IO uint32_t *) (COMP_BASE + COMP_Selection) = ((uint32_t)0x00000000); +} + +/** + * @brief Initializes the COMP peripheral according to the specified parameters + * in COMP_InitStruct + * @note If the selected comparator is locked, initialization can't be performed. + * To unlock the configuration, perform a system reset. + * @note By default, PA1 is selected as COMP1 non inverting input. + * To use PA4 as COMP1 non inverting input call COMP_SwitchCmd() after COMP_Init() + * @param COMP_Selection: the selected comparator. + * This parameter can be COMP_Selection_COMPx where x can be 1 to 7 + * to select the COMP peripheral. + * @param COMP_InitStruct: pointer to an COMP_InitTypeDef structure that contains + * the configuration information for the specified COMP peripheral. + * - COMP_InvertingInput specifies the inverting input of COMP + * - COMP_NonInvertingInput specifies the non inverting input of COMP + * - COMP_Output connect COMP output to selected timer + * input (Input capture / Output Compare Reference Clear / Break Input) + * - COMP_BlankingSrce specifies the blanking source of COMP + * - COMP_OutputPol select output polarity + * - COMP_Hysteresis configures COMP hysteresis value + * - COMP_Mode configures COMP power mode + * @retval None + */ +void COMP_Init(uint32_t COMP_Selection, COMP_InitTypeDef* COMP_InitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_COMP_ALL_PERIPH(COMP_Selection)); + assert_param(IS_COMP_INVERTING_INPUT(COMP_InitStruct->COMP_InvertingInput)); + assert_param(IS_COMP_NONINVERTING_INPUT(COMP_InitStruct->COMP_NonInvertingInput)); + assert_param(IS_COMP_OUTPUT(COMP_InitStruct->COMP_Output)); + assert_param(IS_COMP_BLANKING_SOURCE(COMP_InitStruct->COMP_BlankingSrce)); + assert_param(IS_COMP_OUTPUT_POL(COMP_InitStruct->COMP_OutputPol)); + assert_param(IS_COMP_HYSTERESIS(COMP_InitStruct->COMP_Hysteresis)); + assert_param(IS_COMP_MODE(COMP_InitStruct->COMP_Mode)); + + /*!< Get the COMPx_CSR register value */ + tmpreg = *(__IO uint32_t *) (COMP_BASE + COMP_Selection); + + /*!< Clear the COMP1SW1, COMPxINSEL, COMPxOUTSEL, COMPxPOL, COMPxHYST and COMPxMODE bits */ + tmpreg &= (uint32_t) (COMP_CSR_CLEAR_MASK); + + /*!< Configure COMP: inverting input, output redirection, hysteresis value and power mode */ + /*!< Set COMPxINSEL bits according to COMP_InitStruct->COMP_InvertingInput value */ + /*!< Set COMPxNONINSEL bits according to COMP_InitStruct->COMP_NonInvertingInput value */ + /*!< Set COMPxBLANKING bits according to COMP_InitStruct->COMP_BlankingSrce value */ + /*!< Set COMPxOUTSEL bits according to COMP_InitStruct->COMP_Output value */ + /*!< Set COMPxPOL bit according to COMP_InitStruct->COMP_OutputPol value */ + /*!< Set COMPxHYST bits according to COMP_InitStruct->COMP_Hysteresis value */ + /*!< Set COMPxMODE bits according to COMP_InitStruct->COMP_Mode value */ + tmpreg |= (uint32_t)(COMP_InitStruct->COMP_InvertingInput | COMP_InitStruct->COMP_NonInvertingInput | + COMP_InitStruct->COMP_Output | COMP_InitStruct->COMP_OutputPol | COMP_InitStruct->COMP_BlankingSrce | + COMP_InitStruct->COMP_Hysteresis | COMP_InitStruct->COMP_Mode); + + /*!< Write to COMPx_CSR register */ + *(__IO uint32_t *) (COMP_BASE + COMP_Selection) = tmpreg; +} + +/** + * @brief Fills each COMP_InitStruct member with its default value. + * @param COMP_InitStruct: pointer to an COMP_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void COMP_StructInit(COMP_InitTypeDef* COMP_InitStruct) +{ + COMP_InitStruct->COMP_InvertingInput = COMP_InvertingInput_1_4VREFINT; + COMP_InitStruct->COMP_NonInvertingInput = COMP_NonInvertingInput_IO1; + COMP_InitStruct->COMP_Output = COMP_Output_None; + COMP_InitStruct->COMP_BlankingSrce = COMP_BlankingSrce_None; + COMP_InitStruct->COMP_OutputPol = COMP_OutputPol_NonInverted; + COMP_InitStruct->COMP_Hysteresis = COMP_Hysteresis_No; + COMP_InitStruct->COMP_Mode = COMP_Mode_UltraLowPower; +} + +/** + * @brief Enable or disable the COMP peripheral. + * @note If the selected comparator is locked, enable/disable can't be performed. + * To unlock the configuration, perform a system reset. + * @param COMP_Selection: the selected comparator. + * This parameter can be COMP_Selection_COMPx where x can be 1 to 7 + * to select the COMP peripheral. + * @param NewState: new state of the COMP peripheral. + * This parameter can be: ENABLE or DISABLE. + * When enabled, the comparator compares the non inverting input with + * the inverting input and the comparison result is available + * on comparator output. + * When disabled, the comparator doesn't perform comparison and the + * output level is low. + * @retval None + */ +void COMP_Cmd(uint32_t COMP_Selection, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_COMP_ALL_PERIPH(COMP_Selection)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected COMPx peripheral */ + *(__IO uint32_t *) (COMP_BASE + COMP_Selection) |= (uint32_t) (COMP_CSR_COMPxEN); + } + else + { + /* Disable the selected COMP peripheral */ + *(__IO uint32_t *) (COMP_BASE + COMP_Selection) &= (uint32_t)(~COMP_CSR_COMPxEN); + } +} + +/** + * @brief Close or Open the SW1 switch. + * @note If the COMP1 is locked, Close/Open the SW1 switch can't be performed. + * To unlock the configuration, perform a system reset. + * @note This switch is solely intended to redirect signals onto high + * impedance input, such as COMP1 non-inverting input (highly resistive switch) + * @param NewState: New state of the analog switch. + * This parameter can be + * ENABLE so the SW1 is closed; PA1 is connected to PA4 + * or DISABLE so the SW1 switch is open; PA1 is disconnected from PA4 + * @retval None + */ +void COMP_SwitchCmd(uint32_t COMP_Selection, FunctionalState NewState) +{ + /* Check the parameter */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Close SW1 switch */ + *(__IO uint32_t *) (COMP_BASE + COMP_Selection) |= (uint32_t) (COMP_CSR_COMP1SW1); + } + else + { + /* Open SW1 switch */ + *(__IO uint32_t *) (COMP_BASE + COMP_Selection) &= (uint32_t)(~COMP_CSR_COMP1SW1); + } +} + +/** + * @brief Return the output level (high or low) of the selected comparator. + * The output level depends on the selected polarity. + * If the polarity is not inverted: + * - Comparator output is low when the non-inverting input is at a lower + * voltage than the inverting input + * - Comparator output is high when the non-inverting input is at a higher + * voltage than the inverting input + * If the polarity is inverted: + * - Comparator output is high when the non-inverting input is at a lower + * voltage than the inverting input + * - Comparator output is low when the non-inverting input is at a higher + * voltage than the inverting input + * @param COMP_Selection: the selected comparator. + * This parameter can be COMP_Selection_COMPx where x can be 1 to 7 + * to select the COMP peripheral. + * @retval Returns the selected comparator output level: low or high. + * + */ +uint32_t COMP_GetOutputLevel(uint32_t COMP_Selection) +{ + uint32_t compout = 0x0; + + /* Check the parameters */ + assert_param(IS_COMP_ALL_PERIPH(COMP_Selection)); + + /* Check if selected comparator output is high */ + if ((*(__IO uint32_t *) (COMP_BASE + COMP_Selection) & (COMP_CSR_COMPxOUT)) != 0) + { + compout = COMP_OutputLevel_High; + } + else + { + compout = COMP_OutputLevel_Low; + } + + /* Return the comparator output level */ + return (uint32_t)(compout); +} + +/** + * @} + */ + +/** @defgroup COMP_Group2 Window mode control function + * @brief Window mode control function + * +@verbatim + =============================================================================== + ##### Window mode control function ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the window mode. + * Window mode for comparators makes use of two comparators: + * COMP1 and COM2, COMP3 and COMP4, COMP5 and COMP6. + * In window mode, COMPx and COMPx-1 (where x can be 2, 4 or 6) + * non inverting inputs are connected together and only COMPx-1 non + * inverting input can be used. + * e.g When window mode enabled for COMP4, COMP3 non inverting input (PB14 or PD14) + * is to be used. + * @note If the COMPx is locked, ENABLE/DISABLE the window mode can't be performed. + * To unlock the configuration, perform a system reset. + * @param COMP_Selection: the selected comparator. + * This parameter can be COMP_Selection_COMPx where x can be 2, 4 or 6 + * to select the COMP peripheral. + * param NewState: new state of the window mode. + * This parameter can be ENABLE or DISABLE. + * When enbaled, COMPx and COMPx-1 non inverting inputs are connected together. + * When disabled, COMPx and COMPx-1 non inverting inputs are disconnected. + * @retval None + */ +void COMP_WindowCmd(uint32_t COMP_Selection, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_COMP_WINDOW(COMP_Selection)); + + if (NewState != DISABLE) + { + /* Enable the window mode */ + *(__IO uint32_t *) (COMP_BASE + COMP_Selection) |= (uint32_t) COMP_CSR_COMPxWNDWEN; + } + else + { + /* Disable the window mode */ + *(__IO uint32_t *) (COMP_BASE + COMP_Selection) &= (uint32_t)(~COMP_CSR_COMPxWNDWEN); + } +} + +/** + * @} + */ + +/** @defgroup COMP_Group3 COMP configuration locking function + * @brief COMP1, COMP2,...COMP7 configuration locking function + * COMP1, COMP2,...COMP7 configuration can be locked each separately. + * Unlocking is performed by system reset. + * +@verbatim + =============================================================================== + ##### Configuration Lock function ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Lock the selected comparator (COMP1/COMP2) configuration. + * @note Locking the configuration means that all control bits are read-only. + * To unlock the comparator configuration, perform a system reset. + * @param COMP_Selection: the selected comparator. + * This parameter can be COMP_Selection_COMPx where x can be 1 to 7 + * to select the COMP peripheral. + * @retval None + */ +void COMP_LockConfig(uint32_t COMP_Selection) +{ + /* Check the parameter */ + assert_param(IS_COMP_ALL_PERIPH(COMP_Selection)); + + /* Set the lock bit corresponding to selected comparator */ + *(__IO uint32_t *) (COMP_BASE + COMP_Selection) |= (uint32_t) (COMP_CSR_COMPxLOCK); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_crc.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_crc.c new file mode 100644 index 0000000..94a02fe --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_crc.c @@ -0,0 +1,354 @@ +/** + ****************************************************************************** + * @file stm32f30x_crc.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of CRC computation unit peripheral: + * + Configuration of the CRC computation unit + * + CRC computation of one/many 32-bit data + * + CRC Independent register (IDR) access + * + @verbatim + + =============================================================================== + ##### How to use this driver ##### + =============================================================================== + [..] + (#) Enable CRC AHB clock using RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE) + function. + (#) Select the polynomial size: 7-bit, 8-bit, 16-bit or 32-bit. + (#) Set the polynomial coefficients using CRC_SetPolynomial(); + (#) If required, select the reverse operation on input data + using CRC_ReverseInputDataSelect(); + (#) If required, enable the reverse operation on output data + using CRC_ReverseOutputDataCmd(Enable); + (#) If required, set the initialization remainder value using + CRC_SetInitRegister(); + (#) use CRC_CalcCRC() function to compute the CRC of a 32-bit data + or use CRC_CalcBlockCRC() function to compute the CRC if a 32-bit + data buffer. + + @endverbatim + + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_crc.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup CRC + * @brief CRC driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup CRC_Private_Functions + * @{ + */ + +/** @defgroup CRC_Group1 Configuration of the CRC computation unit functions + * @brief Configuration of the CRC computation unit functions + * +@verbatim + =============================================================================== + ##### CRC configuration functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes CRC peripheral registers to their default reset values. + * @param None + * @retval None + */ +void CRC_DeInit(void) +{ + /* Set DR register to reset value */ + CRC->DR = 0xFFFFFFFF; + /* Set the POL register to the reset value: 0x04C11DB7 */ + CRC->POL = 0x04C11DB7; + /* Reset IDR register */ + CRC->IDR = 0x00; + /* Set INIT register to reset value */ + CRC->INIT = 0xFFFFFFFF; + /* Reset the CRC calculation unit */ + CRC->CR = CRC_CR_RESET; +} + +/** + * @brief Resets the CRC calculation unit and sets INIT register content in DR register. + * @param None + * @retval None + */ +void CRC_ResetDR(void) +{ + /* Reset CRC generator */ + CRC->CR |= CRC_CR_RESET; +} + +/** + * @brief Selects the polynomial size. + * @param CRC_PolSize: Specifies the polynomial size. + * This parameter can be: + * @arg CRC_PolSize_7: 7-bit polynomial for CRC calculation + * @arg CRC_PolSize_8: 8-bit polynomial for CRC calculation + * @arg CRC_PolSize_16: 16-bit polynomial for CRC calculation + * @arg CRC_PolSize_32: 32-bit polynomial for CRC calculation + * @retval None + */ +void CRC_PolynomialSizeSelect(uint32_t CRC_PolSize) +{ + uint32_t tmpcr = 0; + + /* Check the parameter */ + assert_param(IS_CRC_POL_SIZE(CRC_PolSize)); + + /* Get CR register value */ + tmpcr = CRC->CR; + + /* Reset POL_SIZE bits */ + tmpcr &= (uint32_t)~((uint32_t)CRC_CR_POLSIZE); + /* Set the polynomial size */ + tmpcr |= (uint32_t)CRC_PolSize; + + /* Write to CR register */ + CRC->CR = (uint32_t)tmpcr; +} + +/** + * @brief Selects the reverse operation to be performed on input data. + * @param CRC_ReverseInputData: Specifies the reverse operation on input data. + * This parameter can be: + * @arg CRC_ReverseInputData_No: No reverse operation is performed + * @arg CRC_ReverseInputData_8bits: reverse operation performed on 8 bits + * @arg CRC_ReverseInputData_16bits: reverse operation performed on 16 bits + * @arg CRC_ReverseInputData_32bits: reverse operation performed on 32 bits + * @retval None + */ +void CRC_ReverseInputDataSelect(uint32_t CRC_ReverseInputData) +{ + uint32_t tmpcr = 0; + + /* Check the parameter */ + assert_param(IS_CRC_REVERSE_INPUT_DATA(CRC_ReverseInputData)); + + /* Get CR register value */ + tmpcr = CRC->CR; + + /* Reset REV_IN bits */ + tmpcr &= (uint32_t)~((uint32_t)CRC_CR_REV_IN); + /* Set the reverse operation */ + tmpcr |= (uint32_t)CRC_ReverseInputData; + + /* Write to CR register */ + CRC->CR = (uint32_t)tmpcr; +} + +/** + * @brief Enables or disable the reverse operation on output data. + * The reverse operation on output data is performed on 32-bit. + * @param NewState: new state of the reverse operation on output data. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void CRC_ReverseOutputDataCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable reverse operation on output data */ + CRC->CR |= CRC_CR_REV_OUT; + } + else + { + /* Disable reverse operation on output data */ + CRC->CR &= (uint32_t)~((uint32_t)CRC_CR_REV_OUT); + } +} + +/** + * @brief Initializes the INIT register. + * @note After resetting CRC calculation unit, CRC_InitValue is stored in DR register + * @param CRC_InitValue: Programmable initial CRC value + * @retval None + */ +void CRC_SetInitRegister(uint32_t CRC_InitValue) +{ + CRC->INIT = CRC_InitValue; +} + +/** + * @brief Initializes the polynomail coefficients. + * @param CRC_Pol: Polynomial to be used for CRC calculation. + * @retval None + */ +void CRC_SetPolynomial(uint32_t CRC_Pol) +{ + CRC->POL = CRC_Pol; +} + +/** + * @} + */ + +/** @defgroup CRC_Group2 CRC computation of one/many 32-bit data functions + * @brief CRC computation of one/many 32-bit data functions + * +@verbatim + =============================================================================== + ##### CRC computation functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Computes the 32-bit CRC of a given data word(32-bit). + * @param CRC_Data: data word(32-bit) to compute its CRC + * @retval 32-bit CRC + */ +uint32_t CRC_CalcCRC(uint32_t CRC_Data) +{ + CRC->DR = CRC_Data; + + return (CRC->DR); +} + +/** + * @brief Computes the 16-bit CRC of a given 16-bit data. + * @param CRC_Data: data half-word(16-bit) to compute its CRC + * @retval 16-bit CRC + */ +uint32_t CRC_CalcCRC16bits(uint16_t CRC_Data) +{ + *(uint16_t*)(CRC_BASE) = (uint16_t) CRC_Data; + + return (CRC->DR); +} + +/** + * @brief Computes the 8-bit CRC of a given 8-bit data. + * @param CRC_Data: 8-bit data to compute its CRC + * @retval 8-bit CRC + */ +uint32_t CRC_CalcCRC8bits(uint8_t CRC_Data) +{ + *(uint8_t*)(CRC_BASE) = (uint8_t) CRC_Data; + + return (CRC->DR); +} + +/** + * @brief Computes the 32-bit CRC of a given buffer of data word(32-bit). + * @param pBuffer: pointer to the buffer containing the data to be computed + * @param BufferLength: length of the buffer to be computed + * @retval 32-bit CRC + */ +uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength) +{ + uint32_t index = 0; + + for(index = 0; index < BufferLength; index++) + { + CRC->DR = pBuffer[index]; + } + return (CRC->DR); +} + +/** + * @brief Returns the current CRC value. + * @param None + * @retval 32-bit CRC + */ +uint32_t CRC_GetCRC(void) +{ + return (CRC->DR); +} + +/** + * @} + */ + +/** @defgroup CRC_Group3 CRC Independent Register (IDR) access functions + * @brief CRC Independent Register (IDR) access (write/read) functions + * +@verbatim + =============================================================================== + ##### CRC Independent Register (IDR) access functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Stores an 8-bit data in the Independent Data(ID) register. + * @param CRC_IDValue: 8-bit value to be stored in the ID register + * @retval None + */ +void CRC_SetIDRegister(uint8_t CRC_IDValue) +{ + CRC->IDR = CRC_IDValue; +} + +/** + * @brief Returns the 8-bit data stored in the Independent Data(ID) register + * @param None + * @retval 8-bit value of the ID register + */ +uint8_t CRC_GetIDRegister(void) +{ + return (CRC->IDR); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_dac.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_dac.c new file mode 100644 index 0000000..3c350ba --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_dac.c @@ -0,0 +1,754 @@ +/** + ****************************************************************************** + * @file stm32f30x_dac.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the Digital-to-Analog Converter (DAC) peripheral: + * + DAC channels configuration: trigger, output buffer, data format + * + DMA management + * + Interrupts and flags management + * + @verbatim + + =============================================================================== + ##### DAC Peripheral features ##### + =============================================================================== + [..] The device integrates two 12-bit Digital Analog Converters that can + be used independently or simultaneously (dual mode): + (#) DAC1 integrates two DAC channels: + (++) DAC1 channel 1 with DAC1_OUT1 as output + (++) DAC1 channel 2 with DAC1_OUT2 as output + (++) The two channels can be used independently or simultaneously (dual mode) + + (#) DAC2 integrates only one channel DAC2 channel 1 with DAC2_OUT1 as output + + [..] Digital to Analog conversion can be non-triggered using DAC_Trigger_None + and DAC_OUT1/DAC_OUT2 is available once writing to DHRx register using + DAC_SetChannel1Data()/DAC_SetChannel2Data. + + [..] Digital to Analog conversion can be triggered by: + (#) External event: EXTI Line 9 (any GPIOx_Pin9) using DAC_Trigger_Ext_IT9. + The used pin (GPIOx_Pin9) must be configured in input mode. + + (#) Timers TRGO: TIM2, TIM8/TIM3, TIM4, TIM6, TIM7, and TIM15 + (DAC_Trigger_T2_TRGO, DAC_Trigger_T4_TRGO...) + The timer TRGO event should be selected using TIM_SelectOutputTrigger() + (++) To trigger DAC conversions by TIM3 instead of TIM8 follow + this sequence: + (+++) Enable SYSCFG APB clock by calling + RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); + (+++) Select DAC_Trigger_T3_TRGO when calling DAC_Init() + (+++) Remap the DAC trigger from TIM8 to TIM3 by calling + SYSCFG_TriggerRemapConfig(SYSCFG_TriggerRemap_DACTIM3, ENABLE) + (#) Software using DAC_Trigger_Software + + [..] Each DAC channel integrates an output buffer that can be used to + reduce the output impedance, and to drive external loads directly + without having to add an external operational amplifier. + To enable, the output buffer use + DAC_InitStructure.DAC_OutputBuffer = DAC_OutputBuffer_Enable; + + [..] Refer to the device datasheet for more details about output impedance + value with and without output buffer. + + [..] Both DAC channels can be used to generate: + (+) Noise wave using DAC_WaveGeneration_Noise + (+) Triangle wave using DAC_WaveGeneration_Triangle + + [..] Wave generation can be disabled using DAC_WaveGeneration_None + + [..] The DAC data format can be: + (+) 8-bit right alignment using DAC_Align_8b_R + (+) 12-bit left alignment using DAC_Align_12b_L + (+) 12-bit right alignment using DAC_Align_12b_R + + [..] The analog output voltage on each DAC channel pin is determined + by the following equation: + (+) DAC_OUTx = VREF+ * DOR / 4095 with DOR is the Data Output Register. + VREF+ is the input voltage reference (refer to the device datasheet) + e.g. To set DAC_OUT1 to 0.7V, use DAC_SetChannel1Data(DAC_Align_12b_R, 868); + Assuming that VREF+ = 3.3, DAC_OUT1 = (3.3 * 868) / 4095 = 0.7V + + [..] A DMA1 request can be generated when an external trigger (but not + a software trigger) occurs if DMA1 requests are enabled using + DAC_DMACmd() + DMA1 requests are mapped as following: + (+) DAC channel1 is mapped on DMA1 channel3 which must be already + configured + (+) DAC channel2 is mapped on DMA1 channel4 which must be already + configured + + ##### How to use this driver ##### + =============================================================================== + [..] + (+) Enable DAC APB1 clock to get write access to DAC registers + using RCC_APB1PeriphClockCmd(RCC_APB1Periph_DAC, ENABLE) + + (+) Configure DACx_OUTy (DAC1_OUT1: PA4, DAC1_OUT2: PA5, DAC2_OUT1: PA6) + in analog mode. + + (+) Configure the DAC channel using DAC_Init() + + (+) Enable the DAC channel using DAC_Cmd() + + @endverbatim + + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_dac.h" +#include "stm32f30x_rcc.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup DAC + * @brief DAC driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* CR register Mask */ +#define CR_CLEAR_MASK ((uint32_t)0x00000FFE) + +/* DAC Dual Channels SWTRIG masks */ +#define DUAL_SWTRIG_SET ((uint32_t)0x00000003) +#define DUAL_SWTRIG_RESET ((uint32_t)0xFFFFFFFC) + +/* DHR registers offsets */ +#define DHR12R1_OFFSET ((uint32_t)0x00000008) +#define DHR12R2_OFFSET ((uint32_t)0x00000014) +#define DHR12RD_OFFSET ((uint32_t)0x00000020) + +/* DOR register offset */ +#define DOR_OFFSET ((uint32_t)0x0000002C) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup DAC_Private_Functions + * @{ + */ + +/** @defgroup DAC_Group1 DAC channels configuration + * @brief DAC channels configuration: trigger, output buffer, data format + * +@verbatim + =============================================================================== + ##### DAC channels configuration: trigger, output buffer, data format ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the DAC peripheral registers to their default reset values. + * @param DACx: where x can be 1 or 2 to select the DAC peripheral. + * @retval None + */ +void DAC_DeInit(DAC_TypeDef* DACx) +{ + /* Check the parameters */ + assert_param(IS_DAC_ALL_PERIPH(DACx)); + + if (DACx == DAC1) + { + /* Enable DAC1 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC1, ENABLE); + /* Release DAC1 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC1, DISABLE); + } + else + { + /* Enable DAC2 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC2, ENABLE); + /* Release DAC2 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC2, DISABLE); + } +} + +/** + * @brief Initializes the DAC peripheral according to the specified + * parameters in the DAC_InitStruct. + * @param DACx: where x can be 1 or 2 to select the DAC peripheral. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_InitStruct: pointer to a DAC_InitTypeDef structure that + * contains the configuration information for the specified DAC channel. + * @retval None + */ +void DAC_Init(DAC_TypeDef* DACx, uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct) +{ + uint32_t tmpreg1 = 0, tmpreg2 = 0; + + /* Check the DAC parameters */ + assert_param(IS_DAC_ALL_PERIPH(DACx)); + assert_param(IS_DAC_TRIGGER(DAC_InitStruct->DAC_Trigger)); + assert_param(IS_DAC_GENERATE_WAVE(DAC_InitStruct->DAC_WaveGeneration)); + assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude)); + assert_param(IS_DAC_BUFFER_SWITCH_STATE(DAC_InitStruct->DAC_Buffer_Switch)); + +/*---------------------------- DAC CR Configuration --------------------------*/ + /* Get the DAC CR value */ + tmpreg1 = DACx->CR; + /* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */ + tmpreg1 &= ~(CR_CLEAR_MASK << DAC_Channel); + /* Configure for the selected DAC channel: buffer output, trigger, wave generation, + mask/amplitude for wave generation */ + + /* Set TSELx and TENx bits according to DAC_Trigger value */ + /* Set WAVEx bits according to DAC_WaveGeneration value */ + /* Set MAMPx bits according to DAC_LFSRUnmask_TriangleAmplitude value */ + /* Set BOFFx OUTENx bit according to DAC_Buffer_Switch value */ + tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration | + DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | DAC_InitStruct->DAC_Buffer_Switch); + + /* Calculate CR register value depending on DAC_Channel */ + tmpreg1 |= tmpreg2 << DAC_Channel; + /* Write to DAC CR */ + DACx->CR = tmpreg1; +} + +/** + * @brief Fills each DAC_InitStruct member with its default value. + * @param DAC_InitStruct: pointer to a DAC_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct) +{ +/*--------------- Reset DAC init structure parameters values -----------------*/ + /* Initialize the DAC_Trigger member */ + DAC_InitStruct->DAC_Trigger = DAC_Trigger_None; + /* Initialize the DAC_WaveGeneration member */ + DAC_InitStruct->DAC_WaveGeneration = DAC_WaveGeneration_None; + /* Initialize the DAC_LFSRUnmask_TriangleAmplitude member */ + DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0; + /* Initialize the DAC_Buffer_Switch member */ + DAC_InitStruct->DAC_Buffer_Switch = DAC_BufferSwitch_Enable; +} + +/** + * @brief Enables or disables the specified DAC channel. + * @param DACx: where x can be 1 or 2 to select the DAC peripheral. + * @param DAC_Channel: The selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param NewState: new state of the DAC channel. + * This parameter can be: ENABLE or DISABLE. + * @note When the DAC channel is enabled the trigger source can no more + * be modified. + * @retval None + */ +void DAC_Cmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_ALL_PERIPH(DACx)); + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected DAC channel */ + DACx->CR |= (DAC_CR_EN1 << DAC_Channel); + } + else + { + /* Disable the selected DAC channel */ + DACx->CR &= (~(DAC_CR_EN1 << DAC_Channel)); + } +} + +/** + * @brief Enables or disables the selected DAC channel software trigger. + * @param DACx: where x can be 1 or 2 to select the DAC peripheral. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param NewState: new state of the selected DAC channel software trigger. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_SoftwareTriggerCmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_ALL_PERIPH(DACx)); + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable software trigger for the selected DAC channel */ + DACx->SWTRIGR |= (uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4); + } + else + { + /* Disable software trigger for the selected DAC channel */ + DACx->SWTRIGR &= ~((uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4)); + } +} + +/** + * @brief Enables or disables simultaneously the two DAC channels software + * triggers. + * @param DACx: where x can be 1 to select the DAC1 peripheral. + * @note Dual trigger is not applicable for DAC2 (DAC2 integrates one channel). + * @param NewState: new state of the DAC channels software triggers. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_DualSoftwareTriggerCmd(DAC_TypeDef* DACx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_LIST1_PERIPH(DACx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable software trigger for both DAC channels */ + DACx->SWTRIGR |= DUAL_SWTRIG_SET; + } + else + { + /* Disable software trigger for both DAC channels */ + DACx->SWTRIGR &= DUAL_SWTRIG_RESET; + } +} + +/** + * @brief Enables or disables the selected DAC channel wave generation. + * @param DACx: where x can be 1 to select the DAC1 peripheral. + * @note Wave generation is not available in DAC2. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_Wave: Specifies the wave type to enable or disable. + * This parameter can be one of the following values: + * @arg DAC_Wave_Noise: noise wave generation + * @arg DAC_Wave_Triangle: triangle wave generation + * @param NewState: new state of the selected DAC channel wave generation. + * This parameter can be: ENABLE or DISABLE. + * @note + * @retval None + */ +void DAC_WaveGenerationCmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_LIST1_PERIPH(DACx)); + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_WAVE(DAC_Wave)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected wave generation for the selected DAC channel */ + DACx->CR |= DAC_Wave << DAC_Channel; + } + else + { + /* Disable the selected wave generation for the selected DAC channel */ + DACx->CR &= ~(DAC_Wave << DAC_Channel); + } +} + +/** + * @brief Set the specified data holding register value for DAC channel1. + * @param DACx: where x can be 1 or 2 to select the DAC peripheral. + * @param DAC_Align: Specifies the data alignment for DAC channel1. + * This parameter can be one of the following values: + * @arg DAC_Align_8b_R: 8bit right data alignment selected + * @arg DAC_Align_12b_L: 12bit left data alignment selected + * @arg DAC_Align_12b_R: 12bit right data alignment selected + * @param Data: Data to be loaded in the selected data holding register. + * @retval None + */ +void DAC_SetChannel1Data(DAC_TypeDef* DACx, uint32_t DAC_Align, uint16_t Data) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_ALL_PERIPH(DACx)); + assert_param(IS_DAC_ALIGN(DAC_Align)); + assert_param(IS_DAC_DATA(Data)); + + tmp = (uint32_t)DACx; + tmp += DHR12R1_OFFSET + DAC_Align; + + /* Set the DAC channel1 selected data holding register */ + *(__IO uint32_t *) tmp = Data; +} + +/** + * @brief Set the specified data holding register value for DAC channel2. + * @param DACx: where x can be 1 to select the DAC peripheral. + * @note This function is available only for DAC1. + * @param DAC_Align: Specifies the data alignment for DAC channel2. + * This parameter can be one of the following values: + * @arg DAC_Align_8b_R: 8bit right data alignment selected + * @arg DAC_Align_12b_L: 12bit left data alignment selected + * @arg DAC_Align_12b_R: 12bit right data alignment selected + * @param Data : Data to be loaded in the selected data holding register. + * @retval None + */ +void DAC_SetChannel2Data(DAC_TypeDef* DACx, uint32_t DAC_Align, uint16_t Data) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_LIST1_PERIPH(DACx)); + assert_param(IS_DAC_ALIGN(DAC_Align)); + assert_param(IS_DAC_DATA(Data)); + + tmp = (uint32_t)DACx; + tmp += DHR12R2_OFFSET + DAC_Align; + + /* Set the DAC channel2 selected data holding register */ + *(__IO uint32_t *)tmp = Data; +} + +/** + * @brief Set the specified data holding register value for dual channel DAC. + * @param DACx: where x can be 1 to select the DAC peripheral. + * @note This function isn't applicable for DAC2. + * @param DAC_Align: Specifies the data alignment for dual channel DAC. + * This parameter can be one of the following values: + * @arg DAC_Align_8b_R: 8bit right data alignment selected + * @arg DAC_Align_12b_L: 12bit left data alignment selected + * @arg DAC_Align_12b_R: 12bit right data alignment selected + * @param Data2: Data for DAC Channel2 to be loaded in the selected data + * holding register. + * @param Data1: Data for DAC Channel1 to be loaded in the selected data + * holding register. + * @note In dual mode, a unique register access is required to write in both + * DAC channels at the same time. + * @retval None + */ +void DAC_SetDualChannelData(DAC_TypeDef* DACx, uint32_t DAC_Align, uint16_t Data2, uint16_t Data1) +{ + uint32_t data = 0, tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_LIST1_PERIPH(DACx)); + assert_param(IS_DAC_ALIGN(DAC_Align)); + assert_param(IS_DAC_DATA(Data1)); + assert_param(IS_DAC_DATA(Data2)); + + /* Calculate and set dual DAC data holding register value */ + if (DAC_Align == DAC_Align_8b_R) + { + data = ((uint32_t)Data2 << 8) | Data1; + } + else + { + data = ((uint32_t)Data2 << 16) | Data1; + } + + tmp = (uint32_t)DACx; + tmp += DHR12RD_OFFSET + DAC_Align; + + /* Set the dual DAC selected data holding register */ + *(__IO uint32_t *)tmp = data; +} + +/** + * @brief Returns the last data output value of the selected DAC channel. + * @param DACx: where x can be 1 or 2 to select the DAC peripheral. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @retval The selected DAC channel data output value. + */ +uint16_t DAC_GetDataOutputValue(DAC_TypeDef* DACx, uint32_t DAC_Channel) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_ALL_PERIPH(DACx)); + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + + tmp = (uint32_t) DACx; + tmp += DOR_OFFSET + ((uint32_t)DAC_Channel >> 2); + + /* Returns the DAC channel data output register value */ + return (uint16_t) (*(__IO uint32_t*) tmp); +} + +/** + * @} + */ + +/** @defgroup DAC_Group2 DMA management functions + * @brief DMA management functions + * +@verbatim + =============================================================================== + ##### DMA management functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified DAC channel DMA request. + * When enabled DMA1 is generated when an external trigger (EXTI Line9, + * TIM2, TIM4, TIM6, TIM7 or TIM9 but not a software trigger) occurs + * @param DACx: where x can be 1 or 2 to select the DAC peripheral. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param NewState: new state of the selected DAC channel DMA request. + * This parameter can be: ENABLE or DISABLE. + * @note The DAC channel1 (channel2) is mapped on DMA1 channel3 (channel4) which + * must be already configured. + * @retval None + */ +void DAC_DMACmd(DAC_TypeDef* DACx, uint32_t DAC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_ALL_PERIPH(DACx)); + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected DAC channel DMA request */ + DACx->CR |= (DAC_CR_DMAEN1 << DAC_Channel); + } + else + { + /* Disable the selected DAC channel DMA request */ + DACx->CR &= (~(DAC_CR_DMAEN1 << DAC_Channel)); + } +} + +/** + * @} + */ + +/** @defgroup DAC_Group3 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + ##### Interrupts and flags management functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified DAC interrupts. + * @param DACx: where x can be 1 or 2 to select the DAC peripheral. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_IT: specifies the DAC interrupt sources to be enabled or disabled. + * This parameter can be: + * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask + * @note The DMA underrun occurs when a second external trigger arrives before + * the acknowledgement for the first external trigger is received (first request). + * @param NewState: new state of the specified DAC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_ITConfig(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_ALL_PERIPH(DACx)); + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_DAC_IT(DAC_IT)); + + if (NewState != DISABLE) + { + /* Enable the selected DAC interrupts */ + DACx->CR |= (DAC_IT << DAC_Channel); + } + else + { + /* Disable the selected DAC interrupts */ + DACx->CR &= (~(uint32_t)(DAC_IT << DAC_Channel)); + } +} + +/** + * @brief Checks whether the specified DAC flag is set or not. + * @param DACx: where x can be 1 or 2 to select the DAC peripheral. + * @param DAC_Channel: thee selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_FLAG: specifies the flag to check. + * This parameter can be: + * @arg DAC_FLAG_DMAUDR: DMA underrun flag + * @note The DMA underrun occurs when a second external trigger arrives before + * the acknowledgement for the first external trigger is received (first request). + * @retval The new state of DAC_FLAG (SET or RESET). + */ +FlagStatus DAC_GetFlagStatus(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_FLAG) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_DAC_ALL_PERIPH(DACx)); + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_FLAG(DAC_FLAG)); + + /* Check the status of the specified DAC flag */ + if ((DACx->SR & (DAC_FLAG << DAC_Channel)) != (uint8_t)RESET) + { + /* DAC_FLAG is set */ + bitstatus = SET; + } + else + { + /* DAC_FLAG is reset */ + bitstatus = RESET; + } + /* Return the DAC_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the DAC channel's pending flags. + * @param DACx: where x can be 1 or 2 to select the DAC peripheral. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_FLAG: specifies the flag to clear. + * This parameter can be: + * @arg DAC_FLAG_DMAUDR: DMA underrun flag + * @retval None + */ +void DAC_ClearFlag(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_DAC_ALL_PERIPH(DACx)); + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_FLAG(DAC_FLAG)); + + /* Clear the selected DAC flags */ + DACx->SR = (DAC_FLAG << DAC_Channel); +} + +/** + * @brief Checks whether the specified DAC interrupt has occurred or not. + * @param DACx: where x can be 1 or 2 to select the DAC peripheral. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_IT: specifies the DAC interrupt source to check. + * This parameter can be: + * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask + * @note The DMA underrun occurs when a second external trigger arrives before + * the acknowledgement for the first external trigger is received (first request). + * @retval The new state of DAC_IT (SET or RESET). + */ +ITStatus DAC_GetITStatus(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_DAC_ALL_PERIPH(DACx)); + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_IT(DAC_IT)); + + /* Get the DAC_IT enable bit status */ + enablestatus = (DACx->CR & (DAC_IT << DAC_Channel)) ; + + /* Check the status of the specified DAC interrupt */ + if (((DACx->SR & (DAC_IT << DAC_Channel)) != (uint32_t)RESET) && enablestatus) + { + /* DAC_IT is set */ + bitstatus = SET; + } + else + { + /* DAC_IT is reset */ + bitstatus = RESET; + } + /* Return the DAC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the DAC channel's interrupt pending bits. + * @param DACx: where x can be 1 or 2 to select the DAC peripheral. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_IT: specifies the DAC interrupt pending bit to clear. + * This parameter can be the following values: + * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask + * @retval None + */ +void DAC_ClearITPendingBit(DAC_TypeDef* DACx, uint32_t DAC_Channel, uint32_t DAC_IT) +{ + /* Check the parameters */ + assert_param(IS_DAC_ALL_PERIPH(DACx)); + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_IT(DAC_IT)); + + /* Clear the selected DAC interrupt pending bits */ + DACx->SR = (DAC_IT << DAC_Channel); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_dbgmcu.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_dbgmcu.c new file mode 100644 index 0000000..ced108a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_dbgmcu.c @@ -0,0 +1,213 @@ +/** + ****************************************************************************** + * @file stm32f30x_dbgmcu.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the Debug MCU (DBGMCU) peripheral: + * + Device and Revision ID management + * + Peripherals Configuration + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_dbgmcu.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup DBGMCU + * @brief DBGMCU driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define IDCODE_DEVID_MASK ((uint32_t)0x00000FFF) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup DBGMCU_Private_Functions + * @{ + */ + +/** @defgroup DBGMCU_Group1 Device and Revision ID management functions + * @brief Device and Revision ID management functions + * +@verbatim + ============================================================================== + ##### Device and Revision ID management functions ##### + ============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Returns the device revision identifier. + * @param None + * @retval Device revision identifier + */ +uint32_t DBGMCU_GetREVID(void) +{ + return(DBGMCU->IDCODE >> 16); +} + +/** + * @brief Returns the device identifier. + * @param None + * @retval Device identifier + */ +uint32_t DBGMCU_GetDEVID(void) +{ + return(DBGMCU->IDCODE & IDCODE_DEVID_MASK); +} + +/** + * @} + */ + +/** @defgroup DBGMCU_Group2 Peripherals Configuration functions + * @brief Peripherals Configuration + * +@verbatim + ============================================================================== + ##### Peripherals Configuration functions ##### + ============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Configures low power mode behavior when the MCU is in Debug mode. + * @param DBGMCU_Periph: specifies the low power mode. + * This parameter can be any combination of the following values: + * @arg DBGMCU_SLEEP: Keep debugger connection during SLEEP mode. + * @arg DBGMCU_STOP: Keep debugger connection during STOP mode. + * @arg DBGMCU_STANDBY: Keep debugger connection during STANDBY mode. + * @param NewState: new state of the specified low power mode in Debug mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DBGMCU_PERIPH(DBGMCU_Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + DBGMCU->CR |= DBGMCU_Periph; + } + else + { + DBGMCU->CR &= ~DBGMCU_Periph; + } +} + +/** + * @brief Configures APB1 peripheral behavior when the MCU is in Debug mode. + * @param DBGMCU_Periph: specifies the APB1 peripheral. + * This parameter can be any combination of the following values: + * @arg DBGMCU_TIM2_STOP: TIM2 counter stopped when Core is halted. + * @arg DBGMCU_TIM3_STOP: TIM3 counter stopped when Core is halted. + * @arg DBGMCU_TIM4_STOP: TIM4 counter stopped when Core is halted. + * @arg DBGMCU_TIM6_STOP: TIM6 counter stopped when Core is halted. + * @arg DBGMCU_TIM7_STOP: TIM7 counter stopped when Core is halted. + * @arg DBGMCU_RTC_STOP: RTC Calendar and Wakeup counter are stopped when + * Core is halted. + * @arg DBGMCU_WWDG_STOP: Debug WWDG stopped when Core is halted. + * @arg DBGMCU_IWDG_STOP: Debug IWDG stopped when Core is halted. + * @arg DBGMCU_I2C1_SMBUS_TIMEOUT: I2C1 SMBUS timeout mode stopped when + * Core is halted. + * @arg DBGMCU_I2C2_SMBUS_TIMEOUT: I2C2 SMBUS timeout mode stopped when + * Core is halted. + * @arg DBGMCU_CAN1_STOP: Debug CAN2 stopped when Core is halted. + * @param NewState: new state of the specified APB1 peripheral in Debug mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DBGMCU_APB1PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DBGMCU_APB1PERIPH(DBGMCU_Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + DBGMCU->APB1FZ |= DBGMCU_Periph; + } + else + { + DBGMCU->APB1FZ &= ~DBGMCU_Periph; + } +} + +/** + * @brief Configures APB2 peripheral behavior when the MCU is in Debug mode. + * @param DBGMCU_Periph: specifies the APB2 peripheral. + * This parameter can be any combination of the following values: + * @arg DBGMCU_TIM1_STOP: TIM1 counter stopped when Core is halted. + * @arg DBGMCU_TIM8_STOP: TIM8 counter stopped when Core is halted. + * @arg DBGMCU_TIM15_STOP: TIM15 counter stopped when Core is halted. + * @arg DBGMCU_TIM16_STOP: TIM16 counter stopped when Core is halted. + * @arg DBGMCU_TIM17_STOP: TIM17 counter stopped when Core is halted. + * @param NewState: new state of the specified APB2 peripheral in Debug mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DBGMCU_APB2PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DBGMCU_APB2PERIPH(DBGMCU_Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + DBGMCU->APB2FZ |= DBGMCU_Periph; + } + else + { + DBGMCU->APB2FZ &= ~DBGMCU_Periph; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_dma.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_dma.c new file mode 100644 index 0000000..0c33b67 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_dma.c @@ -0,0 +1,866 @@ +/** + ****************************************************************************** + * @file stm32f30x_dma.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the Direct Memory Access controller (DMA): + * + Initialization and Configuration + * + Data Counter + * + Interrupts and flags management + * + @verbatim + + =============================================================================== + ##### How to use this driver ##### + =============================================================================== + [..] + (#) Enable The DMA controller clock using + RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE) function for DMA1 or + using RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA2, ENABLE) function for DMA2. + (#) Enable and configure the peripheral to be connected to the DMA channel + (except for internal SRAM / FLASH memories: no initialization is necessary). + (#) For a given Channel, program the Source and Destination addresses, + the transfer Direction, the Buffer Size, the Peripheral and Memory + Incrementation mode and Data Size, the Circular or Normal mode, + the channel transfer Priority and the Memory-to-Memory transfer + mode (if needed) using the DMA_Init() function. + (#) Enable the NVIC and the corresponding interrupt(s) using the function + DMA_ITConfig() if you need to use DMA interrupts. + (#) Enable the DMA channel using the DMA_Cmd() function. + (#) Activate the needed channel Request using PPP_DMACmd() function for + any PPP peripheral except internal SRAM and FLASH (ie. SPI, USART ...) + The function allowing this operation is provided in each PPP peripheral + driver (ie. SPI_DMACmd for SPI peripheral). + (#) Optionally, you can configure the number of data to be transferred + when the channel is disabled (ie. after each Transfer Complete event + or when a Transfer Error occurs) using the function DMA_SetCurrDataCounter(). + And you can get the number of remaining data to be transferred using + the function DMA_GetCurrDataCounter() at run time (when the DMA channel is + enabled and running). + (#) To control DMA events you can use one of the following two methods: + (##) Check on DMA channel flags using the function DMA_GetFlagStatus(). + (##) Use DMA interrupts through the function DMA_ITConfig() at initialization + phase and DMA_GetITStatus() function into interrupt routines in + communication phase. + After checking on a flag you should clear it using DMA_ClearFlag() + function. And after checking on an interrupt event you should + clear it using DMA_ClearITPendingBit() function. + + @endverbatim + + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_dma.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup DMA + * @brief DMA driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define CCR_CLEAR_MASK ((uint32_t)0xFFFF800F) /* DMA Channel config registers Masks */ +#define FLAG_Mask ((uint32_t)0x10000000) /* DMA2 FLAG mask */ + + +/* DMA1 Channelx interrupt pending bit masks */ +#define DMA1_CHANNEL1_IT_MASK ((uint32_t)(DMA_ISR_GIF1 | DMA_ISR_TCIF1 | DMA_ISR_HTIF1 | DMA_ISR_TEIF1)) +#define DMA1_CHANNEL2_IT_MASK ((uint32_t)(DMA_ISR_GIF2 | DMA_ISR_TCIF2 | DMA_ISR_HTIF2 | DMA_ISR_TEIF2)) +#define DMA1_CHANNEL3_IT_MASK ((uint32_t)(DMA_ISR_GIF3 | DMA_ISR_TCIF3 | DMA_ISR_HTIF3 | DMA_ISR_TEIF3)) +#define DMA1_CHANNEL4_IT_MASK ((uint32_t)(DMA_ISR_GIF4 | DMA_ISR_TCIF4 | DMA_ISR_HTIF4 | DMA_ISR_TEIF4)) +#define DMA1_CHANNEL5_IT_MASK ((uint32_t)(DMA_ISR_GIF5 | DMA_ISR_TCIF5 | DMA_ISR_HTIF5 | DMA_ISR_TEIF5)) +#define DMA1_CHANNEL6_IT_MASK ((uint32_t)(DMA_ISR_GIF6 | DMA_ISR_TCIF6 | DMA_ISR_HTIF6 | DMA_ISR_TEIF6)) +#define DMA1_CHANNEL7_IT_MASK ((uint32_t)(DMA_ISR_GIF7 | DMA_ISR_TCIF7 | DMA_ISR_HTIF7 | DMA_ISR_TEIF7)) + +/* DMA2 Channelx interrupt pending bit masks */ +#define DMA2_CHANNEL1_IT_MASK ((uint32_t)(DMA_ISR_GIF1 | DMA_ISR_TCIF1 | DMA_ISR_HTIF1 | DMA_ISR_TEIF1)) +#define DMA2_CHANNEL2_IT_MASK ((uint32_t)(DMA_ISR_GIF2 | DMA_ISR_TCIF2 | DMA_ISR_HTIF2 | DMA_ISR_TEIF2)) +#define DMA2_CHANNEL3_IT_MASK ((uint32_t)(DMA_ISR_GIF3 | DMA_ISR_TCIF3 | DMA_ISR_HTIF3 | DMA_ISR_TEIF3)) +#define DMA2_CHANNEL4_IT_MASK ((uint32_t)(DMA_ISR_GIF4 | DMA_ISR_TCIF4 | DMA_ISR_HTIF4 | DMA_ISR_TEIF4)) +#define DMA2_CHANNEL5_IT_MASK ((uint32_t)(DMA_ISR_GIF5 | DMA_ISR_TCIF5 | DMA_ISR_HTIF5 | DMA_ISR_TEIF5)) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup DMA_Private_Functions + * @{ + */ + +/** @defgroup DMA_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] This subsection provides functions allowing to initialize the DMA channel + source and destination addresses, incrementation and data sizes, transfer + direction, buffer size, circular/normal mode selection, memory-to-memory + mode selection and channel priority value. + [..] The DMA_Init() function follows the DMA configuration procedures as described + in reference manual (RM00316). + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the DMAy Channelx registers to their default reset + * values. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @retval None + */ +void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + + /* Disable the selected DMAy Channelx */ + DMAy_Channelx->CCR &= (uint16_t)(~DMA_CCR_EN); + + /* Reset DMAy Channelx control register */ + DMAy_Channelx->CCR = 0; + + /* Reset DMAy Channelx remaining bytes register */ + DMAy_Channelx->CNDTR = 0; + + /* Reset DMAy Channelx peripheral address register */ + DMAy_Channelx->CPAR = 0; + + /* Reset DMAy Channelx memory address register */ + DMAy_Channelx->CMAR = 0; + + if (DMAy_Channelx == DMA1_Channel1) + { + /* Reset interrupt pending bits for DMA1 Channel1 */ + DMA1->IFCR |= DMA1_CHANNEL1_IT_MASK; + } + else if (DMAy_Channelx == DMA1_Channel2) + { + /* Reset interrupt pending bits for DMA1 Channel2 */ + DMA1->IFCR |= DMA1_CHANNEL2_IT_MASK; + } + else if (DMAy_Channelx == DMA1_Channel3) + { + /* Reset interrupt pending bits for DMA1 Channel3 */ + DMA1->IFCR |= DMA1_CHANNEL3_IT_MASK; + } + else if (DMAy_Channelx == DMA1_Channel4) + { + /* Reset interrupt pending bits for DMA1 Channel4 */ + DMA1->IFCR |= DMA1_CHANNEL4_IT_MASK; + } + else if (DMAy_Channelx == DMA1_Channel5) + { + /* Reset interrupt pending bits for DMA1 Channel5 */ + DMA1->IFCR |= DMA1_CHANNEL5_IT_MASK; + } + else if (DMAy_Channelx == DMA1_Channel6) + { + /* Reset interrupt pending bits for DMA1 Channel6 */ + DMA1->IFCR |= DMA1_CHANNEL6_IT_MASK; + } + else if (DMAy_Channelx == DMA1_Channel7) + { + /* Reset interrupt pending bits for DMA1 Channel7 */ + DMA1->IFCR |= DMA1_CHANNEL7_IT_MASK; + } + else if (DMAy_Channelx == DMA2_Channel1) + { + /* Reset interrupt pending bits for DMA2 Channel1 */ + DMA2->IFCR |= DMA2_CHANNEL1_IT_MASK; + } + else if (DMAy_Channelx == DMA2_Channel2) + { + /* Reset interrupt pending bits for DMA2 Channel2 */ + DMA2->IFCR |= DMA2_CHANNEL2_IT_MASK; + } + else if (DMAy_Channelx == DMA2_Channel3) + { + /* Reset interrupt pending bits for DMA2 Channel3 */ + DMA2->IFCR |= DMA2_CHANNEL3_IT_MASK; + } + else if (DMAy_Channelx == DMA2_Channel4) + { + /* Reset interrupt pending bits for DMA2 Channel4 */ + DMA2->IFCR |= DMA2_CHANNEL4_IT_MASK; + } + else + { + if (DMAy_Channelx == DMA2_Channel5) + { + /* Reset interrupt pending bits for DMA2 Channel5 */ + DMA2->IFCR |= DMA2_CHANNEL5_IT_MASK; + } + } +} + +/** + * @brief Initializes the DMAy Channelx according to the specified parameters + * in the DMA_InitStruct. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param DMA_InitStruct: pointer to a DMA_InitTypeDef structure that contains + * the configuration information for the specified DMA Channel. + * @retval None + */ +void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + assert_param(IS_DMA_DIR(DMA_InitStruct->DMA_DIR)); + assert_param(IS_DMA_PERIPHERAL_INC_STATE(DMA_InitStruct->DMA_PeripheralInc)); + assert_param(IS_DMA_MEMORY_INC_STATE(DMA_InitStruct->DMA_MemoryInc)); + assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(DMA_InitStruct->DMA_PeripheralDataSize)); + assert_param(IS_DMA_MEMORY_DATA_SIZE(DMA_InitStruct->DMA_MemoryDataSize)); + assert_param(IS_DMA_MODE(DMA_InitStruct->DMA_Mode)); + assert_param(IS_DMA_PRIORITY(DMA_InitStruct->DMA_Priority)); + assert_param(IS_DMA_M2M_STATE(DMA_InitStruct->DMA_M2M)); + +/*--------------------------- DMAy Channelx CCR Configuration ----------------*/ + /* Get the DMAy_Channelx CCR value */ + tmpreg = DMAy_Channelx->CCR; + + /* Clear MEM2MEM, PL, MSIZE, PSIZE, MINC, PINC, CIRC and DIR bits */ + tmpreg &= CCR_CLEAR_MASK; + + /* Configure DMAy Channelx: data transfer, data size, priority level and mode */ + /* Set DIR bit according to DMA_DIR value */ + /* Set CIRC bit according to DMA_Mode value */ + /* Set PINC bit according to DMA_PeripheralInc value */ + /* Set MINC bit according to DMA_MemoryInc value */ + /* Set PSIZE bits according to DMA_PeripheralDataSize value */ + /* Set MSIZE bits according to DMA_MemoryDataSize value */ + /* Set PL bits according to DMA_Priority value */ + /* Set the MEM2MEM bit according to DMA_M2M value */ + tmpreg |= DMA_InitStruct->DMA_DIR | DMA_InitStruct->DMA_Mode | + DMA_InitStruct->DMA_PeripheralInc | DMA_InitStruct->DMA_MemoryInc | + DMA_InitStruct->DMA_PeripheralDataSize | DMA_InitStruct->DMA_MemoryDataSize | + DMA_InitStruct->DMA_Priority | DMA_InitStruct->DMA_M2M; + + /* Write to DMAy Channelx CCR */ + DMAy_Channelx->CCR = tmpreg; + +/*--------------------------- DMAy Channelx CNDTR Configuration --------------*/ + /* Write to DMAy Channelx CNDTR */ + DMAy_Channelx->CNDTR = DMA_InitStruct->DMA_BufferSize; + +/*--------------------------- DMAy Channelx CPAR Configuration ---------------*/ + /* Write to DMAy Channelx CPAR */ + DMAy_Channelx->CPAR = DMA_InitStruct->DMA_PeripheralBaseAddr; + +/*--------------------------- DMAy Channelx CMAR Configuration ---------------*/ + /* Write to DMAy Channelx CMAR */ + DMAy_Channelx->CMAR = DMA_InitStruct->DMA_MemoryBaseAddr; +} + +/** + * @brief Fills each DMA_InitStruct member with its default value. + * @param DMA_InitStruct: pointer to a DMA_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct) +{ +/*-------------- Reset DMA init structure parameters values ------------------*/ + /* Initialize the DMA_PeripheralBaseAddr member */ + DMA_InitStruct->DMA_PeripheralBaseAddr = 0; + /* Initialize the DMA_MemoryBaseAddr member */ + DMA_InitStruct->DMA_MemoryBaseAddr = 0; + /* Initialize the DMA_DIR member */ + DMA_InitStruct->DMA_DIR = DMA_DIR_PeripheralSRC; + /* Initialize the DMA_BufferSize member */ + DMA_InitStruct->DMA_BufferSize = 0; + /* Initialize the DMA_PeripheralInc member */ + DMA_InitStruct->DMA_PeripheralInc = DMA_PeripheralInc_Disable; + /* Initialize the DMA_MemoryInc member */ + DMA_InitStruct->DMA_MemoryInc = DMA_MemoryInc_Disable; + /* Initialize the DMA_PeripheralDataSize member */ + DMA_InitStruct->DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; + /* Initialize the DMA_MemoryDataSize member */ + DMA_InitStruct->DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; + /* Initialize the DMA_Mode member */ + DMA_InitStruct->DMA_Mode = DMA_Mode_Normal; + /* Initialize the DMA_Priority member */ + DMA_InitStruct->DMA_Priority = DMA_Priority_Low; + /* Initialize the DMA_M2M member */ + DMA_InitStruct->DMA_M2M = DMA_M2M_Disable; +} + +/** + * @brief Enables or disables the specified DMAy Channelx. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param NewState: new state of the DMAy Channelx. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected DMAy Channelx */ + DMAy_Channelx->CCR |= DMA_CCR_EN; + } + else + { + /* Disable the selected DMAy Channelx */ + DMAy_Channelx->CCR &= (uint16_t)(~DMA_CCR_EN); + } +} + +/** + * @} + */ + +/** @defgroup DMA_Group2 Data Counter functions + * @brief Data Counter functions + * +@verbatim + =============================================================================== + ##### Data Counter functions ##### + =============================================================================== + [..] This subsection provides function allowing to configure and read the buffer + size (number of data to be transferred).The DMA data counter can be written + only when the DMA channel is disabled (ie. after transfer complete event). + [..] The following function can be used to write the Channel data counter value: + (+) void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber). + [..] + (@) It is advised to use this function rather than DMA_Init() in situations + where only the Data buffer needs to be reloaded. + [..] The DMA data counter can be read to indicate the number of remaining transfers + for the relative DMA channel. This counter is decremented at the end of each + data transfer and when the transfer is complete: + (+) If Normal mode is selected: the counter is set to 0. + (+) If Circular mode is selected: the counter is reloaded with the initial + value(configured before enabling the DMA channel). + [..] The following function can be used to read the Channel data counter value: + (+) uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx). + +@endverbatim + * @{ + */ + +/** + * @brief Sets the number of data units in the current DMAy Channelx transfer. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param DataNumber: The number of data units in the current DMAy Channelx + * transfer. + * @note This function can only be used when the DMAy_Channelx is disabled. + * @retval None. + */ +void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + +/*--------------------------- DMAy Channelx CNDTR Configuration --------------*/ + /* Write to DMAy Channelx CNDTR */ + DMAy_Channelx->CNDTR = DataNumber; +} + +/** + * @brief Returns the number of remaining data units in the current + * DMAy Channelx transfer. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @retval The number of remaining data units in the current DMAy Channelx + * transfer. + */ +uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + /* Return the number of remaining data units for DMAy Channelx */ + return ((uint16_t)(DMAy_Channelx->CNDTR)); +} + +/** + * @} + */ + +/** @defgroup DMA_Group3 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + ##### Interrupts and flags management functions ##### + =============================================================================== + [..] This subsection provides functions allowing to configure the DMA Interrupt + sources and check or clear the flags or pending bits status. + The user should identify which mode will be used in his application to manage + the DMA controller events: Polling mode or Interrupt mode. + + *** Polling Mode *** + ==================== + [..] Each DMA channel can be managed through 4 event Flags (y : DMA Controller + number, x : DMA channel number): + (#) DMAy_FLAG_TCx : to indicate that a Transfer Complete event occurred. + (#) DMAy_FLAG_HTx : to indicate that a Half-Transfer Complete event occurred. + (#) DMAy_FLAG_TEx : to indicate that a Transfer Error occurred. + (#) DMAy_FLAG_GLx : to indicate that at least one of the events described + above occurred. + [..] + (@) Clearing DMAy_FLAG_GLx results in clearing all other pending flags of the + same channel (DMAy_FLAG_TCx, DMAy_FLAG_HTx and DMAy_FLAG_TEx). + [..] In this Mode it is advised to use the following functions: + (+) FlagStatus DMA_GetFlagStatus(uint32_t DMA_FLAG); + (+) void DMA_ClearFlag(uint32_t DMA_FLAG); + + *** Interrupt Mode *** + ====================== + [..] Each DMA channel can be managed through 4 Interrupts: + (+) Interrupt Source + (##) DMA_IT_TC: specifies the interrupt source for the Transfer Complete + event. + (##) DMA_IT_HT: specifies the interrupt source for the Half-transfer Complete + event. + (##) DMA_IT_TE: specifies the interrupt source for the transfer errors event. + (##) DMA_IT_GL: to indicate that at least one of the interrupts described + above occurred. + -@@- Clearing DMA_IT_GL interrupt results in clearing all other interrupts of + the same channel (DMA_IT_TCx, DMA_IT_HT and DMA_IT_TE). + [..] In this Mode it is advised to use the following functions: + (+) void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState); + (+) ITStatus DMA_GetITStatus(uint32_t DMA_IT); + (+) void DMA_ClearITPendingBit(uint32_t DMA_IT); + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified DMAy Channelx interrupts. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param DMA_IT: specifies the DMA interrupts sources to be enabled + * or disabled. + * This parameter can be any combination of the following values: + * @arg DMA_IT_TC: Transfer complete interrupt mask + * @arg DMA_IT_HT: Half transfer interrupt mask + * @arg DMA_IT_TE: Transfer error interrupt mask + * @param NewState: new state of the specified DMA interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + assert_param(IS_DMA_CONFIG_IT(DMA_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected DMA interrupts */ + DMAy_Channelx->CCR |= DMA_IT; + } + else + { + /* Disable the selected DMA interrupts */ + DMAy_Channelx->CCR &= ~DMA_IT; + } +} + +/** + * @brief Checks whether the specified DMAy Channelx flag is set or not. + * @param DMAy_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag. + * @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag. + * @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag. + * @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag. + * @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag. + * @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag. + * @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag. + * @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag. + * @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag. + * @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag. + * @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag. + * @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag. + * @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag. + * @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag. + * @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag. + * @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag. + * @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag. + * @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag. + * @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag. + * @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag. + * @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag. + * @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag. + * @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag. + * @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag. + * @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag. + * @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag. + * @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag. + * @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag. + * @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag. + * @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag. + * @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag. + * @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag. + * @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag. + * @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag. + * @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag. + * @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag. + * @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag. + * @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag. + * @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag. + * @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag. + * @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag. + * @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag. + * @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag. + * @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag. + * @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag. + * @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag. + * @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag. + * @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag. + * + * @note + * The Global flag (DMAy_FLAG_GLx) is set whenever any of the other flags + * relative to the same channel is set (Transfer Complete, Half-transfer + * Complete or Transfer Error flags: DMAy_FLAG_TCx, DMAy_FLAG_HTx or + * DMAy_FLAG_TEx). + * + * @retval The new state of DMAy_FLAG (SET or RESET). + */ +FlagStatus DMA_GetFlagStatus(uint32_t DMAy_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_DMA_GET_FLAG(DMAy_FLAG)); + + /* Calculate the used DMAy */ + if ((DMAy_FLAG & FLAG_Mask) != (uint32_t)RESET) + { + /* Get DMA2 ISR register value */ + tmpreg = DMA2->ISR ; + } + else + { + /* Get DMA1 ISR register value */ + tmpreg = DMA1->ISR ; + } + + /* Check the status of the specified DMAy flag */ + if ((tmpreg & DMAy_FLAG) != (uint32_t)RESET) + { + /* DMAy_FLAG is set */ + bitstatus = SET; + } + else + { + /* DMAy_FLAG is reset */ + bitstatus = RESET; + } + + /* Return the DMAy_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the DMAy Channelx's pending flags. + * @param DMAy_FLAG: specifies the flag to clear. + * This parameter can be any combination (for the same DMA) of the following values: + * @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag. + * @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag. + * @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag. + * @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag. + * @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag. + * @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag. + * @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag. + * @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag. + * @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag. + * @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag. + * @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag. + * @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag. + * @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag. + * @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag. + * @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag. + * @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag. + * @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag. + * @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag. + * @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag. + * @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag. + * @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag. + * @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag. + * @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag. + * @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag. + * @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag. + * @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag. + * @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag. + * @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag. + * @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag. + * @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag. + * @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag. + * @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag. + * @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag. + * @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag. + * @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag. + * @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag. + * @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag. + * @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag. + * @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag. + * @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag. + * @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag. + * @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag. + * @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag. + * @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag. + * @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag. + * @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag. + * @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag. + * @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag. + * + * @note + * Clearing the Global flag (DMAy_FLAG_GLx) results in clearing all other flags + * relative to the same channel (Transfer Complete, Half-transfer Complete and + * Transfer Error flags: DMAy_FLAG_TCx, DMAy_FLAG_HTx and DMAy_FLAG_TEx). + * + * @retval None + */ +void DMA_ClearFlag(uint32_t DMAy_FLAG) +{ + /* Check the parameters */ + assert_param(IS_DMA_CLEAR_FLAG(DMAy_FLAG)); + +/* Calculate the used DMAy */ + if ((DMAy_FLAG & FLAG_Mask) != (uint32_t)RESET) + { + /* Clear the selected DMAy flags */ + DMA2->IFCR = DMAy_FLAG; + } + else + { + /* Clear the selected DMAy flags */ + DMA1->IFCR = DMAy_FLAG; + } +} + +/** + * @brief Checks whether the specified DMAy Channelx interrupt has occurred or not. + * @param DMAy_IT: specifies the DMAy interrupt source to check. + * This parameter can be one of the following values: + * @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt. + * @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt. + * @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt. + * @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt. + * @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt. + * @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt. + * @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt. + * @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt. + * @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt. + * @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt. + * @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt. + * @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt. + * @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt. + * @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt. + * @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt. + * @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt. + * @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt. + * @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt. + * @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt. + * @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt. + * @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt. + * @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt. + * @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt. + * @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt. + * @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt. + * @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt. + * @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt. + * @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt. + * @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt. + * @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt. + * @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt. + * @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt. + * @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt. + * @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt. + * @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt. + * @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt. + * @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt. + * @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt. + * @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt. + * @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt. + * @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt. + * @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt. + * @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt. + * @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt. + * @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt. + * @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt. + * @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt. + * @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt. + * + * @note + * The Global interrupt (DMAy_FLAG_GLx) is set whenever any of the other + * interrupts relative to the same channel is set (Transfer Complete, + * Half-transfer Complete or Transfer Error interrupts: DMAy_IT_TCx, + * DMAy_IT_HTx or DMAy_IT_TEx). + * + * @retval The new state of DMAy_IT (SET or RESET). + */ +ITStatus DMA_GetITStatus(uint32_t DMAy_IT) +{ + ITStatus bitstatus = RESET; + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_DMA_GET_IT(DMAy_IT)); + + /* Calculate the used DMA */ + if ((DMAy_IT & FLAG_Mask) != (uint32_t)RESET) + { + /* Get DMA2 ISR register value */ + tmpreg = DMA2->ISR; + } + else + { + /* Get DMA1 ISR register value */ + tmpreg = DMA1->ISR; + } + + /* Check the status of the specified DMAy interrupt */ + if ((tmpreg & DMAy_IT) != (uint32_t)RESET) + { + /* DMAy_IT is set */ + bitstatus = SET; + } + else + { + /* DMAy_IT is reset */ + bitstatus = RESET; + } + /* Return the DMAy_IT status */ + return bitstatus; +} + +/** + * @brief Clears the DMAy Channelx's interrupt pending bits. + * @param DMAy_IT: specifies the DMAy interrupt pending bit to clear. + * This parameter can be any combination (for the same DMA) of the following values: + * @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt. + * @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt. + * @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt. + * @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt. + * @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt. + * @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt. + * @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt. + * @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt. + * @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt. + * @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt. + * @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt. + * @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt. + * @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt. + * @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt. + * @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt. + * @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt. + * @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt. + * @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt. + * @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt. + * @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt. + * @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt. + * @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt. + * @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt. + * @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt. + * @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt. + * @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt. + * @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt. + * @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt. + * @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt. + * @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt. + * @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt. + * @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt. + * @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt. + * @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt. + * @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt. + * @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt. + * @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt. + * @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt. + * @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt. + * @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt. + * @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt. + * @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt. + * @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt. + * @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt. + * @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt. + * @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt. + * @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt. + * @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt. + * + * @note + * Clearing the Global interrupt (DMAy_IT_GLx) results in clearing all other + * interrupts relative to the same channel (Transfer Complete, Half-transfer + * Complete and Transfer Error interrupts: DMAy_IT_TCx, DMAy_IT_HTx and + * DMAy_IT_TEx). + * + * @retval None + */ +void DMA_ClearITPendingBit(uint32_t DMAy_IT) +{ + /* Check the parameters */ + assert_param(IS_DMA_CLEAR_IT(DMAy_IT)); + + /* Calculate the used DMAy */ + if ((DMAy_IT & FLAG_Mask) != (uint32_t)RESET) + { + /* Clear the selected DMAy interrupt pending bits */ + DMA2->IFCR = DMAy_IT; + } + else + { + /* Clear the selected DMAy interrupt pending bits */ + DMA1->IFCR = DMAy_IT; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_exti.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_exti.c new file mode 100644 index 0000000..6f8a9d0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_exti.c @@ -0,0 +1,349 @@ +/** + ****************************************************************************** + * @file stm32f30x_exti.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the EXTI peripheral: + * + Initialization and Configuration + * + Interrupts and flags management + * + @verbatim + =============================================================================== + ##### EXTI features ##### + =============================================================================== + [..] External interrupt/event lines are mapped as following: + (#) All available GPIO pins are connected to the 16 external + interrupt/event lines from EXTI0 to EXTI15. + (#) EXTI line 16 is connected to the PVD output + (#) EXTI line 17 is connected to the RTC Alarm event + (#) EXTI line 18 is connected to USB Device wakeup event + (#) EXTI line 19 is connected to the RTC Tamper and TimeStamp events + (#) EXTI line 20 is connected to the RTC wakeup event + (#) EXTI line 21 is connected to the Comparator 1 wakeup event + (#) EXTI line 22 is connected to the Comparator 2 wakeup event + (#) EXTI line 23 is connected to the I2C1 wakeup event + (#) EXTI line 24 is connected to the I2C2 wakeup event + (#) EXTI line 25 is connected to the USART1 wakeup event + (#) EXTI line 26 is connected to the USART2 wakeup event + (#) EXTI line 27 is reserved + (#) EXTI line 28 is connected to the USART3 wakeup event + (#) EXTI line 29 is connected to the Comparator 3 event + (#) EXTI line 30 is connected to the Comparator 4 event + (#) EXTI line 31 is connected to the Comparator 5 event + (#) EXTI line 32 is connected to the Comparator 6 event + (#) EXTI line 33 is connected to the Comparator 7 event + (#) EXTI line 34 is connected for thr UART4 wakeup event + (#) EXTI line 35 is connected for the UART5 wakeup event + + ##### How to use this driver ##### + =============================================================================== + [..] In order to use an I/O pin as an external interrupt source, + follow steps below: + (#) Configure the I/O in input mode using GPIO_Init(). + (#) Select the input source pin for the EXTI line using + SYSCFG_EXTILineConfig(). + (#) Select the mode(interrupt, event) and configure the trigger + selection (Rising, falling or both) using EXTI_Init(). For the + internal interrupt, the trigger selection is not needed + (the active edge is always the rising one). + (#) Configure NVIC IRQ channel mapped to the EXTI line using NVIC_Init(). + (#) Optionally, you can generate a software interrupt using the function + EXTI_GenerateSWInterrupt(). + [..] + (@) SYSCFG APB clock must be enabled to get write access to SYSCFG_EXTICRx + registers using RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); + + @endverbatim + + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_exti.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup EXTI + * @brief EXTI driver modules + * @{ + */ + + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define EXTI_LINENONE ((uint32_t)0x00000) /* No interrupt selected */ + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup EXTI_Private_Functions + * @{ + */ + +/** @defgroup EXTI_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the EXTI peripheral registers to their default reset + * values. + * @param None + * @retval None + */ +void EXTI_DeInit(void) +{ + EXTI->IMR = 0x1F800000; + EXTI->EMR = 0x00000000; + EXTI->RTSR = 0x00000000; + EXTI->FTSR = 0x00000000; + EXTI->SWIER = 0x00000000; + EXTI->PR = 0xE07FFFFF; + EXTI->IMR2 = 0x0000000C; + EXTI->EMR2 = 0x00000000; + EXTI->RTSR2 = 0x00000000; + EXTI->FTSR2 = 0x00000000; + EXTI->SWIER2 = 0x00000000; + EXTI->PR2 = 0x00000003; +} + +/** + * @brief Initializes the EXTI peripheral according to the specified + * parameters in the EXTI_InitStruct. + * EXTI_Line specifies the EXTI line (EXTI0....EXTI35). + * EXTI_Mode specifies which EXTI line is used as interrupt or an event. + * EXTI_Trigger selects the trigger. When the trigger occurs, interrupt + * pending bit will be set. + * EXTI_LineCmd controls (Enable/Disable) the EXTI line. + * @param EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure that + * contains the configuration information for the EXTI peripheral. + * @retval None + */ + + +void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct) +{ + uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_EXTI_MODE(EXTI_InitStruct->EXTI_Mode)); + assert_param(IS_EXTI_TRIGGER(EXTI_InitStruct->EXTI_Trigger)); + assert_param(IS_EXTI_LINE_ALL(EXTI_InitStruct->EXTI_Line)); + assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->EXTI_LineCmd)); + + tmp = (uint32_t)EXTI_BASE; + + if (EXTI_InitStruct->EXTI_LineCmd != DISABLE) + { + /* Clear EXTI line configuration */ + *(__IO uint32_t *) (((uint32_t) &(EXTI->IMR)) + ((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20) &= ~(uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F)); + *(__IO uint32_t *) (((uint32_t) &(EXTI->EMR)) + ((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20) &= ~(uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F)); + + tmp += EXTI_InitStruct->EXTI_Mode + (((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20); + + *(__IO uint32_t *) tmp |= (uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F)); + + tmp = (uint32_t)EXTI_BASE; + + /* Clear Rising Falling edge configuration */ + *(__IO uint32_t *) (((uint32_t) &(EXTI->RTSR)) + ((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20) &= ~(uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F)); + *(__IO uint32_t *) (((uint32_t) &(EXTI->FTSR)) + ((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20) &= ~(uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F)); + + /* Select the trigger for the selected interrupts */ + if (EXTI_InitStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling) + { + /* Rising Falling edge */ + *(__IO uint32_t *) (((uint32_t) &(EXTI->RTSR)) + ((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20) |= (uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F)); + *(__IO uint32_t *) (((uint32_t) &(EXTI->FTSR)) + ((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20) |= (uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F)); + } + else + { + tmp += EXTI_InitStruct->EXTI_Trigger + (((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20); + + *(__IO uint32_t *) tmp |= (uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F)); + } + } + + else + { + tmp += EXTI_InitStruct->EXTI_Mode + (((EXTI_InitStruct->EXTI_Line) >> 5 ) * 0x20); + + /* Disable the selected external lines */ + *(__IO uint32_t *) tmp &= ~(uint32_t)(1 << (EXTI_InitStruct->EXTI_Line & 0x1F)); + } + +} + +/** + * @brief Fills each EXTI_InitStruct member with its reset value. + * @param EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct) +{ + EXTI_InitStruct->EXTI_Line = EXTI_LINENONE; + EXTI_InitStruct->EXTI_Mode = EXTI_Mode_Interrupt; + EXTI_InitStruct->EXTI_Trigger = EXTI_Trigger_Rising_Falling; + EXTI_InitStruct->EXTI_LineCmd = DISABLE; +} + +/** + * @brief Generates a Software interrupt on selected EXTI line. + * @param EXTI_Line: specifies the EXTI line on which the software interrupt + * will be generated. + * This parameter can be any combination of EXTI_Linex where x can be (0..20). + * @retval None + */ +void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE_EXT(EXTI_Line)); + + *(__IO uint32_t *) (((uint32_t) &(EXTI->SWIER)) + ((EXTI_Line) >> 5 ) * 0x20) |= (uint32_t)(1 << (EXTI_Line & 0x1F)); + +} + +/** + * @} + */ + +/** @defgroup EXTI_Group2 Interrupts and flags management functions + * @brief EXTI Interrupts and flags management functions + * +@verbatim + =============================================================================== + ##### Interrupts and flags management functions ##### + =============================================================================== + [..] + This section provides functions allowing to configure the EXTI Interrupts + sources and check or clear the flags or pending bits status. + +@endverbatim + * @{ + */ + +/** + * @brief Checks whether the specified EXTI line flag is set or not. + * @param EXTI_Line: specifies the EXTI line flag to check. + * This parameter can be any combination of EXTI_Linex where x can be (0..20). + * @retval The new state of EXTI_Line (SET or RESET). + */ +FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_GET_EXTI_LINE(EXTI_Line)); + + if ((*(__IO uint32_t *) (((uint32_t) &(EXTI->PR)) + ((EXTI_Line) >> 5 ) * 0x20)& (uint32_t)(1 << (EXTI_Line & 0x1F))) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the EXTI's line pending flags. + * @param EXTI_Line: specifies the EXTI lines flags to clear. + * This parameter can be any combination of EXTI_Linex where x can be (0..20). + * @retval None + */ +void EXTI_ClearFlag(uint32_t EXTI_Line) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE_EXT(EXTI_Line)); + + *(__IO uint32_t *) (((uint32_t) &(EXTI->PR)) + ((EXTI_Line) >> 5 ) * 0x20) = (1 << (EXTI_Line & 0x1F)); +} + +/** + * @brief Checks whether the specified EXTI line is asserted or not. + * @param EXTI_Line: specifies the EXTI line to check. + * This parameter can be any combination of EXTI_Linex where x can be (0..20). + * @retval The new state of EXTI_Line (SET or RESET). + */ +ITStatus EXTI_GetITStatus(uint32_t EXTI_Line) +{ + ITStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_GET_EXTI_LINE(EXTI_Line)); + + if ((*(__IO uint32_t *) (((uint32_t) &(EXTI->PR)) + ((EXTI_Line) >> 5 ) * 0x20)& (uint32_t)(1 << (EXTI_Line & 0x1F))) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; + +} + +/** + * @brief Clears the EXTI's line pending bits. + * @param EXTI_Line: specifies the EXTI lines to clear. + * This parameter can be any combination of EXTI_Linex where x can be (0..20). + * @retval None + */ +void EXTI_ClearITPendingBit(uint32_t EXTI_Line) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE_EXT(EXTI_Line)); + + *(__IO uint32_t *) (((uint32_t) &(EXTI->PR)) + ((EXTI_Line) >> 5 ) * 0x20) = (1 << (EXTI_Line & 0x1F)); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_flash.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_flash.c new file mode 100644 index 0000000..20b9782 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_flash.c @@ -0,0 +1,1170 @@ +/** + ****************************************************************************** + * @file stm32f30x_flash.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the FLASH peripheral: + * + FLASH Interface configuration + * + FLASH Memory Programming + * + Option Bytes Programming + * + Interrupts and flags management + * + @verbatim + + =============================================================================== + ##### How to use this driver ##### + =============================================================================== + [..] This driver provides functions to configure and program the FLASH + memory of all STM32F30x devices. These functions are split in 4 groups: + (#) FLASH Interface configuration functions: this group includes the + management of following features: + (++) Set the latency. + (++) Enable/Disable the Half Cycle Access. + (++) Enable/Disable the prefetch buffer. + (#) FLASH Memory Programming functions: this group includes all needed + functions to erase and program the main memory: + (++) Lock and Unlock the FLASH interface. + (++) Erase function: Erase page, erase all pages. + (++) Program functions: Half Word and Word write. + (#) FLASH Option Bytes Programming functions: this group includes all + needed functions to manage the Option Bytes: + (++) Lock and Unlock the Flash Option bytes. + (++) Launch the Option Bytes loader + (++) Erase the Option Bytes + (++) Set/Reset the write protection + (++) Set the Read protection Level + (++) Program the user option Bytes + (++) Set/Reset the BOOT1 bit + (++) Enable/Disable the VDDA Analog Monitoring + (++) Enable/Disable the SRAM parity + (++) Get the user option bytes + (++) Get the Write protection + (++) Get the read protection status + (#) FLASH Interrupts and flags management functions: this group includes + all needed functions to: + (++) Enable/Disable the FLASH interrupt sources. + (++) Get flags status. + (++) Clear flags. + (++) Get FLASH operation status. + (++) Wait for last FLASH operation. + + @endverbatim + + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_flash.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup FLASH + * @brief FLASH driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* FLASH Mask */ +#define RDPRT_MASK ((uint32_t)0x00000002) +#define WRP01_MASK ((uint32_t)0x0000FFFF) +#define WRP23_MASK ((uint32_t)0xFFFF0000) +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup FLASH_Private_Functions + * @{ + */ + +/** @defgroup FLASH_Group1 FLASH Interface configuration functions + * @brief FLASH Interface configuration functions + * + +@verbatim + =============================================================================== + ##### FLASH Interface configuration functions ##### + =============================================================================== + [..] This group includes the following functions: + (+) void FLASH_SetLatency(uint32_t FLASH_Latency); + (+) void FLASH_HalfCycleAccessCmd(uint32_t FLASH_HalfCycleAccess); + (+) void FLASH_PrefetchBufferCmd(FunctionalState NewState); + [..] The unlock sequence is not needed for these functions. + +@endverbatim + * @{ + */ + +/** + * @brief Sets the code latency value. + * @param FLASH_Latency: specifies the FLASH Latency value. + * This parameter can be one of the following values: + * @arg FLASH_Latency_0: FLASH Zero Latency cycle + * @arg FLASH_Latency_1: FLASH One Latency cycle + * @arg FLASH_Latency_2: FLASH Two Latency cycles + * @retval None + */ +void FLASH_SetLatency(uint32_t FLASH_Latency) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_FLASH_LATENCY(FLASH_Latency)); + + /* Read the ACR register */ + tmpreg = FLASH->ACR; + + /* Sets the Latency value */ + tmpreg &= (uint32_t) (~((uint32_t)FLASH_ACR_LATENCY)); + tmpreg |= FLASH_Latency; + + /* Write the ACR register */ + FLASH->ACR = tmpreg; +} + +/** + * @brief Enables or disables the Half cycle flash access. + * @param FLASH_HalfCycleAccess: specifies the FLASH Half cycle Access mode. + * This parameter can be one of the following values: + * @arg FLASH_HalfCycleAccess_Enable: FLASH Half Cycle Enable + * @arg FLASH_HalfCycleAccess_Disable: FLASH Half Cycle Disable + * @retval None + */ +void FLASH_HalfCycleAccessCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if(NewState != DISABLE) + { + FLASH->ACR |= FLASH_ACR_HLFCYA; + } + else + { + FLASH->ACR &= (uint32_t)(~((uint32_t)FLASH_ACR_HLFCYA)); + } +} + +/** + * @brief Enables or disables the Prefetch Buffer. + * @param NewState: new state of the Prefetch Buffer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FLASH_PrefetchBufferCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if(NewState != DISABLE) + { + FLASH->ACR |= FLASH_ACR_PRFTBE; + } + else + { + FLASH->ACR &= (uint32_t)(~((uint32_t)FLASH_ACR_PRFTBE)); + } +} + +/** + * @} + */ + +/** @defgroup FLASH_Group2 FLASH Memory Programming functions + * @brief FLASH Memory Programming functions + * +@verbatim + =============================================================================== + ##### FLASH Memory Programming functions ##### + =============================================================================== + [..] This group includes the following functions: + (+) void FLASH_Unlock(void); + (+) void FLASH_Lock(void); + (+) FLASH_Status FLASH_ErasePage(uint32_t Page_Address); + (+) FLASH_Status FLASH_EraseAllPages(void); + (+) FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data); + (+) FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data); + [..] Any operation of erase or program should follow these steps: + (#) Call the FLASH_Unlock() function to enable the FLASH control register + program memory access. + (#) Call the desired function to erase page or program data. + (#) Call the FLASH_Lock() function to disable the FLASH control register + access (recommended to protect the FLASH memory against possible + unwanted operation). + +@endverbatim + * @{ + */ + +/** + * @brief Unlocks the FLASH control register access + * @param None + * @retval None + */ +void FLASH_Unlock(void) +{ + if((FLASH->CR & FLASH_CR_LOCK) != RESET) + { + /* Authorize the FLASH Registers access */ + FLASH->KEYR = FLASH_KEY1; + FLASH->KEYR = FLASH_KEY2; + } +} + +/** + * @brief Locks the FLASH control register access + * @param None + * @retval None + */ +void FLASH_Lock(void) +{ + /* Set the LOCK Bit to lock the FLASH Registers access */ + FLASH->CR |= FLASH_CR_LOCK; +} + +/** + * @brief Erases a specified page in program memory. + * @note To correctly run this function, the FLASH_Unlock() function + * must be called before. + * @note Call the FLASH_Lock() to disable the flash memory access + * (recommended to protect the FLASH memory against possible unwanted operation) + * @param Page_Address: The page address in program memory to be erased. + * @note A Page is erased in the Program memory only if the address to load + * is the start address of a page (multiple of 1024 bytes). + * @retval FLASH Status: The returned value can be: + * FLASH_ERROR_PROGRAM, FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ErasePage(uint32_t Page_Address) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_FLASH_PROGRAM_ADDRESS(Page_Address)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + /* If the previous operation is completed, proceed to erase the page */ + FLASH->CR |= FLASH_CR_PER; + FLASH->AR = Page_Address; + FLASH->CR |= FLASH_CR_STRT; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + /* Disable the PER Bit */ + FLASH->CR &= ~FLASH_CR_PER; + } + + /* Return the Erase Status */ + return status; +} + +/** + * @brief Erases all FLASH pages. + * @note To correctly run this function, the FLASH_Unlock() function + * must be called before. + * all the FLASH_Lock() to disable the flash memory access + * (recommended to protect the FLASH memory against possible unwanted operation) + * @param None + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EraseAllPages(void) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR |= FLASH_CR_MER; + FLASH->CR |= FLASH_CR_STRT; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + /* Disable the MER Bit */ + FLASH->CR &= ~FLASH_CR_MER; + } + + /* Return the Erase Status */ + return status; +} + +/** + * @brief Programs a word at a specified address. + * @note To correctly run this function, the FLASH_Unlock() function + * must be called before. + * Call the FLASH_Lock() to disable the flash memory access + * (recommended to protect the FLASH memory against possible unwanted operation) + * @param Address: specifies the address to be programmed. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_FLASH_PROGRAM_ADDRESS(Address)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + /* If the previous operation is completed, proceed to program the new first + half word */ + FLASH->CR |= FLASH_CR_PG; + + *(__IO uint16_t*)Address = (uint16_t)Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + /* If the previous operation is completed, proceed to program the new second + half word */ + tmp = Address + 2; + + *(__IO uint16_t*) tmp = Data >> 16; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + /* Disable the PG Bit */ + FLASH->CR &= ~FLASH_CR_PG; + } + else + { + /* Disable the PG Bit */ + FLASH->CR &= ~FLASH_CR_PG; + } + } + + /* Return the Program Status */ + return status; +} + +/** + * @brief Programs a half word at a specified address. + * @note To correctly run this function, the FLASH_Unlock() function + * must be called before. + * Call the FLASH_Lock() to disable the flash memory access + * (recommended to protect the FLASH memory against possible unwanted operation) + * @param Address: specifies the address to be programmed. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_FLASH_PROGRAM_ADDRESS(Address)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + /* If the previous operation is completed, proceed to program the new data */ + FLASH->CR |= FLASH_CR_PG; + + *(__IO uint16_t*)Address = Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + /* Disable the PG Bit */ + FLASH->CR &= ~FLASH_CR_PG; + } + + /* Return the Program Status */ + return status; +} + +/** + * @} + */ + +/** @defgroup FLASH_Group3 Option Bytes Programming functions + * @brief Option Bytes Programming functions + * +@verbatim + =============================================================================== + ##### Option Bytes Programming functions ##### + =============================================================================== + [..] This group includes the following functions: + (+) void FLASH_OB_Unlock(void); + (+) void FLASH_OB_Lock(void); + (+) void FLASH_OB_Erase(void); + (+) FLASH_Status FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState); + (+) FLASH_Status FLASH_OB_RDPConfig(uint8_t OB_RDP); + (+) FLASH_Status FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY); + (+) FLASH_Status FLASH_OB_BOOTConfig(uint8_t OB_BOOT1); + (+) FLASH_Status FLASH_OB_VDDAConfig(uint8_t OB_VDDA_ANALOG); + (+) FLASH_Status FLASH_OB_SRMParityConfig(uint8_t OB_SRAM_Parity); + (+) FLASH_Status FLASH_OB_WriteUser(uint8_t OB_USER); + (+) FLASH_Status FLASH_OB_Launch(void); + (+) uint32_t FLASH_OB_GetUser(void); + (+) uint8_t FLASH_OB_GetWRP(void); + (+) uint8_t FLASH_OB_GetRDP(void); + [..] Any operation of erase or program should follow these steps: + (#) Call the FLASH_OB_Unlock() function to enable the FLASH option control + register access. + (#) Call one or several functions to program the desired Option Bytes: + (++) void FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState); + => to Enable/Disable the desired sector write protection. + (++) FLASH_Status FLASH_OB_RDPConfig(uint8_t OB_RDP) => to set the + desired read Protection Level. + (++) FLASH_Status FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY); + => to configure the user Option Bytes. + (++) FLASH_Status FLASH_OB_BOOTConfig(uint8_t OB_BOOT1); + => to set the boot1 mode + (++) FLASH_Status FLASH_OB_VDDAConfig(uint8_t OB_VDDA_ANALOG); + => to Enable/Disable the VDDA monotoring. + (++) FLASH_Status FLASH_OB_SRMParityConfig(uint8_t OB_SRAM_Parity); + => to Enable/Disable the SRAM Parity check. + (++) FLASH_Status FLASH_OB_WriteUser(uint8_t OB_USER); + => to write all user option bytes: OB_IWDG, OB_STOP, OB_STDBY, + OB_BOOT1, OB_VDDA_ANALOG and OB_VDD_SD12. + (#) Once all needed Option Bytes to be programmed are correctly written, + call the FLASH_OB_Launch() function to launch the Option Bytes + programming process. + (#@) When changing the IWDG mode from HW to SW or from SW to HW, a system + reset is needed to make the change effective. + (#) Call the FLASH_OB_Lock() function to disable the FLASH option control + register access (recommended to protect the Option Bytes against + possible unwanted operations). + +@endverbatim + * @{ + */ + +/** + * @brief Unlocks the option bytes block access. + * @param None + * @retval None + */ +void FLASH_OB_Unlock(void) +{ + if((FLASH->CR & FLASH_CR_OPTWRE) == RESET) + { + /* Unlocking the option bytes block access */ + FLASH->OPTKEYR = FLASH_OPTKEY1; + FLASH->OPTKEYR = FLASH_OPTKEY2; + } +} + +/** + * @brief Locks the option bytes block access. + * @param None + * @retval None + */ +void FLASH_OB_Lock(void) +{ + /* Set the OPTWREN Bit to lock the option bytes block access */ + FLASH->CR &= ~FLASH_CR_OPTWRE; +} + +/** + * @brief Launch the option byte loading. + * @param None + * @retval None + */ +void FLASH_OB_Launch(void) +{ + /* Set the OBL_Launch bit to launch the option byte loading */ + FLASH->CR |= FLASH_CR_OBL_LAUNCH; +} + +/** + * @brief Erases the FLASH option bytes. + * @note This functions erases all option bytes except the Read protection (RDP). + * @param None + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_OB_Erase(void) +{ + uint16_t rdptmp = OB_RDP_Level_0; + + FLASH_Status status = FLASH_COMPLETE; + + /* Get the actual read protection Option Byte value */ + if(FLASH_OB_GetRDP() != RESET) + { + rdptmp = 0x00; + } + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + /* If the previous operation is completed, proceed to erase the option bytes */ + FLASH->CR |= FLASH_CR_OPTER; + FLASH->CR |= FLASH_CR_STRT; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + /* If the erase operation is completed, disable the OPTER Bit */ + FLASH->CR &= ~FLASH_CR_OPTER; + + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= FLASH_CR_OPTPG; + + /* Restore the last read protection Option Byte value */ + OB->RDP = (uint16_t)rdptmp; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= ~FLASH_CR_OPTPG; + } + } + else + { + if (status != FLASH_TIMEOUT) + { + /* Disable the OPTPG Bit */ + FLASH->CR &= ~FLASH_CR_OPTPG; + } + } + } + /* Return the erase status */ + return status; +} + +/** + * @brief Write protects the desired pages + * @note To correctly run this function, the FLASH_OB_Unlock() function + * must be called before. + * @note Call the FLASH_OB_Lock() to disable the flash control register access and the option bytes + * (recommended to protect the FLASH memory against possible unwanted operation) + * @param OB_WRP: specifies the address of the pages to be write protected. + * This parameter can be: + * @arg value between OB_WRP_Pages0to35 and OB_WRP_Pages60to63 + * @arg OB_WRP_AllPages + * @retval FLASH Status: The returned value can be: + * FLASH_ERROR_PROGRAM, FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_OB_EnableWRP(uint32_t OB_WRP) +{ + uint16_t WRP0_Data = 0xFFFF, WRP1_Data = 0xFFFF; + + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_OB_WRP(OB_WRP)); + + OB_WRP = (uint32_t)(~OB_WRP); + WRP0_Data = (uint16_t)(OB_WRP & OB_WRP0_WRP0); + WRP1_Data = (uint16_t)((OB_WRP & OB_WRP0_nWRP0) >> 8); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + FLASH->CR |= FLASH_CR_OPTPG; + + if(WRP0_Data != 0xFF) + { + OB->WRP0 = WRP0_Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + } + if((status == FLASH_COMPLETE) && (WRP1_Data != 0xFF)) + { + OB->WRP1 = WRP1_Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + } + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= ~FLASH_CR_OPTPG; + } + } + /* Return the write protection operation Status */ + return status; +} + +/** + * @brief Enables or disables the read out protection. + * @note To correctly run this function, the FLASH_OB_Unlock() function + * must be called before. + * @note Call the FLASH_OB_Lock() to disable the flash control register access and the option bytes + * (recommended to protect the FLASH memory against possible unwanted operation) + * @param FLASH_ReadProtection_Level: specifies the read protection level. + * This parameter can be: + * @arg OB_RDP_Level_0: No protection + * @arg OB_RDP_Level_1: Read protection of the memory + * @arg OB_RDP_Level_2: Chip protection + * @retval FLASH Status: The returned value can be: + * FLASH_ERROR_PROGRAM, FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_OB_RDPConfig(uint8_t OB_RDP) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_OB_RDP(OB_RDP)); + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + FLASH->CR |= FLASH_CR_OPTER; + FLASH->CR |= FLASH_CR_STRT; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + /* If the erase operation is completed, disable the OPTER Bit */ + FLASH->CR &= ~FLASH_CR_OPTER; + + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= FLASH_CR_OPTPG; + + OB->RDP = OB_RDP; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= ~FLASH_CR_OPTPG; + } + } + else + { + if(status != FLASH_TIMEOUT) + { + /* Disable the OPTER Bit */ + FLASH->CR &= ~FLASH_CR_OPTER; + } + } + } + /* Return the protection operation Status */ + return status; +} + +/** + * @brief Programs the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY. + * @param OB_IWDG: Selects the IWDG mode + * This parameter can be one of the following values: + * @arg OB_IWDG_SW: Software IWDG selected + * @arg OB_IWDG_HW: Hardware IWDG selected + * @param OB_STOP: Reset event when entering STOP mode. + * This parameter can be one of the following values: + * @arg OB_STOP_NoRST: No reset generated when entering in STOP + * @arg OB_STOP_RST: Reset generated when entering in STOP + * @param OB_STDBY: Reset event when entering Standby mode. + * This parameter can be one of the following values: + * @arg OB_STDBY_NoRST: No reset generated when entering in STANDBY + * @arg OB_STDBY_RST: Reset generated when entering in STANDBY + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_OB_IWDG_SOURCE(OB_IWDG)); + assert_param(IS_OB_STOP_SOURCE(OB_STOP)); + assert_param(IS_OB_STDBY_SOURCE(OB_STDBY)); + + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= FLASH_CR_OPTPG; + + OB->USER = (uint8_t)((uint8_t)(OB_IWDG | OB_STOP) | (uint8_t)(OB_STDBY |0xF8)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= ~FLASH_CR_OPTPG; + } + } + /* Return the Option Byte program Status */ + return status; +} + +/** + * @brief Sets or resets the BOOT1. + * @param OB_BOOT1: Set or Reset the BOOT1. + * This parameter can be one of the following values: + * @arg OB_BOOT1_RESET: BOOT1 Reset + * @arg OB_BOOT1_SET: BOOT1 Set + * @retval None + */ +FLASH_Status FLASH_OB_BOOTConfig(uint8_t OB_BOOT1) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_OB_BOOT1(OB_BOOT1)); + + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= FLASH_CR_OPTPG; + + OB->USER = OB_BOOT1|0xEF; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= ~FLASH_CR_OPTPG; + } + } + /* Return the Option Byte program Status */ + return status; +} + +/** + * @brief Sets or resets the analogue monitoring on VDDA Power source. + * @param OB_VDDA_ANALOG: Selects the analog monitoring on VDDA Power source. + * This parameter can be one of the following values: + * @arg OB_VDDA_ANALOG_ON: Analog monitoring on VDDA Power source ON + * @arg OB_VDDA_ANALOG_OFF: Analog monitoring on VDDA Power source OFF + * @retval None + */ +FLASH_Status FLASH_OB_VDDAConfig(uint8_t OB_VDDA_ANALOG) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_OB_VDDA_ANALOG(OB_VDDA_ANALOG)); + + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= FLASH_CR_OPTPG; + + OB->USER = OB_VDDA_ANALOG |0xDF; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= ~FLASH_CR_OPTPG; + } + } + /* Return the Option Byte program Status */ + return status; +} + +/** + * @brief Sets or resets the SRAM partiy. + * @param OB_SRAM_Parity: Set or Reset the SRAM partiy enable bit. + * This parameter can be one of the following values: + * @arg OB_SRAM_PARITY_SET: Set SRAM partiy. + * @arg OB_SRAM_PARITY_RESET: Reset SRAM partiy. + * @retval None + */ +FLASH_Status FLASH_OB_SRAMParityConfig(uint8_t OB_SRAM_Parity) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_OB_SRAM_PARITY(OB_SRAM_Parity)); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= FLASH_CR_OPTPG; + + OB->USER = OB_SRAM_Parity | 0xBF; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= ~FLASH_CR_OPTPG; + } + } + /* Return the Option Byte program Status */ + return status; +} + +/** + * @brief Programs the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY/ BOOT1 and OB_VDDA_ANALOG. + * @note To correctly run this function, the FLASH_OB_Unlock() function + * must be called before. + * @note Call the FLASH_OB_Lock() to disable the flash control register access and the option bytes + * (recommended to protect the FLASH memory against possible unwanted operation) + * @param OB_USER: Selects all user option bytes + * This parameter is a combination of the following values: + * @arg OB_IWDG_SW / OB_IWDG_HW: Software / Hardware WDG selected + * @arg OB_STOP_NoRST / OB_STOP_RST: No reset / Reset generated when entering in STOP + * @arg OB_STDBY_NoRST / OB_STDBY_RST: No reset / Reset generated when entering in STANDBY + * @arg OB_BOOT1_RESET / OB_BOOT1_SET: BOOT1 Reset / Set + * @arg OB_VDDA_ANALOG_ON / OB_VDDA_ANALOG_OFF: Analog monitoring on VDDA Power source ON / OFF + * @retval FLASH Status: The returned value can be: + * FLASH_ERROR_PROGRAM, FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_OB_WriteUser(uint8_t OB_USER) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= FLASH_CR_OPTPG; + + OB->USER = OB_USER | 0x88; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= ~FLASH_CR_OPTPG; + } + } + /* Return the Option Byte program Status */ + return status; + +} + +/** + * @brief Programs a half word at a specified Option Byte Data address. + * @note To correctly run this function, the FLASH_OB_Unlock() function + * must be called before. + * Call the FLASH_OB_Lock() to disable the flash control register access and the option bytes + * (recommended to protect the FLASH memory against possible unwanted operation) + * @param Address: specifies the address to be programmed. + * This parameter can be 0x1FFFF804 or 0x1FFFF806. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ProgramOptionByteData(uint32_t Address, uint8_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Check the parameters */ + assert_param(IS_OB_DATA_ADDRESS(Address)); + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status == FLASH_COMPLETE) + { + /* Enables the Option Bytes Programming operation */ + FLASH->CR |= FLASH_CR_OPTPG; + *(__IO uint16_t*)Address = Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(FLASH_ER_PRG_TIMEOUT); + + if(status != FLASH_TIMEOUT) + { + /* If the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= ~FLASH_CR_OPTPG; + } + } + /* Return the Option Byte Data Program Status */ + return status; +} + +/** + * @brief Returns the FLASH User Option Bytes values. + * @param None + * @retval The FLASH User Option Bytes . + */ +uint8_t FLASH_OB_GetUser(void) +{ + /* Return the User Option Byte */ + return (uint8_t)(FLASH->OBR >> 8); +} + +/** + * @brief Returns the FLASH Write Protection Option Bytes value. + * @param None + * @retval The FLASH Write Protection Option Bytes value + */ +uint32_t FLASH_OB_GetWRP(void) +{ + /* Return the FLASH write protection Register value */ + return (uint32_t)(FLASH->WRPR); +} + +/** + * @brief Checks whether the FLASH Read out Protection Status is set or not. + * @param None + * @retval FLASH ReadOut Protection Status(SET or RESET) + */ +FlagStatus FLASH_OB_GetRDP(void) +{ + FlagStatus readstatus = RESET; + + if ((uint8_t)(FLASH->OBR & (FLASH_OBR_RDPRT1 | FLASH_OBR_RDPRT2)) != RESET) + { + readstatus = SET; + } + else + { + readstatus = RESET; + } + return readstatus; +} + +/** + * @} + */ + +/** @defgroup FLASH_Group4 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + ##### Interrupts and flags management functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified FLASH interrupts. + * @param FLASH_IT: specifies the FLASH interrupt sources to be enabled or + * disabled. + * This parameter can be any combination of the following values: + * @arg FLASH_IT_EOP: FLASH end of programming Interrupt + * @arg FLASH_IT_ERR: FLASH Error Interrupt + * @retval None + */ +void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FLASH_IT(FLASH_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if(NewState != DISABLE) + { + /* Enable the interrupt sources */ + FLASH->CR |= FLASH_IT; + } + else + { + /* Disable the interrupt sources */ + FLASH->CR &= ~(uint32_t)FLASH_IT; + } +} + +/** + * @brief Checks whether the specified FLASH flag is set or not. + * @param FLASH_FLAG: specifies the FLASH flag to check. + * This parameter can be one of the following values: + * @arg FLASH_FLAG_BSY: FLASH write/erase operations in progress flag + * @arg FLASH_FLAG_PGERR: FLASH Programming error flag flag + * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag + * @arg FLASH_FLAG_EOP: FLASH End of Programming flag + * @retval The new state of FLASH_FLAG (SET or RESET). + */ +FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_FLASH_GET_FLAG(FLASH_FLAG)); + + if((FLASH->SR & FLASH_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the new state of FLASH_FLAG (SET or RESET) */ + return bitstatus; +} + +/** + * @brief Clears the FLASH's pending flags. + * @param FLASH_FLAG: specifies the FLASH flags to clear. + * This parameter can be any combination of the following values: + * @arg FLASH_FLAG_PGERR: FLASH Programming error flag flag + * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag + * @arg FLASH_FLAG_EOP: FLASH End of Programming flag + * @retval None + */ +void FLASH_ClearFlag(uint32_t FLASH_FLAG) +{ + /* Check the parameters */ + assert_param(IS_FLASH_CLEAR_FLAG(FLASH_FLAG)); + + /* Clear the flags */ + FLASH->SR = FLASH_FLAG; +} + +/** + * @brief Returns the FLASH Status. + * @param None + * @retval FLASH Status: The returned value can be: + * FLASH_BUSY, FLASH_ERROR_PROGRAM, FLASH_ERROR_WRP or FLASH_COMPLETE. + */ +FLASH_Status FLASH_GetStatus(void) +{ + FLASH_Status FLASHstatus = FLASH_COMPLETE; + + if((FLASH->SR & FLASH_FLAG_BSY) == FLASH_FLAG_BSY) + { + FLASHstatus = FLASH_BUSY; + } + else + { + if((FLASH->SR & (uint32_t)FLASH_FLAG_WRPERR)!= (uint32_t)0x00) + { + FLASHstatus = FLASH_ERROR_WRP; + } + else + { + if((FLASH->SR & (uint32_t)(FLASH_SR_PGERR)) != (uint32_t)0x00) + { + FLASHstatus = FLASH_ERROR_PROGRAM; + } + else + { + FLASHstatus = FLASH_COMPLETE; + } + } + } + /* Return the FLASH Status */ + return FLASHstatus; +} + +/** + * @brief Waits for a FLASH operation to complete or a TIMEOUT to occur. + * @param Timeout: FLASH programming Timeout + * @retval FLASH Status: The returned value can be: FLASH_BUSY, + * FLASH_ERROR_PROGRAM, FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_WaitForLastOperation(uint32_t Timeout) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check for the FLASH Status */ + status = FLASH_GetStatus(); + + /* Wait for a FLASH operation to complete or a TIMEOUT to occur */ + while((status == FLASH_BUSY) && (Timeout != 0x00)) + { + status = FLASH_GetStatus(); + Timeout--; + } + + if(Timeout == 0x00 ) + { + status = FLASH_TIMEOUT; + } + /* Return the operation status */ + return status; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_gpio.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_gpio.c new file mode 100644 index 0000000..006b9c7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_gpio.c @@ -0,0 +1,535 @@ +/** + ****************************************************************************** + * @file stm32f30x_gpio.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the GPIO peripheral: + * + Initialization and Configuration functions + * + GPIO Read and Write functions + * + GPIO Alternate functions configuration functions + * + * @verbatim + + + =============================================================================== + ##### How to use this driver ##### + =============================================================================== + [..] + (#) Enable the GPIO AHB clock using RCC_AHBPeriphClockCmd() + (#) Configure the GPIO pin(s) using GPIO_Init() + Four possible configuration are available for each pin: + (++) Input: Floating, Pull-up, Pull-down. + (++) Output: Push-Pull (Pull-up, Pull-down or no Pull), + Open Drain (Pull-up, Pull-down or no Pull). + In output mode, the speed is configurable: Low, Medium, Fast or High. + (++) Alternate Function: Push-Pull (Pull-up, Pull-down or no Pull), + Open Drain (Pull-up, Pull-down or no Pull). + (++) Analog: required mode when a pin is to be used as ADC channel, + DAC output or comparator input. + (#) Peripherals alternate function: + (++) For ADC, DAC and comparators, configure the desired pin in + analog mode using GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AN + (++) For other peripherals (TIM, USART...): + (+++) Connect the pin to the desired peripherals' Alternate + Function (AF) using GPIO_PinAFConfig() function. + (+++) Configure the desired pin in alternate function mode using + GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF + (+++) Select the type, pull-up/pull-down and output speed via + GPIO_PuPd, GPIO_OType and GPIO_Speed members. + (+++) Call GPIO_Init() function. + (#) To get the level of a pin configured in input mode use GPIO_ReadInputDataBit() + (#) To set/reset the level of a pin configured in output mode use + GPIO_SetBits()/GPIO_ResetBits() + (#) During and just after reset, the alternate functions are not active + and the GPIO pins are configured in input floating mode (except JTAG pins). + (#) The LSE oscillator pins OSC32_IN and OSC32_OUT can be used as + general-purpose (PC14 and PC15, respectively) when the LSE + oscillator is off. The LSE has priority over the GPIO function. + (#) The HSE oscillator pins OSC_IN/OSC_OUT can be used as general-purpose + (PF0 and PF1 respectively) when the HSE oscillator is off. The HSE has + the priority over the GPIO function. + + @endverbatim + + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_gpio.h" +#include "stm32f30x_rcc.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup GPIO + * @brief GPIO driver modules + * @{ + */ + + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup GPIO_Private_Functions + * @{ + */ + +/** @defgroup GPIO_Group1 Initialization and Configuration + * @brief Initialization and Configuration + * +@verbatim + =============================================================================== + ##### Initialization and Configuration ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the GPIOx peripheral registers to their default reset + * values. + * @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral. + * @retval None + */ +void GPIO_DeInit(GPIO_TypeDef* GPIOx) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + if(GPIOx == GPIOA) + { + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOA, ENABLE); + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOA, DISABLE); + } + else if(GPIOx == GPIOB) + { + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOB, ENABLE); + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOB, DISABLE); + } + else if(GPIOx == GPIOC) + { + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOC, ENABLE); + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOC, DISABLE); + } + else if(GPIOx == GPIOD) + { + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOD, ENABLE); + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOD, DISABLE); + } + else if(GPIOx == GPIOE) + { + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOE, ENABLE); + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOE, DISABLE); + } + else + { + if(GPIOx == GPIOF) + { + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOF, ENABLE); + RCC_AHBPeriphResetCmd(RCC_AHBPeriph_GPIOF, DISABLE); + } + } +} + +/** + * @brief Initializes the GPIOx peripheral according to the specified + * parameters in the GPIO_InitStruct. + * @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral. + * @param GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure that + * contains the configuration information for the specified GPIO + * peripheral. + * @note GPIO_Pin: selects the pin to be configured: + * GPIO_Pin_0->GPIO_Pin_15 for GPIOA, GPIOB, GPIOC, GPIOD and GPIOE; + * GPIO_Pin_0->GPIO_Pin_2, GPIO_Pin_4, GPIO_Pin_6, GPIO_Pin_9 + * and GPIO_Pin_10 for GPIOF. + * @retval None + */ +void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct) +{ + uint32_t pinpos = 0x00, pos = 0x00 , currentpin = 0x00; + uint32_t tmpreg = 0x00; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_InitStruct->GPIO_Pin)); + assert_param(IS_GPIO_MODE(GPIO_InitStruct->GPIO_Mode)); + assert_param(IS_GPIO_PUPD(GPIO_InitStruct->GPIO_PuPd)); + + /*-------------------------- Configure the port pins -----------------------*/ + /*-- GPIO Mode Configuration --*/ + for (pinpos = 0x00; pinpos < 0x10; pinpos++) + { + pos = ((uint32_t)0x01) << pinpos; + + /* Get the port pins position */ + currentpin = (GPIO_InitStruct->GPIO_Pin) & pos; + + if (currentpin == pos) + { + if ((GPIO_InitStruct->GPIO_Mode == GPIO_Mode_OUT) || (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_AF)) + { + /* Check Speed mode parameters */ + assert_param(IS_GPIO_SPEED(GPIO_InitStruct->GPIO_Speed)); + + /* Speed mode configuration */ + GPIOx->OSPEEDR &= ~(GPIO_OSPEEDER_OSPEEDR0 << (pinpos * 2)); + GPIOx->OSPEEDR |= ((uint32_t)(GPIO_InitStruct->GPIO_Speed) << (pinpos * 2)); + + /* Check Output mode parameters */ + assert_param(IS_GPIO_OTYPE(GPIO_InitStruct->GPIO_OType)); + + /* Output mode configuration */ + GPIOx->OTYPER &= ~((GPIO_OTYPER_OT_0) << ((uint16_t)pinpos)); + GPIOx->OTYPER |= (uint16_t)(((uint16_t)GPIO_InitStruct->GPIO_OType) << ((uint16_t)pinpos)); + } + + GPIOx->MODER &= ~(GPIO_MODER_MODER0 << (pinpos * 2)); + + GPIOx->MODER |= (((uint32_t)GPIO_InitStruct->GPIO_Mode) << (pinpos * 2)); + + /* Use temporary variable to update PUPDR register configuration, to avoid + unexpected transition in the GPIO pin configuration. */ + tmpreg = GPIOx->PUPDR; + tmpreg &= ~(GPIO_PUPDR_PUPDR0 << ((uint16_t)pinpos * 2)); + tmpreg |= (((uint32_t)GPIO_InitStruct->GPIO_PuPd) << (pinpos * 2)); + GPIOx->PUPDR = tmpreg; + } + } +} + +/** + * @brief Fills each GPIO_InitStruct member with its default value. + * @param GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct) +{ + /* Reset GPIO init structure parameters values */ + GPIO_InitStruct->GPIO_Pin = GPIO_Pin_All; + GPIO_InitStruct->GPIO_Mode = GPIO_Mode_IN; + GPIO_InitStruct->GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStruct->GPIO_OType = GPIO_OType_PP; + GPIO_InitStruct->GPIO_PuPd = GPIO_PuPd_NOPULL; +} + +/** + * @brief Locks GPIO Pins configuration registers. + * The locked registers are GPIOx_MODER, GPIOx_OTYPER, GPIOx_OSPEEDR, + * GPIOx_PUPDR, GPIOx_AFRL and GPIOx_AFRH. + * @note The configuration of the locked GPIO pins can no longer be modified + * until the next reset. + * @param GPIOx: where x can be (A or B or D) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to be written. + * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). + * @retval None + */ +void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint32_t tmp = 0x00010000; + + /* Check the parameters */ + assert_param(IS_GPIO_LIST_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + tmp |= GPIO_Pin; + /* Set LCKK bit */ + GPIOx->LCKR = tmp; + /* Reset LCKK bit */ + GPIOx->LCKR = GPIO_Pin; + /* Set LCKK bit */ + GPIOx->LCKR = tmp; + /* Read LCKK bit */ + tmp = GPIOx->LCKR; + /* Read LCKK bit */ + tmp = GPIOx->LCKR; +} + +/** + * @} + */ + +/** @defgroup GPIO_Group2 GPIO Read and Write + * @brief GPIO Read and Write + * +@verbatim + =============================================================================== + ##### GPIO Read and Write ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Reads the specified input port pin. + * @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to read. + * @note This parameter can be GPIO_Pin_x where x can be : + * (0..15) for GPIOA, GPIOB, GPIOC, GPIOD or GPIOE; + * (0..2, 4, 6, 9..10) for GPIOF. + * @retval The input port pin value. + */ +uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint8_t bitstatus = 0x00; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + + if ((GPIOx->IDR & GPIO_Pin) != (uint32_t)Bit_RESET) + { + bitstatus = (uint8_t)Bit_SET; + } + else + { + bitstatus = (uint8_t)Bit_RESET; + } + return bitstatus; +} + +/** + * @brief Reads the specified input port pin. + * @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral. + * @retval The input port pin value. + */ +uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + return ((uint16_t)GPIOx->IDR); +} + +/** + * @brief Reads the specified output data port bit. + * @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral. + * @param GPIO_Pin: Specifies the port bit to read. + * @note This parameter can be GPIO_Pin_x where x can be : + * (0..15) for GPIOA, GPIOB, GPIOC, GPIOD or GPIOE; + * (0..2, 4, 6, 9..10) for GPIOF. + * @retval The output port pin value. + */ +uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint8_t bitstatus = 0x00; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + + if ((GPIOx->ODR & GPIO_Pin) != (uint32_t)Bit_RESET) + { + bitstatus = (uint8_t)Bit_SET; + } + else + { + bitstatus = (uint8_t)Bit_RESET; + } + return bitstatus; +} + +/** + * @brief Reads the specified GPIO output data port. + * @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral. + * @retval GPIO output data port value. + */ +uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + return ((uint16_t)GPIOx->ODR); +} + +/** + * @brief Sets the selected data port bits. + * @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bits to be written. + * @note This parameter can be GPIO_Pin_x where x can be : + * (0..15) for GPIOA, GPIOB, GPIOC, GPIOD or GPIOE; + * (0..2, 4, 6, 9..10) for GPIOF. + * @retval None + */ +void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + GPIOx->BSRR = GPIO_Pin; +} + +/** + * @brief Clears the selected data port bits. + * @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bits to be written. + * @note This parameter can be GPIO_Pin_x where x can be : + * (0..15) for GPIOA, GPIOB, GPIOC, GPIOD or GPIOE; + * (0..2, 4, 6, 9..10) for GPIOF. + * @retval None + */ +void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + GPIOx->BRR = GPIO_Pin; +} + +/** + * @brief Sets or clears the selected data port bit. + * @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to be written. + * @note This parameter can be GPIO_Pin_x where x can be : + * (0..15) for GPIOA, GPIOB, GPIOC, GPIOD or GPIOE; + * (0..2, 4, 6, 9..10) for GPIOF. + * @param BitVal: specifies the value to be written to the selected bit. + * This parameter can be one of the BitAction enumeration values: + * @arg Bit_RESET: to clear the port pin + * @arg Bit_SET: to set the port pin + * @retval None + */ +void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + assert_param(IS_GPIO_BIT_ACTION(BitVal)); + + if (BitVal != Bit_RESET) + { + GPIOx->BSRR = GPIO_Pin; + } + else + { + GPIOx->BRR = GPIO_Pin ; + } +} + +/** + * @brief Writes data to the specified GPIO data port. + * @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral. + * @param PortVal: specifies the value to be written to the port output data + * register. + * @retval None + */ +void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + GPIOx->ODR = PortVal; +} + +/** + * @} + */ + +/** @defgroup GPIO_Group3 GPIO Alternate functions configuration functions + * @brief GPIO Alternate functions configuration functions + * +@verbatim + =============================================================================== + ##### GPIO Alternate functions configuration functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Writes data to the specified GPIO data port. + * @param GPIOx: where x can be (A, B, C, D, E or F) to select the GPIO peripheral. + * @param GPIO_PinSource: specifies the pin for the Alternate function. + * This parameter can be GPIO_PinSourcex where x can be (0..15). + * @param GPIO_AF: selects the pin to be used as Alternate function. + * This parameter can be one of the following value: + * @arg GPIO_AF_0: JTCK-SWCLK, JTDI, JTDO/TRACESW0, JTMS-SWDAT, MCO, NJTRST, + * TRACED, TRACECK. + * @arg GPIO_AF_1: OUT, TIM2, TIM15, TIM16, TIM17. + * @arg GPIO_AF_2: COMP1_OUT, TIM1, TIM2, TIM3, TIM4, TIM8, TIM15, TIM16. + * @arg GPIO_AF_3: COMP7_OUT, TIM8, TIM15, Touch, HRTIM. + * @arg GPIO_AF_4: I2C1, I2C2, TIM1, TIM8, TIM16, TIM17. + * @arg GPIO_AF_5: IR_OUT, I2S2, I2S3, SPI1, SPI2, TIM8, USART4, USART5 + * @arg GPIO_AF_6: IR_OUT, I2S2, I2S3, SPI2, SPI3, TIM1, TIM8 + * @arg GPIO_AF_7: AOP2_OUT, CAN, COMP3_OUT, COMP5_OUT, COMP6_OUT, USART1, + * USART2, USART3. + * @arg GPIO_AF_8: COMP1_OUT, COMP2_OUT, COMP3_OUT, COMP4_OUT, COMP5_OUT, + * COMP6_OUT. + * @arg GPIO_AF_9: AOP4_OUT, CAN, TIM1, TIM8, TIM15. + * @arg GPIO_AF_10: AOP1_OUT, AOP3_OUT, TIM2, TIM3, TIM4, TIM8, TIM17. + * @arg GPIO_AF_11: TIM1, TIM8. + * @arg GPIO_AF_12: TIM1, HRTIM. + * @arg GPIO_AF_13: HRTIM, AOP2_OUT. + * @arg GPIO_AF_14: USBDM, USBDP. + * @arg GPIO_AF_15: OUT. + * @note The pin should already been configured in Alternate Function mode(AF) + * using GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF + * @note Refer to the Alternate function mapping table in the device datasheet + * for the detailed mapping of the system and peripherals alternate + * function I/O pins. + * @retval None + */ +void GPIO_PinAFConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF) +{ + uint32_t temp = 0x00; + uint32_t temp_2 = 0x00; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource)); + assert_param(IS_GPIO_AF(GPIO_AF)); + + temp = ((uint32_t)(GPIO_AF) << ((uint32_t)((uint32_t)GPIO_PinSource & (uint32_t)0x07) * 4)); + GPIOx->AFR[GPIO_PinSource >> 0x03] &= ~((uint32_t)0xF << ((uint32_t)((uint32_t)GPIO_PinSource & (uint32_t)0x07) * 4)); + temp_2 = GPIOx->AFR[GPIO_PinSource >> 0x03] | temp; + GPIOx->AFR[GPIO_PinSource >> 0x03] = temp_2; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_hrtim.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_hrtim.c new file mode 100644 index 0000000..a4fe59b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_hrtim.c @@ -0,0 +1,4124 @@ +/** + ****************************************************************************** + * @file stm32f30x_hrtim.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief HRTIMx module driver. + * + * This file provides firmware functions to manage the following + * functionalities of the HRTIMx peripheral: + * + Initialization/de-initialization methods + * + I/O operation methods + * + Peripheral Control methods + * + @verbatim +================================================================================ + ##### ##### +================================================================================ + + [..] < HRTIM introduction: + (#) The high-resolution timer can generate up to 10 digital signals with + highly accurate timings. + It is primarily intended to drive power conversion systems such as + switch mode power supplies or lighting systems, + but can be of general purpose usage, whenever a very fine timing + resolution is expected. + + (#) Its modular architecture allows to generate either independent or + coupled waveforms. + The wave-shape is defined by self-contained timings + (using counters and compare units) and a broad range of external events, + such as analog or digital feedbacks and synchronisation signals. + This allows to produce a large variety of control signal (PWM, phase-shifted, + constant Ton,...) and address most of conversion topologies. + + (#) For control and monitoring purposes, the timer has also timing measure + capabilities and links to built-in ADC and DAC converters. + Last, it features light-load management mode and is able to handle + various fault schemes for safe shut-down purposes. + + + ##### How to use this driver ##### +================================================================================ + [..] This driver provides functions to configure and program the HRTIM + of all stm32f33x devices. + These functions are split in 9 groups: + + (#) HRTIM Simple TimeBase management: this group includes all needed functions + to configure the HRTIM Timebase unit: + (++) Initializes the HRTIMx timer in simple time base mode + (++) Start/Stop the time base generation + (++) Deinitialize the HRTIM peripheral + + + (#) HRTIM simple Output Compare management: this group includes all needed + functions to configure the Compare unit used in Output compare mode: + (++) Initializes the HRTIMx timer time base unit + (++) Configure the compare unit in in simple Output Compare mode + (++) Start/Stop the Output compare generation + + (#) HRTIM simple PWM management: this group includes all needed + functions to configure the Compare unit used in PWM mode: + (++) Initializes the HRTIMx timer time base unit + (++) Configure the compare unit in in simple PWM mode + (++) Start/Stop the PWM generation + + (#) HRTIM simple Capture management: this group includes all needed + functions to configure the Capture unit used in Capture mode: + (++) Initializes the HRTIMx timer time base unit + (++) Configure the compare unit in in simple Capture mode + (++) Start/Stop the Capture mode + + (#) HRTIM simple One Pulse management: this group includes all needed + functions to configure the Capture unit and Compare unit used in One Pulse mode: + (++) Initializes the HRTIMx timer time base unit + (++) Configure the compare unit and the capture unit in in simple One Pulse mode + (++) Start/Stop the One Pulse mode generation + + (#) HRTIM Waveform management: this group includes all needed + functions to configure the HRTIM possible waveform mode: + (++) Initializes the HRTIMx timer Master time base unit + (++) Initializes the HRTIMx timer Slaves time base unit + (++) Configures the HRTIMx timer Compare unit + (++) Configures the HRTIMx Slave timer Capture unit + (++) Configures the HRTIMx timer Output unit + (++) Configures the HRTIMx timer DeadTime / Chopper / Burst features + (++) Configures the HRTIMx timer Fault / External event features + (++) Configures the HRTIMx timer Synchronization features: Internal/External connection, DACs,... + (++) Configures the HRTIMx timer Synchronization features: ADCs Triggers + (++) HRTIMx timer Outputs Start/Stop + (++) Start/Stop the HRTIMx Timer counters + + (#) HRTIM interrupts, DMA and flags management + (++) Enable/Disable interrupt sources + (++) Get flags status + (++) Clear flags/ Pending bits + (++) Enable/Disable DMA requests + (++) Configure DMA burst mode + + (#) TIM specific interface management, this group includes all + needed functions to use the specific TIM interface: + (++) HRTIMx timer DLL calibration + + @endverbatim + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_hrtim.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup HRTIM + * @brief HRTIM driver module + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define HRTIM_FLTR_FLTxEN (HRTIM_FLTR_FLT1EN |\ + HRTIM_FLTR_FLT2EN |\ + HRTIM_FLTR_FLT3EN |\ + HRTIM_FLTR_FLT4EN | \ + HRTIM_FLTR_FLT5EN) + +#define HRTIM_TIMCR_TIMUPDATETRIGGER (HRTIM_TIMUPDATETRIGGER_MASTER |\ + HRTIM_TIMUPDATETRIGGER_TIMER_A |\ + HRTIM_TIMUPDATETRIGGER_TIMER_B |\ + HRTIM_TIMUPDATETRIGGER_TIMER_C |\ + HRTIM_TIMUPDATETRIGGER_TIMER_D |\ + HRTIM_TIMUPDATETRIGGER_TIMER_E) + +#define HRTIM_TIM_OFFSET (uint32_t)0x00000080 +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +static uint32_t TimerIdxToTimerId[] = +{ + HRTIM_TIMERID_TIMER_A, + HRTIM_TIMERID_TIMER_B, + HRTIM_TIMERID_TIMER_C, + HRTIM_TIMERID_TIMER_D, + HRTIM_TIMERID_TIMER_E, + HRTIM_TIMERID_MASTER, +}; + +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +static void HRTIM_MasterBase_Config(HRTIM_TypeDef* HRTIMx, HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruc); +static void HRTIM_TimingUnitBase_Config(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruct); +static void HRTIM_MasterWaveform_Config(HRTIM_TypeDef * HRTIMx, HRTIM_TimerInitTypeDef * TimerInit); +static void HRTIM_TimingUnitWaveform_Config(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + HRTIM_TimerInitTypeDef * TimerInit); +static void HRTIM_CompareUnitConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t CompareUnit, + HRTIM_CompareCfgTypeDef * CompareCfg); +static void HRTIM_CaptureUnitConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t CaptureUnit, + uint32_t Event); +static void HRTIM_OutputConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t Output, + HRTIM_OutputCfgTypeDef * OutputCfg); +static void HRTIM_ExternalEventConfig(HRTIM_TypeDef * HRTIMx, + uint32_t Event, + HRTIM_EventCfgTypeDef * EventCfg); +static void HRTIM_TIM_ResetConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t Event); + /** @defgroup HRTIM_Private_Functions + * @{ + */ + +/** @defgroup HRTIM_Group1 Initialization/de-initialization methods + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization/de-initialization methods ##### + =============================================================================== + [..] This section provides functions allowing to: + (+)Initializes timer in basic time base mode + (+)Initializes timer in basic OC mode + (+)Initializes timer in basic PWM mode + (+)Initializes timer in basic Capture mode + (+)Initializes timer in One Pulse mode + (+)Initializes a timer operating in waveform mode + (+)De-initializes the HRTIMx timer + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the HRTIMx timer in basic time base mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 for master timer + * @arg 0x1 to 0x5 for timers A to E + * @note The time-base unit initialization parameters specify: + * The timer counter operating mode (continuous, one shot) + * The timer clock prescaler + * The timer period + * The timer repetition counter. + * @retval None + */ +void HRTIM_SimpleBase_Init(HRTIM_TypeDef* HRTIMx, uint32_t TimerIdx, HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruct) +{ + /* Check the parameters */ + assert_param(IS_HRTIM_TIMERINDEX(TimerIdx)); + assert_param(IS_HRTIM_MODE(HRTIM_BaseInitStruct->Mode)); + + if (TimerIdx == HRTIM_TIMERINDEX_MASTER) + { + /* Configure master timer */ + HRTIM_MasterBase_Config(HRTIMx, HRTIM_BaseInitStruct); + } + else + { + /* Configure timing unit */ + HRTIM_TimingUnitBase_Config(HRTIMx, TimerIdx, HRTIM_BaseInitStruct); + } +} + +/** + * @brief De-initializes a timer operating in all mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @retval None + */ +#ifdef __GNUC__ +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wunused-parameter" +#endif +void HRTIM_DeInit(HRTIM_TypeDef* HRTIMx) +{ + /* Check the parameters */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_HRTIM1, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_HRTIM1, DISABLE); + } +#ifdef __GNUC__ +# pragma GCC diagnostic pop +#endif + +/** + * @brief Initializes the HRTIMx timer in basic output compare mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x1 to 0x5 for timers A to E + * @note Initializes the time-base unit of the timer and prepare it to + * operate in output compare mode + * @retval None + */ +void HRTIM_SimpleOC_Init(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruct) +{ + /* Check the parameters */ + assert_param(IS_HRTIM_TIMERINDEX(TimerIdx)); + assert_param(IS_HRTIM_MODE(HRTIM_BaseInitStruct->Mode)); + + /* Configure timing unit */ + HRTIM_TimingUnitBase_Config(HRTIMx, TimerIdx, HRTIM_BaseInitStruct); +} + +/** + * @brief Initializes the HRTIMx timer in basic PWM mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x1 to 0x5 for timers A to E + * @note Initializes the time-base unit of the timer and prepare it to + * operate in capture mode + * @retval None + */ +void HRTIM_SimplePWM_Init(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruct) +{ + /* Check the parameters */ + assert_param(IS_HRTIM_TIMERINDEX(TimerIdx)); + assert_param(IS_HRTIM_MODE(HRTIM_BaseInitStruct->Mode)); + + /* Configure timing unit */ + HRTIM_TimingUnitBase_Config(HRTIMx, TimerIdx, HRTIM_BaseInitStruct); +} + +/** + * @brief Initializes a timer operating in basic capture mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x1 to 0x5 for timers A to E + * @retval None + */ +void HRTIM_SimpleCapture_Init(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruct) +{ + /* Check the parameters */ + assert_param(IS_HRTIM_TIMERINDEX(TimerIdx)); + assert_param(IS_HRTIM_MODE(HRTIM_BaseInitStruct->Mode)); + + /* Configure timing unit */ + HRTIM_TimingUnitBase_Config(HRTIMx, TimerIdx, HRTIM_BaseInitStruct); +} + +/** + * @brief Initializes the HRTIMx timer in basic one pulse mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x1 to 0x5 for timers A to E + * @note Initializes the time-base unit of the timer and prepare it to + * operate in one pulse mode. In this mode the counter operates + * in single shot mode (retriggerable or not) + * @retval None + */ +void HRTIM_SimpleOnePulse_Init(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruct) +{ + /* Check the parameters */ + assert_param(IS_HRTIM_TIMERINDEX(TimerIdx)); + assert_param(IS_HRTIM_MODE(HRTIM_BaseInitStruct->Mode)); + + /* Configure timing unit */ + HRTIM_TimingUnitBase_Config(HRTIMx, TimerIdx, HRTIM_BaseInitStruct); +} + +/** + * @brief Initializes a timer operating in waveform mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 for master timer + * @arg 0x1 to 0x5 for timers A to E + * @param pTimerInit: pointer to the timer initialization data structure + * @retval None + */ +void HRTIM_Waveform_Init(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruct, + HRTIM_TimerInitTypeDef* HRTIM_TimerInitStruct) +{ + /* Check the parameters */ + assert_param(IS_HRTIM_HALFMODE(HRTIM_TimerInitStruct->HalfModeEnable)); + assert_param(IS_HRTIM_SYNCSTART(HRTIM_TimerInitStruct->StartOnSync)); + assert_param(IS_HRTIM_SYNCRESET(HRTIM_TimerInitStruct->ResetOnSync)); + assert_param(IS_HRTIM_DACSYNC(HRTIM_TimerInitStruct->DACSynchro)); + assert_param(IS_HRTIM_PRELOAD(HRTIM_TimerInitStruct->PreloadEnable)); + assert_param(IS_HRTIM_TIMERBURSTMODE(HRTIM_TimerInitStruct->BurstMode)); + assert_param(IS_HRTIM_UPDATEONREPETITION(HRTIM_TimerInitStruct->RepetitionUpdate)); + + if (TimerIdx == HRTIM_TIMERINDEX_MASTER) + { + /* Check parameters */ + assert_param(IS_HRTIM_UPDATEGATING_MASTER(HRTIM_TimerInitStruct->UpdateGating)); + + /* Configure master timer */ + HRTIM_MasterBase_Config(HRTIMx, HRTIM_BaseInitStruct); + HRTIM_MasterWaveform_Config(HRTIMx, HRTIM_TimerInitStruct); + } + else + { + /* Check parameters */ + assert_param(IS_HRTIM_UPDATEGATING_TIM(HRTIM_TimerInitStruct->UpdateGating)); + + /* Configure timing unit */ + HRTIM_TimingUnitBase_Config(HRTIMx, TimerIdx, HRTIM_BaseInitStruct); + HRTIM_TimingUnitWaveform_Config(HRTIMx, TimerIdx, HRTIM_TimerInitStruct); + } +} + +/** + * @} + */ + +/** @defgroup HRTIM_Group2 I/O operation methods + * @brief Data transfers functions + * +@verbatim + =============================================================================== + ##### IO operation methods ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to manage the HRTIMx data + transfers. + (+) Starts the DLL calibration. + (+) Starts / stops the counter of a timer operating in basic time base mode + (+) Starts / stops the output compare signal generation on the designed timer output + (+) Starts / stops the PWM output signal generation on the designed timer output + (+) Enables / disables a basic capture on the designed capture unit + +@endverbatim + * @{ + */ + +/** + * @brief Starts the DLL calibration + * @param HRTIMx: pointer to HRTIMx peripheral + * @param CalibrationRate: DLL calibration period + * This parameter can be one of the following values: + * @arg HRTIM_SINGLE_CALIBRATION: One shot DLL calibration + * @arg HRTIM_CALIBRATIONRATE_7300: 7.3 ms + * @arg HRTIM_CALIBRATIONRATE_910: 910 us + * @arg HRTIM_CALIBRATIONRATE_114: 114 us + * @arg HRTIM_CALIBRATIONRATE_14: 14 us + * @retval None + */ +void HRTIM_DLLCalibrationStart(HRTIM_TypeDef * HRTIMx, uint32_t CalibrationRate) +{ + uint32_t HRTIM_dllcr; + + /* Check the parameters */ + assert_param(IS_HRTIM_CALIBRATIONRATE(CalibrationRate)); + + /* Configure DLL Calibration */ + HRTIM_dllcr = (HRTIMx->HRTIM_COMMON).DLLCR; + + if (CalibrationRate == HRTIM_SINGLE_CALIBRATION) + { + /* One shot DLL calibration */ + HRTIM_dllcr &= ~(HRTIM_DLLCR_CALEN); + HRTIM_dllcr |= HRTIM_DLLCR_CAL; + } + else + { + /* Periodic DLL calibration */ + HRTIM_dllcr &= ~(HRTIM_DLLCR_CALRTE | HRTIM_DLLCR_CAL); + HRTIM_dllcr |= (CalibrationRate | HRTIM_DLLCR_CALEN); + } + + /* Update HRTIMx register */ + HRTIMx->HRTIM_COMMON.DLLCR = HRTIM_dllcr; + +} +/** + * @brief Starts the counter of a timer operating in basic time base mode + * @param HRTIMx: pointer to HRTIM peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x5 for master timer + * @arg 0x0 to 0x4 for timers A to E + * @retval None + */ +void HRTIM_SimpleBaseStart(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx) +{ + /* Check the parameters */ + assert_param(IS_HRTIM_TIMERINDEX(TimerIdx)); + + /* Enable the timer counter */ + __HRTIM_ENABLE(HRTIMx, TimerIdxToTimerId[TimerIdx]); +} + +/** + * @brief Stops the counter of a timer operating in basic time base mode + * @param HRTIMx: pointer to HRTIM peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x5 for master timer + * @arg 0x0 to 0x4 for timers A to E + * @retval None + */ +void HRTIM_SimpleBaseStop(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx) +{ + /* Check the parameters */ + assert_param(IS_HRTIM_TIMERINDEX(TimerIdx)); + + /* Disable the timer counter */ + __HRTIM_DISABLE(HRTIMx, TimerIdxToTimerId[TimerIdx]); +} + +/** + * @brief Starts the output compare signal generation on the designed timer output + * @param HRTIMx: pointer to HRTIM peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param OCChannel: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TE1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TE2: Timer E - Output 2 + * @retval None + */ +void HRTIM_SimpleOCStart(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t OCChannel) +{ + /* Check the parameters */ + assert_param(IS_HRTIM_TIMER_OUTPUT(TimerIdx, OCChannel)); + + /* Enable the timer output */ + (HRTIMx->HRTIM_COMMON).OENR |= OCChannel; + + /* Enable the timer counter */ + __HRTIM_ENABLE(HRTIMx, TimerIdxToTimerId[TimerIdx]); + +} + +/** + * @brief Stops the output compare signal generation on the designed timer output + * @param HRTIMx: pointer to HRTIM peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param OCChannel: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TE1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TE2: Timer E - Output 2 + * @retval None + */ +void HRTIM_SimpleOCStop(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t OCChannel) +{ + /* Check the parameters */ + assert_param(IS_HRTIM_TIMER_OUTPUT(TimerIdx, OCChannel)); + + /* Disable the timer output */ + HRTIMx->HRTIM_COMMON.DISR |= OCChannel; + + /* Disable the timer counter */ + __HRTIM_DISABLE(HRTIMx, TimerIdxToTimerId[TimerIdx]); +} + +/** + * @brief Starts the PWM output signal generation on the designed timer output + * @param HRTIMx: pointer to HRTIM peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param PWMChannel: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TE1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TE2: Timer E - Output 2 + * @retval None + */ +void HRTIM_SimplePWMStart(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t PWMChannel) +{ + /* Check the parameters */ + assert_param(IS_HRTIM_TIMER_OUTPUT(TimerIdx, PWMChannel)); + + /* Enable the timer output */ + HRTIMx->HRTIM_COMMON.OENR |= PWMChannel; + + /* Enable the timer counter */ + __HRTIM_ENABLE(HRTIMx, TimerIdxToTimerId[TimerIdx]); +} + +/** + * @brief Stops the PWM output signal generation on the designed timer output + * @param HRTIMx: pointer to HRTIM peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param PWMChannel: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TE1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TE2: Timer E - Output 2 + * @retval None + */ +void HRTIM_SimplePWMStop(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t PWMChannel) +{ + /* Check the parameters */ + assert_param(IS_HRTIM_TIMER_OUTPUT(TimerIdx, PWMChannel)); + + /* Disable the timer output */ + HRTIMx->HRTIM_COMMON.DISR |= PWMChannel; + + /* Disable the timer counter */ + __HRTIM_DISABLE(HRTIMx, TimerIdxToTimerId[TimerIdx]); +} + +/** + * @brief Enables a basic capture on the designed capture unit + * @param HRTIMx: pointer to HRTIM peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param CaptureChannel: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_CAPTUREUNIT_1: Capture unit 1 + * @arg HRTIM_CAPTUREUNIT_2: Capture unit 2 + * @retval None + * @note The external event triggering the capture is available for all timing + * units. It can be used directly and is active as soon as the timing + * unit counter is enabled. + */ +#ifdef __GNUC__ +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wunused-parameter" +#endif +void HRTIM_SimpleCaptureStart(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t CaptureChannel) +{ + /* Enable the timer counter */ + __HRTIM_ENABLE(HRTIMx, TimerIdxToTimerId[TimerIdx]); + +} +#ifdef __GNUC__ +# pragma GCC diagnostic pop +#endif + +/** + * @brief Disables a basic capture on the designed capture unit + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param CaptureChannel: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_CAPTUREUNIT_1: Capture unit 1 + * @arg HRTIM_CAPTUREUNIT_2: Capture unit 2 + * @retval None + */ +void HRTIM_SimpleCaptureStop(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t CaptureChannel) +{ + /* Check the parameters */ + assert_param(IS_HRTIM_TIMING_UNIT(TimerIdx)); + assert_param(IS_HRTIM_CAPTUREUNIT(CaptureChannel)); + + /* Set the capture unit trigger */ + switch (CaptureChannel) + { + case HRTIM_CAPTUREUNIT_1: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CPT1xCR = HRTIM_CAPTURETRIGGER_NONE; + } + break; + case HRTIM_CAPTUREUNIT_2: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CPT2xCR = HRTIM_CAPTURETRIGGER_NONE; + } + break; + default: + break; + } + + /* Disable the timer counter */ + if ((HRTIMx->HRTIM_TIMERx[TimerIdx].CPT1xCR == HRTIM_CAPTURETRIGGER_NONE) && + (HRTIMx->HRTIM_TIMERx[TimerIdx].CPT2xCR == HRTIM_CAPTURETRIGGER_NONE)) + { + __HRTIM_DISABLE(HRTIMx, TimerIdxToTimerId[TimerIdx]); + } + +} + +/** + * @brief Enables the basic one pulse signal generation on the designed output + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param OnePulseChannel: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TE1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TE2: Timer E - Output 2 + * @retval None + */ +void HRTIM_SimpleOnePulseStart(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t OnePulseChannel) +{ + /* Check the parameters */ + assert_param(IS_HRTIM_TIMER_OUTPUT(TimerIdx, OnePulseChannel)); + + /* Enable the timer output */ + HRTIMx->HRTIM_COMMON.OENR |= OnePulseChannel; + + /* Enable the timer counter */ + __HRTIM_ENABLE(HRTIMx, TimerIdxToTimerId[TimerIdx]); +} + +/** + * @brief Disables the basic one pulse signal generation on the designed output + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param OnePulseChannel: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TE1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TE2: Timer E - Output 2 + * @retval None + */ +void HRTIM_SimpleOnePulseStop(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t OnePulseChannel) +{ + /* Check the parameters */ + assert_param(IS_HRTIM_TIMER_OUTPUT(TimerIdx, OnePulseChannel)); + + /* Disable the timer output */ + HRTIMx->HRTIM_COMMON.DISR |= OnePulseChannel; + + /* Disable the timer counter */ + __HRTIM_DISABLE(HRTIMx, TimerIdxToTimerId[TimerIdx]); +} + +/** + * @brief Starts the counter of the designated timer(s) operating in waveform mode + * Timers can be combined (ORed) to allow for simultaneous counter start + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimersToStart: Timer counter(s) to start + * This parameter can be any combination of the following values: + * @arg HRTIM_TIMERID_MASTER + * @arg HRTIM_TIMERID_TIMER_A + * @arg HRTIM_TIMERID_TIMER_B + * @arg HRTIM_TIMERID_TIMER_C + * @arg HRTIM_TIMERID_TIMER_D + * @arg HRTIM_TIMERID_TIMER_E + * @retval None + */ +void HRTIM_WaveformCounterStart(HRTIM_TypeDef * HRTIMx, + uint32_t TimersToStart) +{ + /* Enable timer(s) counter */ + HRTIMx->HRTIM_MASTER.MCR |= TimersToStart; +} + +/** + * @brief Stops the counter of the designated timer(s) operating in waveform mode + * Timers can be combined (ORed) to allow for simultaneous counter stop + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimersToStop: Timer counter(s) to stop + * This parameter can be any combination of the following values: + * @arg HRTIM_TIMERID_MASTER + * @arg HRTIM_TIMERID_TIMER_A + * @arg HRTIM_TIMERID_TIMER_B + * @arg HRTIM_TIMERID_TIMER_C + * @arg HRTIM_TIMERID_TIMER_D + * @arg HRTIM_TIMERID_TIMER_E + * @retval None + */ +void HRTIM_WaveformCounterStop(HRTIM_TypeDef * HRTIMx, + uint32_t TimersToStop) +{ + /* Disable timer(s) counter */ + HRTIMx->HRTIM_MASTER.MCR &= ~TimersToStop; +} + +/** + * @brief Enables the generation of the waveform signal on the designated output(s) + * Outputs can be combined (ORed) to allow for simultaneous output enabling + * @param HRTIMx: pointer to HRTIMx peripheral + * @param OutputsToStart: Timer output(s) to enable + * This parameter can be any combination of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TE1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TE2: Timer E - Output 2 + * @retval None + */ +void HRTIM_WaveformOutputStart(HRTIM_TypeDef * HRTIMx, + uint32_t OutputsToStart) +{ + /* Enable the HRTIM outputs */ + HRTIMx->HRTIM_COMMON.OENR = OutputsToStart; +} + +/** + * @brief Disables the generation of the waveform signal on the designated output(s) + * Outputs can be combined (ORed) to allow for simultaneous output disabling + * @param HRTIMx: pointer to HRTIMx peripheral + * @param OutputsToStop: Timer output(s) to disable + * This parameter can be any combination of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TE1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TE2: Timer E - Output 2 + * @retval None + */ +void HRTIM_WaveformOutputStop(HRTIM_TypeDef * HRTIMx, + uint32_t OutputsToStop) +{ + /* Disable the HRTIM outputs */ + HRTIMx->HRTIM_COMMON.DISR = OutputsToStop; +} + +/** + * @brief Enables or disables the Master and slaves interrupt request + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param HRTIM_IT: specifies the HRTIM interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg HRTIM_MASTER_IT_MCMP1: Master compare 1 interrupt source + * @arg HRTIM_MASTER_IT_MCMP2: Master compare 2 interrupt source + * @arg HRTIM_MASTER_IT_MCMP3: Master compare 3 interrupt Interrupt source + * @arg HRTIM_MASTER_IT_MCMP4: Master compare 4 Interrupt source + * @arg HRTIM_MASTER_IT_MREP: Master Repetition Interrupt source + * @arg HRTIM_MASTER_IT_SYNC: Synchronization input Interrupt source + * @arg HRTIM_MASTER_IT_MUPD: Master update Interrupt source + * @arg HRTIM_TIM_IT_CMP1: Timer compare 1 Interrupt source + * @arg HRTIM_TIM_IT_CMP2: Timer compare 2 Interrupt source + * @arg HRTIM_TIM_IT_CMP3: Timer compare 3 Interrupt source + * @arg HRTIM_TIM_IT_CMP4: Timer compare 4 Interrupt source + * @arg HRTIM_TIM_IT_REP: Timer repetition Interrupt source + * @arg HRTIM_TIM_IT_UPD: Timer update Interrupt source + * @arg HRTIM_TIM_IT_CPT1: Timer capture 1 Interrupt source + * @arg HRTIM_TIM_IT_CPT2: Timer capture 2 Interrupt source + * @arg HRTIM_TIM_IT_SET1: Timer output 1 set Interrupt source + * @arg HRTIM_TIM_IT_RST1: Timer output 1 reset Interrupt source + * @arg HRTIM_TIM_IT_SET2: Timer output 2 set Interrupt source + * @arg HRTIM_TIM_IT_RST2: Timer output 2 reset Interrupt source + * @arg HRTIM_TIM_IT_RST: Timer reset Interrupt source + * @arg HRTIM_TIM_IT_DLYPRT1: Timer delay protection Interrupt source + * @param NewState: new state of the TIM interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void HRTIM_ITConfig(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, uint32_t HRTIM_IT, FunctionalState NewState) +{ + assert_param(IS_HRTIM_TIMERINDEX(TimerIdx)); + + switch(TimerIdx) + { + case HRTIM_TIMERINDEX_MASTER: + { + if(NewState != DISABLE) + { + HRTIMx->HRTIM_MASTER.MDIER |= HRTIM_IT; + } + else + { + HRTIMx->HRTIM_MASTER.MDIER &= ~HRTIM_IT; + } + } + break; + case HRTIM_TIMERINDEX_TIMER_A: + case HRTIM_TIMERINDEX_TIMER_B: + case HRTIM_TIMERINDEX_TIMER_C: + case HRTIM_TIMERINDEX_TIMER_D: + case HRTIM_TIMERINDEX_TIMER_E: + { + if(NewState != DISABLE) + { + HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxDIER |= HRTIM_IT; + } + else + { + HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxDIER &= ~HRTIM_IT; + } + } + break; + + default: + break; + } +} + +/** + * @brief Enables or disables the common interrupt request + * @param HRTIMx: pointer to HRTIMx peripheral + * @param HRTIM_IT: specifies the HRTIM interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg HRTIM_IT_FLT1: Fault 1 interrupt source + * @arg HRTIM_IT_FLT2: Fault 2 interrupt source + * @arg HRTIM_IT_FLT3: Fault 3 interrupt Interrupt source + * @arg HRTIM_IT_FLT4: Fault 4 Interrupt source + * @arg HRTIM_IT_FLT5: Fault 5 Interrupt source + * @arg HRTIM_IT_SYSFLT: System Fault Interrupt source + * @arg HRTIM_IT_DLLRDY: DLL ready Interrupt source + * @arg HRTIM_IT_BMPER: Burst mode period Interrupt source + * @param NewState: new state of the TIM interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void HRTIM_ITCommonConfig(HRTIM_TypeDef * HRTIMx, uint32_t HRTIM_CommonIT, FunctionalState NewState) +{ + if(NewState != DISABLE) + { + HRTIMx->HRTIM_COMMON.IER |= HRTIM_CommonIT; + } + else + { + HRTIMx->HRTIM_COMMON.IER &= ~HRTIM_CommonIT; + } +} + +/** + * @brief Clears the Master and slaves interrupt flags + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param HRTIM_FLAG: specifies the HRTIM flags sources to be cleared. + * This parameter can be any combination of the following values: + * @arg HRTIM_MASTER_FLAG_MCMP1: Master compare 1 interrupt flag + * @arg HRTIM_MASTER_FLAG_MCMP2: Master compare 2 interrupt flag + * @arg HRTIM_MASTER_FLAG_MCMP3: Master compare 3 interrupt Interrupt flag + * @arg HRTIM_MASTER_FLAG_MCMP4: Master compare 4 Interrupt flag + * @arg HRTIM_MASTER_FLAG_MREP: Master Repetition Interrupt flag + * @arg HRTIM_MASTER_FLAG_SYNC: Synchronization input Interrupt flag + * @arg HRTIM_MASTER_FLAG_MUPD: Master update Interrupt flag + * @arg HRTIM_TIM_FLAG_CMP1: Timer compare 1 Interrupt flag + * @arg HRTIM_TIM_FLAG_CMP2: Timer compare 2 Interrupt flag + * @arg HRTIM_TIM_FLAG_CMP3: Timer compare 3 Interrupt flag + * @arg HRTIM_TIM_FLAG_CMP4: Timer compare 4 Interrupt flag + * @arg HRTIM_TIM_FLAG_REP: Timer repetition Interrupt flag + * @arg HRTIM_TIM_FLAG_UPD: Timer update Interrupt flag + * @arg HRTIM_TIM_FLAG_CPT1: Timer capture 1 Interrupt flag + * @arg HRTIM_TIM_FLAG_CPT2: Timer capture 2 Interrupt flag + * @arg HRTIM_TIM_FLAG_SET1: Timer output 1 set Interrupt flag + * @arg HRTIM_TIM_FLAG_RST1: Timer output 1 reset Interrupt flag + * @arg HRTIM_TIM_FLAG_SET2: Timer output 2 set Interrupt flag + * @arg HRTIM_TIM_FLAG_RST2: Timer output 2 reset Interrupt flag + * @arg HRTIM_TIM_FLAG_RST: Timer reset Interrupt flag + * @arg HRTIM_TIM_FLAG_DLYPRT1: Timer delay protection Interrupt flag + * @retval None + */ +void HRTIM_ClearFlag(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, uint32_t HRTIM_FLAG) +{ + assert_param(IS_HRTIM_TIMERINDEX(TimerIdx)); + + switch(TimerIdx) + { + case HRTIM_TIMERINDEX_MASTER: + { + HRTIMx->HRTIM_MASTER.MICR |= HRTIM_FLAG; + } + break; + case HRTIM_TIMERINDEX_TIMER_A: + case HRTIM_TIMERINDEX_TIMER_B: + case HRTIM_TIMERINDEX_TIMER_C: + case HRTIM_TIMERINDEX_TIMER_D: + case HRTIM_TIMERINDEX_TIMER_E: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxICR |= HRTIM_FLAG; + } + break; + + default: + break; + } +} + +/** + * @brief Clears the common interrupt flags + * @param HRTIMx: pointer to HRTIMx peripheral + * @param HRTIM_FLAG: specifies the HRTIM flags to be cleared. + * This parameter can be any combination of the following values: + * @arg HRTIM_FLAG_FLT1: Fault 1 interrupt flag + * @arg HRTIM_FLAG_FLT2: Fault 2 interrupt flag + * @arg HRTIM_FLAG_FLT3: Fault 3 interrupt Interrupt flag + * @arg HRTIM_FLAG_FLT4: Fault 4 Interrupt flag + * @arg HRTIM_FLAG_FLT5: Fault 5 Interrupt flag + * @arg HRTIM_FLAG_SYSFLT: System Fault Interrupt flag + * @arg HRTIM_FLAG_DLLRDY: DLL ready Interrupt flag + * @arg HRTIM_FLAG_BMPER: Burst mode period Interrupt flag + * @retval None + */ +void HRTIM_ClearCommonFlag(HRTIM_TypeDef * HRTIMx, uint32_t HRTIM_CommonFLAG) +{ + HRTIMx->HRTIM_COMMON.ICR |= HRTIM_CommonFLAG; +} + +/** + * @brief Clears the Master and slaves interrupt request pending bits + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param HRTIM_IT: specifies the HRTIM interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg HRTIM_MASTER_IT_MCMP1: Master compare 1 interrupt source + * @arg HRTIM_MASTER_IT_MCMP2: Master compare 2 interrupt source + * @arg HRTIM_MASTER_IT_MCMP3: Master compare 3 interrupt Interrupt source + * @arg HRTIM_MASTER_IT_MCMP4: Master compare 4 Interrupt source + * @arg HRTIM_MASTER_IT_MREP: Master Repetition Interrupt source + * @arg HRTIM_MASTER_IT_SYNC: Synchronization input Interrupt source + * @arg HRTIM_MASTER_IT_MUPD: Master update Interrupt source + * @arg HRTIM_TIM_IT_CMP1: Timer compare 1 Interrupt source + * @arg HRTIM_TIM_IT_CMP2: Timer compare 2 Interrupt source + * @arg HRTIM_TIM_IT_CMP3: Timer compare 3 Interrupt source + * @arg HRTIM_TIM_IT_CMP4: Timer compare 4 Interrupt source + * @arg HRTIM_TIM_IT_REP: Timer repetition Interrupt source + * @arg HRTIM_TIM_IT_UPD: Timer update Interrupt source + * @arg HRTIM_TIM_IT_CPT1: Timer capture 1 Interrupt source + * @arg HRTIM_TIM_IT_CPT2: Timer capture 2 Interrupt source + * @arg HRTIM_TIM_IT_SET1: Timer output 1 set Interrupt source + * @arg HRTIM_TIM_IT_RST1: Timer output 1 reset Interrupt source + * @arg HRTIM_TIM_IT_SET2: Timer output 2 set Interrupt source + * @arg HRTIM_TIM_IT_RST2: Timer output 2 reset Interrupt source + * @arg HRTIM_TIM_IT_RST: Timer reset Interrupt source + * @arg HRTIM_TIM_IT_DLYPRT: Timer delay protection Interrupt source + * @retval None + */ +void HRTIM_ClearITPendingBit(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, uint32_t HRTIM_IT) +{ + assert_param(IS_HRTIM_TIMERINDEX(TimerIdx)); + + switch(TimerIdx) + { + case HRTIM_TIMERINDEX_MASTER: + { + HRTIMx->HRTIM_MASTER.MICR |= HRTIM_IT; + } + break; + case HRTIM_TIMERINDEX_TIMER_A: + case HRTIM_TIMERINDEX_TIMER_B: + case HRTIM_TIMERINDEX_TIMER_C: + case HRTIM_TIMERINDEX_TIMER_D: + case HRTIM_TIMERINDEX_TIMER_E: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxICR |= HRTIM_IT; + } + break; + + default: + break; + } +} + +/** + * @brief Clears the common interrupt pending bits + * @param HRTIMx: pointer to HRTIMx peripheral + * @param HRTIM_IT: specifies the HRTIM interrupts sources to be cleared. + * This parameter can be any combination of the following values: + * @arg HRTIM_IT_FLT1: Fault 1 interrupt source + * @arg HRTIM_IT_FLT2: Fault 2 interrupt source + * @arg HRTIM_IT_FLT3: Fault 3 interrupt Interrupt source + * @arg HRTIM_IT_FLT4: Fault 4 Interrupt source + * @arg HRTIM_IT_FLT5: Fault 5 Interrupt source + * @arg HRTIM_IT_SYSFLT: System Fault Interrupt source + * @arg HRTIM_IT_DLLRDY: DLL ready Interrupt source + * @arg HRTIM_IT_BMPER: Burst mode period Interrupt source + * @retval None + */ +void HRTIM_ClearCommonITPendingBit(HRTIM_TypeDef * HRTIMx, uint32_t HRTIM_CommonIT) +{ + HRTIMx->HRTIM_COMMON.ICR |= HRTIM_CommonIT; +} + + +/** + * @brief Checks whether the specified HRTIM flag is set or not. + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param HRTIM_FLAG: specifies the HRTIM flags to check. + * This parameter can be any combination of the following values: + * @arg HRTIM_MASTER_FLAG_MCMP1: Master compare 1 interrupt flag + * @arg HRTIM_MASTER_FLAG_MCMP2: Master compare 2 interrupt flag + * @arg HRTIM_MASTER_FLAG_MCMP3: Master compare 3 interrupt Interrupt flag + * @arg HRTIM_MASTER_FLAG_MCMP4: Master compare 4 Interrupt flag + * @arg HRTIM_MASTER_FLAG_MREP: Master Repetition Interrupt flag + * @arg HRTIM_MASTER_FLAG_SYNC: Synchronization input Interrupt flag + * @arg HRTIM_MASTER_FLAG_MUPD: Master update Interrupt flag + * @arg HRTIM_TIM_FLAG_CMP1: Timer compare 1 Interrupt flag + * @arg HRTIM_TIM_FLAG_CMP2: Timer compare 2 Interrupt flag + * @arg HRTIM_TIM_FLAG_CMP3: Timer compare 3 Interrupt flag + * @arg HRTIM_TIM_FLAG_CMP4: Timer compare 4 Interrupt flag + * @arg HRTIM_TIM_FLAG_REP: Timer repetition Interrupt flag + * @arg HRTIM_TIM_FLAG_UPD: Timer update Interrupt flag + * @arg HRTIM_TIM_FLAG_CPT1: Timer capture 1 Interrupt flag + * @arg HRTIM_TIM_FLAG_CPT2: Timer capture 2 Interrupt flag + * @arg HRTIM_TIM_FLAG_SET1: Timer output 1 set Interrupt flag + * @arg HRTIM_TIM_FLAG_RST1: Timer output 1 reset Interrupt flag + * @arg HRTIM_TIM_FLAG_SET2: Timer output 2 set Interrupt flag + * @arg HRTIM_TIM_FLAG_RST2: Timer output 2 reset Interrupt flag + * @arg HRTIM_TIM_FLAG_RST: Timer reset Interrupt flag + * @arg HRTIM_TIM_FLAG_DLYPRT: Timer delay protection Interrupt flag + * @retval The new state of HRTIM_FLAG (SET or RESET). + */ +FlagStatus HRTIM_GetFlagStatus(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, uint32_t HRTIM_FLAG) +{ + assert_param(IS_HRTIM_TIMERINDEX(TimerIdx)); + + FlagStatus bitstatus = RESET; + + switch(TimerIdx) + { + case HRTIM_TIMERINDEX_MASTER: + { + if ((HRTIMx->HRTIM_MASTER.MISR & HRTIM_FLAG) != RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + break; + + case HRTIM_TIMERINDEX_TIMER_A: + case HRTIM_TIMERINDEX_TIMER_B: + case HRTIM_TIMERINDEX_TIMER_C: + case HRTIM_TIMERINDEX_TIMER_D: + case HRTIM_TIMERINDEX_TIMER_E: + { + if ((HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxISR & HRTIM_FLAG) != RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + break; + + default: + break; + } + return bitstatus; +} + +/** + * @brief Checks whether the specified HRTIM common flag is set or not. + * @param HRTIMx: pointer to HRTIMx peripheral + * @param HRTIM_FLAG: specifies the HRTIM flags to check. + * This parameter can be any combination of the following values: + * @arg HRTIM_FLAG_FLT1: Fault 1 interrupt flag + * @arg HRTIM_FLAG_FLT2: Fault 2 interrupt flag + * @arg HRTIM_FLAG_FLT3: Fault 3 interrupt Interrupt flag + * @arg HRTIM_FLAG_FLT4: Fault 4 Interrupt flag + * @arg HRTIM_FLAG_FLT5: Fault 5 Interrupt flag + * @arg HRTIM_FLAG_SYSFLT: System Fault Interrupt flag + * @arg HRTIM_FLAG_DLLRDY: DLL ready Interrupt flag + * @arg HRTIM_FLAG_BMPER: Burst mode period Interrupt flag + * @retval The new state of HRTIM_FLAG (SET or RESET). + */ +FlagStatus HRTIM_GetCommonFlagStatus(HRTIM_TypeDef * HRTIMx, uint32_t HRTIM_CommonFLAG) +{ + FlagStatus bitstatus = RESET; + + if((HRTIMx->HRTIM_COMMON.ISR & HRTIM_CommonFLAG) != RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Checks whether the specified HRTIM interrupt has occurred or not. + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param HRTIM_IT: specifies the HRTIM flags sources to be cleared. + * This parameter can be any combination of the following values: + * @arg HRTIM_MASTER_IT_MCMP1: Master compare 1 interrupt + * @arg HRTIM_MASTER_IT_MCMP2: Master compare 2 interrupt + * @arg HRTIM_MASTER_IT_MCMP3: Master compare 3 interrupt Interrupt + * @arg HRTIM_MASTER_IT_MCMP4: Master compare 4 Interrupt + * @arg HRTIM_MASTER_IT_MREP: Master Repetition Interrupt + * @arg HRTIM_MASTER_IT_SYNC: Synchronization input Interrupt + * @arg HRTIM_MASTER_IT_MUPD: Master update Interrupt + * @arg HRTIM_TIM_IT_CMP1: Timer compare 1 Interrupt + * @arg HRTIM_TIM_IT_CMP2: Timer compare 2 Interrupt + * @arg HRTIM_TIM_IT_CMP3: Timer compare 3 Interrupt + * @arg HRTIM_TIM_IT_CMP4: Timer compare 4 Interrupt + * @arg HRTIM_TIM_IT_REP: Timer repetition Interrupt + * @arg HRTIM_TIM_IT_UPD: Timer update Interrupt + * @arg HRTIM_TIM_IT_CPT1: Timer capture 1 Interrupt + * @arg HRTIM_TIM_IT_CPT2: Timer capture 2 Interrupt + * @arg HRTIM_TIM_IT_SET1: Timer output 1 set Interrupt + * @arg HRTIM_TIM_IT_RST1: Timer output 1 reset Interrupt + * @arg HRTIM_TIM_IT_SET2: Timer output 2 set Interrupt + * @arg HRTIM_TIM_IT_RST2: Timer output 2 reset Interrupt + * @arg HRTIM_TIM_IT_RST: Timer reset Interrupt + * @arg HRTIM_TIM_IT_DLYPRT: Timer delay protection Interrupt + * @retval The new state of the HRTIM_IT(SET or RESET). + */ +ITStatus HRTIM_GetITStatus(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, uint32_t HRTIM_IT) +{ + ITStatus bitstatus = RESET; + uint16_t itstatus = 0x0, itenable = 0x0; + + assert_param(IS_HRTIM_TIMERINDEX(TimerIdx)); + + switch(TimerIdx) + { + case HRTIM_TIMERINDEX_MASTER: + { + itstatus = HRTIMx->HRTIM_MASTER.MISR & HRTIM_IT; + + itenable = HRTIMx->HRTIM_MASTER.MDIER & HRTIM_IT; + if ((itstatus != (uint16_t)RESET) && (itenable != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + break; + + case HRTIM_TIMERINDEX_TIMER_A: + case HRTIM_TIMERINDEX_TIMER_B: + case HRTIM_TIMERINDEX_TIMER_C: + case HRTIM_TIMERINDEX_TIMER_D: + case HRTIM_TIMERINDEX_TIMER_E: + { + itstatus = HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxISR & HRTIM_IT; + + itenable = HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxDIER & HRTIM_IT; + if ((itstatus != (uint16_t)RESET) && (itenable != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + break; + + default: + break; + } + return bitstatus; +} + +/** + * @brief Checks whether the specified HRTIM common interrupt has occurred or not. + * @param HRTIMx: pointer to HRTIMx peripheral + * @param HRTIM_IT: specifies the HRTIM interrupt source to check. + * This parameter can be any combination of the following values: + * @arg HRTIM_IT_FLT1: Fault 1 interrupt + * @arg HRTIM_IT_FLT2: Fault 2 interrupt + * @arg HRTIM_IT_FLT3: Fault 3 interrupt Interrupt + * @arg HRTIM_IT_FLT4: Fault 4 Interrupt + * @arg HRTIM_IT_FLT5: Fault 5 Interrupt + * @arg HRTIM_IT_SYSFLT: System Fault Interrupt + * @arg HRTIM_IT_DLLRDY: DLL ready Interrupt flag + * @arg HRTIM_IT_BMPER: Burst mode period Interrupt + * @retval The new state of HRTIM_FLAG (SET or RESET). + */ +ITStatus HRTIM_GetCommonITStatus(HRTIM_TypeDef * HRTIMx, uint32_t HRTIM_CommonIT) +{ + ITStatus bitstatus = RESET; + uint16_t itstatus = 0x0, itenable = 0x0; + + itstatus = HRTIMx->HRTIM_COMMON.ISR & HRTIM_CommonIT; + itenable = HRTIMx->HRTIM_COMMON.IER & HRTIM_CommonIT; + + if ((itstatus != (uint16_t)RESET) && (itenable != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + + return bitstatus; +} + +/** + * @brief Enables or disables the HRTIMx's DMA Requests. + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param HRTIM_DMA: specifies the DMA Request sources. + * This parameter can be any combination of the following values: + * @arg HRTIM_MASTER_DMA_MCMP1: Master compare 1 DMA request source + * @arg HRTIM_MASTER_DMA_MCMP2: Master compare 2 DMA request source + * @arg HRTIM_MASTER_DMA_MCMP3: Master compare 3 DMA request source + * @arg HRTIM_MASTER_DMA_MCMP4: Master compare 4 DMA request source + * @arg HRTIM_MASTER_DMA_MREP: Master Repetition DMA request source + * @arg HRTIM_MASTER_DMA_SYNC: Synchronization input DMA request source + * @arg HRTIM_MASTER_DMA_MUPD:Master update DMA request source + * @arg HRTIM_TIM_DMA_CMP1: Timer compare 1 DMA request source + * @arg HRTIM_TIM_DMA_CMP2: Timer compare 2 DMA request source + * @arg HRTIM_TIM_DMA_CMP3: Timer compare 3 DMA request source + * @arg HRTIM_TIM_DMA_CMP4: Timer compare 4 DMA request source + * @arg HRTIM_TIM_DMA_REP: Timer repetition DMA request source + * @arg HRTIM_TIM_DMA_UPD: Timer update DMA request source + * @arg HRTIM_TIM_DMA_CPT1: Timer capture 1 DMA request source + * @arg HRTIM_TIM_DMA_CPT2: Timer capture 2 DMA request source + * @arg HRTIM_TIM_DMA_SET1: Timer output 1 set DMA request source + * @arg HRTIM_TIM_DMA_RST1: Timer output 1 reset DMA request source + * @arg HRTIM_TIM_DMA_SET2: Timer output 2 set DMA request source + * @arg HRTIM_TIM_DMA_RST2: Timer output 2 reset DMA request source + * @arg HRTIM_TIM_DMA_RST: Timer reset DMA request source + * @arg HRTIM_TIM_DMA_DLYPRT: Timer delay protection DMA request source + * @param NewState: new state of the DMA Request sources. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void HRTIM_DMACmd(HRTIM_TypeDef* HRTIMx, uint32_t TimerIdx, uint32_t HRTIM_DMA, FunctionalState NewState) +{ + assert_param(IS_HRTIM_TIMERINDEX(TimerIdx)); + + switch(TimerIdx) + { + case HRTIM_TIMERINDEX_MASTER: + { + if(NewState != DISABLE) + { + HRTIMx->HRTIM_MASTER.MDIER |= HRTIM_DMA; + } + else + { + HRTIMx->HRTIM_MASTER.MDIER &= ~HRTIM_DMA; + } + } + break; + case HRTIM_TIMERINDEX_TIMER_A: + case HRTIM_TIMERINDEX_TIMER_B: + case HRTIM_TIMERINDEX_TIMER_C: + case HRTIM_TIMERINDEX_TIMER_D: + case HRTIM_TIMERINDEX_TIMER_E: + { + if(NewState != DISABLE) + { + HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxDIER |= HRTIM_DMA; + } + else + { + HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxDIER &= ~HRTIM_DMA; + } + } + break; + + default: + break; + } +} + +/** + * @} + */ + +/** @defgroup HRTIM_Group3 Peripheral Control methods + * @brief management functions + * +@verbatim + =============================================================================== + ##### Peripheral Control methods ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to control the HRTIMx data + transfers. + +@endverbatim + * @{ + */ + +/** + * @brief Configures an output in basic output compare mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param OCChannel: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TE1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TE2: Timer E - Output 2 + * @param pBasicOCChannelCfg: pointer to the basic output compare output configuration structure + * @note When the timer operates in basic output compare mode: + * Output 1 is implicitely controled by the compare unit 1 + * Output 2 is implicitely controled by the compare unit 2 + * Output Set/Reset crossbar is set according to the selected output compare mode: + * Toggle: SETxyR = RSTxyR = CMPy + * Active: SETxyR = CMPy, RSTxyR = 0 + * Inactive: SETxy =0, RSTxy = CMPy + * @retval None + */ +void HRTIM_SimpleOCChannelConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t OCChannel, + HRTIM_BasicOCChannelCfgTypeDef* pBasicOCChannelCfg) +{ + uint32_t CompareUnit = HRTIM_COMPAREUNIT_1; + HRTIM_CompareCfgTypeDef CompareCfg; + HRTIM_OutputCfgTypeDef OutputCfg; + + /* Check parameters */ + assert_param(IS_HRTIM_TIMER_OUTPUT(TimerIdx, OCChannel)); + assert_param(IS_HRTIM_BASICOCMODE(pBasicOCChannelCfg->Mode)); + assert_param(IS_HRTIM_OUTPUTPOLARITY(pBasicOCChannelCfg->Polarity)); + assert_param(IS_HRTIM_OUTPUTIDLESTATE(pBasicOCChannelCfg->IdleState)); + + /* Configure timer compare unit */ + switch (OCChannel) + { + case HRTIM_OUTPUT_TA1: + case HRTIM_OUTPUT_TB1: + case HRTIM_OUTPUT_TC1: + case HRTIM_OUTPUT_TD1: + case HRTIM_OUTPUT_TE1: + { + CompareUnit = HRTIM_COMPAREUNIT_1; + } + break; + case HRTIM_OUTPUT_TA2: + case HRTIM_OUTPUT_TB2: + case HRTIM_OUTPUT_TC2: + case HRTIM_OUTPUT_TD2: + case HRTIM_OUTPUT_TE2: + { + CompareUnit = HRTIM_COMPAREUNIT_2; + } + break; + default: + break; + } + + CompareCfg.CompareValue = pBasicOCChannelCfg->Pulse; + CompareCfg.AutoDelayedMode = HRTIM_AUTODELAYEDMODE_REGULAR; + CompareCfg.AutoDelayedTimeout = 0; + + HRTIM_CompareUnitConfig(HRTIMx, + TimerIdx, + CompareUnit, + &CompareCfg); + + /* Configure timer output */ + OutputCfg.Polarity = pBasicOCChannelCfg->Polarity; + OutputCfg.IdleState = pBasicOCChannelCfg->IdleState; + OutputCfg.FaultState = HRTIM_OUTPUTFAULTSTATE_NONE; + OutputCfg.IdleMode = HRTIM_OUTPUTIDLEMODE_NONE; + OutputCfg.ChopperModeEnable = HRTIM_OUTPUTCHOPPERMODE_DISABLED; + OutputCfg.BurstModeEntryDelayed = HRTIM_OUTPUTBURSTMODEENTRY_REGULAR; + + switch (pBasicOCChannelCfg->Mode) + { + case HRTIM_BASICOCMODE_TOGGLE: + { + if (CompareUnit == HRTIM_COMPAREUNIT_1) + { + OutputCfg.SetSource = HRTIM_OUTPUTSET_TIMCMP1; + } + else + { + OutputCfg.SetSource = HRTIM_OUTPUTSET_TIMCMP2; + } + OutputCfg.ResetSource = OutputCfg.SetSource; + } + break; + case HRTIM_BASICOCMODE_ACTIVE: + { + if (CompareUnit == HRTIM_COMPAREUNIT_1) + { + OutputCfg.SetSource = HRTIM_OUTPUTSET_TIMCMP1; + } + else + { + OutputCfg.SetSource = HRTIM_OUTPUTSET_TIMCMP2; + } + OutputCfg.ResetSource = HRTIM_OUTPUTRESET_NONE; + } + break; + case HRTIM_BASICOCMODE_INACTIVE: + { + if (CompareUnit == HRTIM_COMPAREUNIT_1) + { + OutputCfg.ResetSource = HRTIM_OUTPUTRESET_TIMCMP1; + } + else + { + OutputCfg.ResetSource = HRTIM_OUTPUTRESET_TIMCMP2; + } + OutputCfg.SetSource = HRTIM_OUTPUTSET_NONE; + } + break; + default: + break; + } + + HRTIM_OutputConfig(HRTIMx, TimerIdx, OCChannel, &OutputCfg); +} + +/** + * @brief Configures an output in basic PWM mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param PWMChannel: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TE1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TE2: Timer E - Output 2 + * @param pBasicPWMChannelCfg: pointer to the basic PWM output configuration structure + * @note When the timer operates in basic PWM output mode: + * Output 1 is implicitly controled by the compare unit 1 + * Output 2 is implicitly controled by the compare unit 2 + * Output Set/Reset crossbar is set as follows: + * Output 1: SETx1R = CMP1, RSTx1R = PER + * Output 2: SETx2R = CMP2, RST2R = PER + * @retval None + */ +void HRTIM_SimplePWMChannelConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t PWMChannel, + HRTIM_BasicPWMChannelCfgTypeDef* pBasicPWMChannelCfg) +{ + uint32_t CompareUnit = HRTIM_COMPAREUNIT_1; + HRTIM_CompareCfgTypeDef CompareCfg; + HRTIM_OutputCfgTypeDef OutputCfg; + + /* Check parameters */ + assert_param(IS_HRTIM_TIMER_OUTPUT(TimerIdx, PWMChannel)); + assert_param(IS_HRTIM_OUTPUTPOLARITY(pBasicPWMChannelCfg->Polarity)); + assert_param(IS_HRTIM_OUTPUTIDLESTATE(pBasicPWMChannelCfg->IdleState)); + + /* Configure timer compare unit */ + switch (PWMChannel) + { + case HRTIM_OUTPUT_TA1: + case HRTIM_OUTPUT_TB1: + case HRTIM_OUTPUT_TC1: + case HRTIM_OUTPUT_TD1: + case HRTIM_OUTPUT_TE1: + { + CompareUnit = HRTIM_COMPAREUNIT_1; + } + break; + case HRTIM_OUTPUT_TA2: + case HRTIM_OUTPUT_TB2: + case HRTIM_OUTPUT_TC2: + case HRTIM_OUTPUT_TD2: + case HRTIM_OUTPUT_TE2: + { + CompareUnit = HRTIM_COMPAREUNIT_2; + } + break; + default: + break; + } + + CompareCfg.CompareValue = pBasicPWMChannelCfg->Pulse; + CompareCfg.AutoDelayedMode = HRTIM_AUTODELAYEDMODE_REGULAR; + CompareCfg.AutoDelayedTimeout = 0; + + HRTIM_CompareUnitConfig(HRTIMx, + TimerIdx, + CompareUnit, + &CompareCfg); + + /* Configure timer output */ + OutputCfg.Polarity = pBasicPWMChannelCfg->Polarity; + OutputCfg.IdleState = pBasicPWMChannelCfg->IdleState; + OutputCfg.FaultState = HRTIM_OUTPUTFAULTSTATE_NONE; + OutputCfg.IdleMode = HRTIM_OUTPUTIDLEMODE_NONE; + OutputCfg.ChopperModeEnable = HRTIM_OUTPUTCHOPPERMODE_DISABLED; + OutputCfg.BurstModeEntryDelayed = HRTIM_OUTPUTBURSTMODEENTRY_REGULAR; + + if (CompareUnit == HRTIM_COMPAREUNIT_1) + { + OutputCfg.SetSource = HRTIM_OUTPUTSET_TIMCMP1; + } + else + { + OutputCfg.SetSource = HRTIM_OUTPUTSET_TIMCMP2; + } + OutputCfg.ResetSource = HRTIM_OUTPUTSET_TIMPER; + + HRTIM_OutputConfig(HRTIMx, TimerIdx, PWMChannel, &OutputCfg); +} + +/** + * @brief Configures a basic capture + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param CaptureChannel: Capture unit + * This parameter can be one of the following values: + * @arg HRTIM_CAPTUREUNIT_1: Capture unit 1 + * @arg HRTIM_CAPTUREUNIT_2: Capture unit 2 + * @param pBasicCaptureChannelCfg: pointer to the basic capture configuration structure + * @note When the timer operates in basic capture mode the capture is triggered + * by the designated external event and GPIO input is implicitly used as event source. + * The cature can be triggered by a rising edge, a falling edge or both + * edges on event channel. + * @retval None + */ +void HRTIM_SimpleCaptureChannelConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t CaptureChannel, + HRTIM_BasicCaptureChannelCfgTypeDef* pBasicCaptureChannelCfg) +{ + HRTIM_EventCfgTypeDef EventCfg; + + /* Check parameters */ + assert_param(IS_HRTIM_TIMING_UNIT(TimerIdx)); + assert_param(IS_HRTIM_CAPTUREUNIT(CaptureChannel)); + assert_param(IS_HRTIM_EVENT(pBasicCaptureChannelCfg->Event)); + assert_param(IS_HRTIM_EVENTPOLARITY(pBasicCaptureChannelCfg->EventPolarity)); + assert_param(IS_HRTIM_EVENTSENSITIVITY(pBasicCaptureChannelCfg->EventSensitivity)); + assert_param(IS_HRTIM_EVENTFILTER(pBasicCaptureChannelCfg->EventFilter)); + + /* Configure external event channel */ + EventCfg.FastMode = HRTIM_EVENTFASTMODE_DISABLE; + EventCfg.Filter = pBasicCaptureChannelCfg->EventFilter; + EventCfg.Polarity = pBasicCaptureChannelCfg->EventPolarity; + EventCfg.Sensitivity = pBasicCaptureChannelCfg->EventSensitivity; + EventCfg.Source = HRTIM_EVENTSRC_1; + + HRTIM_ExternalEventConfig(HRTIMx, + pBasicCaptureChannelCfg->Event, + &EventCfg); + + /* Memorize capture trigger (will be configured when the capture is started */ + HRTIM_CaptureUnitConfig(HRTIMx, + TimerIdx, + CaptureChannel, + pBasicCaptureChannelCfg->Event); +} + +/** + * @brief Configures an output basic one pulse mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param OnePulseChannel: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TE1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TE2: Timer E - Output 2 + * @param pBasicOnePulseChannelCfg: pointer to the basic one pulse output configuration structure + * @note When the timer operates in basic one pulse mode: + * the timer counter is implicitly started by the reset event, + * the reset of the timer counter is triggered by the designated external event + * GPIO input is implicitly used as event source, + * Output 1 is implicitly controled by the compare unit 1, + * Output 2 is implicitly controled by the compare unit 2. + * Output Set/Reset crossbar is set as follows: + * Output 1: SETx1R = CMP1, RSTx1R = PER + * Output 2: SETx2R = CMP2, RST2R = PER + * The counter mode should be HRTIM_MODE_SINGLESHOT_RETRIGGERABLE + * @retval None + */ +void HRTIM_SimpleOnePulseChannelConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t OnePulseChannel, + HRTIM_BasicOnePulseChannelCfgTypeDef* pBasicOnePulseChannelCfg) +{ + uint32_t CompareUnit = HRTIM_COMPAREUNIT_1; + HRTIM_CompareCfgTypeDef CompareCfg; + HRTIM_OutputCfgTypeDef OutputCfg; + HRTIM_EventCfgTypeDef EventCfg; + + /* Check parameters */ + assert_param(IS_HRTIM_TIMER_OUTPUT(TimerIdx, OnePulseChannel)); + assert_param(IS_HRTIM_OUTPUTPOLARITY(pBasicOnePulseChannelCfg->OutputPolarity)); + assert_param(IS_HRTIM_OUTPUTIDLESTATE(pBasicOnePulseChannelCfg->OutputIdleState)); + assert_param(IS_HRTIM_EVENT(pBasicOnePulseChannelCfg->Event)); + assert_param(IS_HRTIM_EVENTPOLARITY(pBasicOnePulseChannelCfg->EventPolarity)); + assert_param(IS_HRTIM_EVENTSENSITIVITY(pBasicOnePulseChannelCfg->EventSensitivity)); + assert_param(IS_HRTIM_EVENTFILTER(pBasicOnePulseChannelCfg->EventFilter)); + + /* Configure timer compare unit */ + switch (OnePulseChannel) + { + case HRTIM_OUTPUT_TA1: + case HRTIM_OUTPUT_TB1: + case HRTIM_OUTPUT_TC1: + case HRTIM_OUTPUT_TD1: + case HRTIM_OUTPUT_TE1: + { + CompareUnit = HRTIM_COMPAREUNIT_1; + } + break; + case HRTIM_OUTPUT_TA2: + case HRTIM_OUTPUT_TB2: + case HRTIM_OUTPUT_TC2: + case HRTIM_OUTPUT_TD2: + case HRTIM_OUTPUT_TE2: + { + CompareUnit = HRTIM_COMPAREUNIT_2; + } + break; + default: + break; + } + + CompareCfg.CompareValue = pBasicOnePulseChannelCfg->Pulse; + CompareCfg.AutoDelayedMode = HRTIM_AUTODELAYEDMODE_REGULAR; + CompareCfg.AutoDelayedTimeout = 0; + + HRTIM_CompareUnitConfig(HRTIMx, + TimerIdx, + CompareUnit, + &CompareCfg); + + /* Configure timer output */ + OutputCfg.Polarity = pBasicOnePulseChannelCfg->OutputPolarity; + OutputCfg.IdleState = pBasicOnePulseChannelCfg->OutputIdleState; + OutputCfg.FaultState = HRTIM_OUTPUTFAULTSTATE_NONE; + OutputCfg.IdleMode = HRTIM_OUTPUTIDLEMODE_NONE; + OutputCfg.ChopperModeEnable = HRTIM_OUTPUTCHOPPERMODE_DISABLED; + OutputCfg.BurstModeEntryDelayed = HRTIM_OUTPUTBURSTMODEENTRY_REGULAR; + + if (CompareUnit == HRTIM_COMPAREUNIT_1) + { + OutputCfg.SetSource = HRTIM_OUTPUTSET_TIMCMP1; + } + else + { + OutputCfg.SetSource = HRTIM_OUTPUTSET_TIMCMP2; + } + OutputCfg.ResetSource = HRTIM_OUTPUTSET_TIMPER; + + HRTIM_OutputConfig(HRTIMx, + TimerIdx, + OnePulseChannel, + &OutputCfg); + + /* Configure external event channel */ + EventCfg.FastMode = HRTIM_EVENTFASTMODE_DISABLE; + EventCfg.Filter = pBasicOnePulseChannelCfg->EventFilter; + EventCfg.Polarity = pBasicOnePulseChannelCfg->EventPolarity; + EventCfg.Sensitivity = pBasicOnePulseChannelCfg->EventSensitivity; + EventCfg.Source = HRTIM_EVENTSRC_1; + + HRTIM_ExternalEventConfig(HRTIMx, + pBasicOnePulseChannelCfg->Event, + &EventCfg); + + /* Configure the timer reset register */ + HRTIM_TIM_ResetConfig(HRTIMx, + TimerIdx, + pBasicOnePulseChannelCfg->Event); +} + +/** + * @brief Configures the general behavior of a timer operating in waveform mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param pTimerCfg: pointer to the timer configuration structure + * @note When the timer operates in waveform mode, all the features supported by + * the HRTIMx are available without any limitation. + * @retval None + */ +void HRTIM_WaveformTimerConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + HRTIM_TimerCfgTypeDef * pTimerCfg) +{ + uint32_t HRTIM_timcr; + uint32_t HRTIM_timfltr; + uint32_t HRTIM_timoutr; + uint32_t HRTIM_timrstr; + + /* Check parameters */ + assert_param(IS_HRTIM_TIMING_UNIT(TimerIdx)); + assert_param(IS_HRTIM_TIMPUSHPULLMODE(pTimerCfg->PushPull)); + assert_param(IS_HRTIM_TIMFAULTENABLE(pTimerCfg->FaultEnable)); + assert_param(IS_HRTIM_TIMFAULTLOCK(pTimerCfg->FaultLock)); + assert_param(IS_HRTIM_TIMDEADTIMEINSERTION(pTimerCfg->DeadTimeInsertion)); + assert_param(IS_HRTIM_TIMDELAYEDPROTECTION(pTimerCfg->DelayedProtectionMode)); + assert_param(IS_HRTIM_TIMUPDATETRIGGER(pTimerCfg->UpdateTrigger)); + assert_param(IS_HRTIM_TIMRESETTRIGGER(pTimerCfg->ResetTrigger)); + assert_param(IS_HRTIM_TIMUPDATEONRESET(pTimerCfg->ResetUpdate)); + + /* Configure timing unit (Timer A to Timer E) */ + HRTIM_timcr = HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxCR; + HRTIM_timfltr = HRTIMx->HRTIM_TIMERx[TimerIdx].FLTxR; + HRTIM_timoutr = HRTIMx->HRTIM_TIMERx[TimerIdx].OUTxR; + HRTIM_timrstr = HRTIMx->HRTIM_TIMERx[TimerIdx].RSTxR; + + /* Set the push-pull mode */ + HRTIM_timcr &= ~(HRTIM_TIMCR_PSHPLL); + HRTIM_timcr |= pTimerCfg->PushPull; + + /* Enable/Disable registers update on timer counter reset */ + HRTIM_timcr &= ~(HRTIM_TIMCR_TRSTU); + HRTIM_timcr |= pTimerCfg->ResetUpdate; + + /* Set the timer update trigger */ + HRTIM_timcr &= ~(HRTIM_TIMCR_TIMUPDATETRIGGER); + HRTIM_timcr |= pTimerCfg->UpdateTrigger; + + /* Enable/Disable the fault channel at timer level */ + HRTIM_timfltr &= ~(HRTIM_FLTR_FLTxEN); + HRTIM_timfltr |= (pTimerCfg->FaultEnable & HRTIM_FLTR_FLTxEN); + + /* Lock/Unlock fault sources at timer level */ + HRTIM_timfltr &= ~(HRTIM_FLTR_FLTCLK); + HRTIM_timfltr |= pTimerCfg->FaultLock; + + /* Enable/Disable dead time insertion at timer level */ + HRTIM_timoutr &= ~(HRTIM_OUTR_DTEN); + HRTIM_timoutr |= pTimerCfg->DeadTimeInsertion; + + /* Enable/Disable delayed protection at timer level */ + HRTIM_timoutr &= ~(HRTIM_OUTR_DLYPRT| HRTIM_OUTR_DLYPRTEN); + HRTIM_timoutr |= pTimerCfg->DelayedProtectionMode; + + /* Set the timer counter reset trigger */ + HRTIM_timrstr = pTimerCfg->ResetTrigger; + + /* Update the HRTIMx registers */ + HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxCR = HRTIM_timcr; + HRTIMx->HRTIM_TIMERx[TimerIdx].FLTxR = HRTIM_timfltr; + HRTIMx->HRTIM_TIMERx[TimerIdx].OUTxR = HRTIM_timoutr; + HRTIMx->HRTIM_TIMERx[TimerIdx].RSTxR = HRTIM_timrstr; + } + +/** + * @brief Configures the compare unit of a timer operating in waveform mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * 0xFF for master timer + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param CompareUnit: Compare unit to configure + * This parameter can be one of the following values: + * @arg HRTIM_COMPAREUNIT_1: Compare unit 1 + * @arg HRTIM_COMPAREUNIT_2: Compare unit 2 + * @arg HRTIM_COMPAREUNIT_3: Compare unit 3 + * @arg HRTIM_COMPAREUNIT_4: Compare unit 4 + * @param pCompareCfg: pointer to the compare unit configuration structure + * @note When auto delayed mode is required for compare unit 2 or compare unit 4, + * application has to configure separately the capture unit. Capture unit + * to configure in that case depends on the compare unit auto delayed mode + * is applied to (see below): + * Auto delayed on output compare 2: capture unit 1 must be configured + * Auto delayed on output compare 4: capture unit 2 must be configured + * @retval None + */ + void HRTIM_WaveformCompareConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t CompareUnit, + HRTIM_CompareCfgTypeDef* pCompareCfg) +{ + uint32_t HRTIM_timcr; + + /* Check parameters */ + assert_param(IS_HRTIM_TIMING_UNIT(TimerIdx)); + assert_param(IS_HRTIM_COMPAREUNIT_AUTODELAYEDMODE(CompareUnit, pCompareCfg->AutoDelayedMode)); + + /* Configure the compare unit */ + switch (CompareUnit) + { + case HRTIM_COMPAREUNIT_1: + { + /* Set the compare value */ + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP1xR = pCompareCfg->CompareValue; + } + break; + case HRTIM_COMPAREUNIT_2: + { + /* Set the compare value */ + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP2xR = pCompareCfg->CompareValue; + + if (pCompareCfg->AutoDelayedMode != HRTIM_AUTODELAYEDMODE_REGULAR) + { + /* Configure auto-delayed mode */ + HRTIM_timcr = HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxCR; + HRTIM_timcr &= ~HRTIM_TIMCR_DELCMP2; + HRTIM_timcr |= pCompareCfg->AutoDelayedMode; + HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxCR = HRTIM_timcr; + + /* Set the compare value for timeout compare unit (if any) */ + if (pCompareCfg->AutoDelayedMode == HRTIM_AUTODELAYEDMODE_AUTODELAYED_TIMEOUTCMP1) + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP1xR = pCompareCfg->AutoDelayedTimeout; + } + else if (pCompareCfg->AutoDelayedMode == HRTIM_AUTODELAYEDMODE_AUTODELAYED_TIMEOUTCMP3) + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP3xR = pCompareCfg->AutoDelayedTimeout; + } + } + } + break; + case HRTIM_COMPAREUNIT_3: + { + /* Set the compare value */ + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP3xR = pCompareCfg->CompareValue; + } + break; + case HRTIM_COMPAREUNIT_4: + { + /* Set the compare value */ + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP4xR = pCompareCfg->CompareValue; + + if (pCompareCfg->AutoDelayedMode != HRTIM_AUTODELAYEDMODE_REGULAR) + { + /* Configure auto-delayed mode */ + HRTIM_timcr = HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxCR; + HRTIM_timcr &= ~HRTIM_TIMCR_DELCMP4; + HRTIM_timcr |= (pCompareCfg->AutoDelayedMode << 2); + HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxCR = HRTIM_timcr; + + /* Set the compare value for timeout compare unit (if any) */ + if (pCompareCfg->AutoDelayedMode == HRTIM_AUTODELAYEDMODE_AUTODELAYED_TIMEOUTCMP1) + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP1xR = pCompareCfg->AutoDelayedTimeout; + } + else if (pCompareCfg->AutoDelayedMode == HRTIM_AUTODELAYEDMODE_AUTODELAYED_TIMEOUTCMP3) + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP3xR = pCompareCfg->AutoDelayedTimeout; + } + } + } + break; + default: + break; + } +} + +/** + * @brief Sets the HRTIMx Master Comparex Register value + * @param HRTIMx: pointer to HRTIMx peripheral + * @param CompareUnit: Compare unit to configure + * This parameter can be one of the following values: + * @arg HRTIM_COMPAREUNIT_1: Compare unit 1 + * @arg HRTIM_COMPAREUNIT_2: Compare unit 2 + * @arg HRTIM_COMPAREUNIT_3: Compare unit 3 + * @arg HRTIM_COMPAREUNIT_4: Compare unit 4 + * @param Compare: specifies the Comparex register new value + * @retval None + */ +void HRTIM_MasterSetCompare(HRTIM_TypeDef * HRTIMx, + uint32_t CompareUnit, + uint32_t Compare) +{ + /* Check parameters */ + assert_param(IS_HRTIM_COMPAREUNIT(CompareUnit)); + + /* Configure the compare unit */ + switch (CompareUnit) + { + case HRTIM_COMPAREUNIT_1: + { + /* Set the compare value */ + HRTIMx->HRTIM_MASTER.MCMP1R = Compare; + } + break; + case HRTIM_COMPAREUNIT_2: + { + /* Set the compare value */ + HRTIMx->HRTIM_MASTER.MCMP2R = Compare; + } + break; + case HRTIM_COMPAREUNIT_3: + { + /* Set the compare value */ + HRTIMx->HRTIM_MASTER.MCMP3R = Compare; + } + break; + case HRTIM_COMPAREUNIT_4: + { + /* Set the compare value */ + HRTIMx->HRTIM_MASTER.MCMP4R = Compare; + } + break; + default: + break; + } +} + +/** + * @brief Sets the HRTIMx Slave Comparex Register value + * @param HRTIMx: pointer to HRTIMx peripheral + * @param CompareUnit: Compare unit to configure + * This parameter can be one of the following values: + * @arg HRTIM_COMPAREUNIT_1: Compare unit 1 + * @arg HRTIM_COMPAREUNIT_2: Compare unit 2 + * @arg HRTIM_COMPAREUNIT_3: Compare unit 3 + * @arg HRTIM_COMPAREUNIT_4: Compare unit 4 + * @param Compare: specifies the Comparex register new value + * @retval None + */ +void HRTIM_SlaveSetCompare(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t CompareUnit, + uint32_t Compare) +{ + /* Check parameters */ + assert_param(IS_HRTIM_COMPAREUNIT(CompareUnit)); + + /* Configure the compare unit */ + switch (CompareUnit) + { + case HRTIM_COMPAREUNIT_1: + { + /* Set the compare value */ + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP1xR = Compare; + } + break; + case HRTIM_COMPAREUNIT_2: + { + /* Set the compare value */ + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP2xR = Compare; + } + break; + case HRTIM_COMPAREUNIT_3: + { + /* Set the compare value */ + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP3xR = Compare; + } + break; + case HRTIM_COMPAREUNIT_4: + { + /* Set the compare value */ + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP4xR = Compare; + } + break; + default: + break; + } +} +/** + * @brief Configures the capture unit of a timer operating in waveform mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param CaptureChannel: Capture unit to configure + * This parameter can be one of the following values: + * @arg HRTIM_CAPTUREUNIT_1: Capture unit 1 + * @arg HRTIM_CAPTUREUNIT_2: Capture unit 2 + * @param pCaptureCfg: pointer to the compare unit configuration structure + * @retval None + */ +void HRTIM_WaveformCaptureConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t CaptureUnit, + HRTIM_CaptureCfgTypeDef* pCaptureCfg) +{ + /* Configure the capture unit */ + switch (CaptureUnit) + { + case HRTIM_CAPTUREUNIT_1: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CPT1xCR = pCaptureCfg->Trigger; + } + break; + case HRTIM_CAPTUREUNIT_2: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CPT2xCR = pCaptureCfg->Trigger; + } + break; + default: + break; + } +} + +/** + * @brief Configures the output of a timer operating in waveform mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param Output: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TE1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TE2: Timer E - Output 2 + * @param pOutputCfg: pointer to the timer output configuration structure + * @retval None + */ +void HRTIM_WaveformOutputConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t Output, + HRTIM_OutputCfgTypeDef * pOutputCfg) +{ + /* Check parameters */ + assert_param(IS_HRTIM_TIMER_OUTPUT(TimerIdx, Output)); + assert_param(IS_HRTIM_OUTPUTPOLARITY(pOutputCfg->Polarity)); + assert_param(IS_HRTIM_OUTPUTIDLESTATE(pOutputCfg->IdleState)); + assert_param(IS_HRTIM_OUTPUTIDLEMODE(pOutputCfg->IdleMode)); + assert_param(IS_HRTIM_OUTPUTFAULTSTATE(pOutputCfg->FaultState)); + assert_param(IS_HRTIM_OUTPUTCHOPPERMODE(pOutputCfg->ChopperModeEnable)); + assert_param(IS_HRTIM_OUTPUTBURSTMODEENTRY(pOutputCfg->BurstModeEntryDelayed)); + + /* Configure the timer output */ + HRTIM_OutputConfig(HRTIMx, TimerIdx, Output, pOutputCfg); +} + +/** + * @brief Configures the event filtering capabilities of a timer (blanking, windowing) + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param Event: external event for which timer event filtering must be configured + * This parameter can be one of the following values: + * @arg HRTIM_EVENT_1: External event 1 + * @arg HRTIM_EVENT_2: External event 2 + * @arg HRTIM_EVENT_3: External event 3 + * @arg HRTIM_EVENT_4: External event 4 + * @arg HRTIM_EVENT_5: External event 5 + * @arg HRTIM_EVENT_6: External event 6 + * @arg HRTIM_EVENT_7: External event 7 + * @arg HRTIM_EVENT_8: External event 8 + * @arg HRTIM_EVENT_9: External event 9 + * @arg HRTIM_EVENT_10: External event 10 + * @param pTimerEventFilteringCfg: pointer to the timer event filtering configuration structure + * @retval None + */ +void HRTIM_TimerEventFilteringConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t Event, + HRTIM_TimerEventFilteringCfgTypeDef* pTimerEventFilteringCfg) +{ + uint32_t HRTIM_eefr; + + /* Check parameters */ + assert_param(IS_HRTIM_TIMING_UNIT(TimerIdx)); + assert_param(IS_HRTIM_EVENT(Event)); + assert_param(IS_HRTIM_TIMEVENTFILTER(pTimerEventFilteringCfg->Filter)); + assert_param(IS_HRTIM_TIMEVENTLATCH(pTimerEventFilteringCfg->Latch)); + + /* Configure timer event filtering capabilities */ + switch (Event) + { + case HRTIM_TIMEVENTFILTER_NONE: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR1 = 0; + HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR2 = 0; + } + break; + case HRTIM_EVENT_1: + { + HRTIM_eefr = HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR1; + HRTIM_eefr &= ~(HRTIM_EEFR1_EE1FLTR | HRTIM_EEFR1_EE1LTCH); + HRTIM_eefr |= (pTimerEventFilteringCfg->Filter | pTimerEventFilteringCfg->Latch); + HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR1 = HRTIM_eefr; + } + break; + case HRTIM_EVENT_2: + { + HRTIM_eefr = HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR1; + HRTIM_eefr &= ~(HRTIM_EEFR1_EE2FLTR | HRTIM_EEFR1_EE2LTCH); + HRTIM_eefr |= ((pTimerEventFilteringCfg->Filter | pTimerEventFilteringCfg->Latch) << 6); + HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR1 = HRTIM_eefr; + } + break; + case HRTIM_EVENT_3: + { + HRTIM_eefr = HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR1; + HRTIM_eefr &= ~(HRTIM_EEFR1_EE3FLTR | HRTIM_EEFR1_EE3LTCH); + HRTIM_eefr |= ((pTimerEventFilteringCfg->Filter | pTimerEventFilteringCfg->Latch) << 12); + HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR1 = HRTIM_eefr; + } + break; + case HRTIM_EVENT_4: + { + HRTIM_eefr = HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR1; + HRTIM_eefr &= ~(HRTIM_EEFR1_EE4FLTR | HRTIM_EEFR1_EE4LTCH); + HRTIM_eefr |= ((pTimerEventFilteringCfg->Filter | pTimerEventFilteringCfg->Latch) << 18); + HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR1 = HRTIM_eefr; + } + break; + case HRTIM_EVENT_5: + { + HRTIM_eefr = HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR1; + HRTIM_eefr &= ~(HRTIM_EEFR1_EE5FLTR | HRTIM_EEFR1_EE5LTCH); + HRTIM_eefr |= ((pTimerEventFilteringCfg->Filter | pTimerEventFilteringCfg->Latch) << 24); + HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR1 = HRTIM_eefr; + } + break; + case HRTIM_EVENT_6: + { + HRTIM_eefr = HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR2; + HRTIM_eefr &= ~(HRTIM_EEFR2_EE6FLTR | HRTIM_EEFR2_EE6LTCH); + HRTIM_eefr |= (pTimerEventFilteringCfg->Filter | pTimerEventFilteringCfg->Latch); + HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR2 = HRTIM_eefr; + } + break; + case HRTIM_EVENT_7: + { + HRTIM_eefr = HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR2; + HRTIM_eefr &= ~(HRTIM_EEFR2_EE7FLTR | HRTIM_EEFR2_EE7LTCH); + HRTIM_eefr |= ((pTimerEventFilteringCfg->Filter | pTimerEventFilteringCfg->Latch) << 6); + HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR2 = HRTIM_eefr; + } + break; + case HRTIM_EVENT_8: + { + HRTIM_eefr = HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR2; + HRTIM_eefr &= ~(HRTIM_EEFR2_EE8FLTR | HRTIM_EEFR2_EE8LTCH); + HRTIM_eefr |= ((pTimerEventFilteringCfg->Filter | pTimerEventFilteringCfg->Latch) << 12); + HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR2 = HRTIM_eefr; + } + break; + case HRTIM_EVENT_9: + { + HRTIM_eefr = HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR2; + HRTIM_eefr &= ~(HRTIM_EEFR2_EE9FLTR | HRTIM_EEFR2_EE9LTCH); + HRTIM_eefr |= ((pTimerEventFilteringCfg->Filter | pTimerEventFilteringCfg->Latch) << 18); + HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR2 = HRTIM_eefr; + } + break; + case HRTIM_EVENT_10: + { + HRTIM_eefr = HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR2; + HRTIM_eefr &= ~(HRTIM_EEFR2_EE10FLTR | HRTIM_EEFR2_EE10LTCH); + HRTIM_eefr |= ((pTimerEventFilteringCfg->Filter | pTimerEventFilteringCfg->Latch) << 24); + HRTIMx->HRTIM_TIMERx[TimerIdx].EEFxR2 = HRTIM_eefr; + } + break; + default: + break; + } +} + +/** + * @brief Configures the dead time insertion feature for a timer + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param pDeadTimeCfg: pointer to the dead time insertion configuration structure + * @retval None + */ +void HRTIM_DeadTimeConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + HRTIM_DeadTimeCfgTypeDef* pDeadTimeCfg) +{ + uint32_t HRTIM_dtr; + + /* Check parameters */ + assert_param(IS_HRTIM_TIMING_UNIT(TimerIdx)); + assert_param(IS_HRTIM_TIMDEADTIME_RISINGSIGN(pDeadTimeCfg->RisingSign)); + assert_param(IS_HRTIM_TIMDEADTIME_RISINGLOCK(pDeadTimeCfg->RisingLock)); + assert_param(IS_HRTIM_TIMDEADTIME_RISINGSIGNLOCK(pDeadTimeCfg->RisingSignLock)); + assert_param(IS_HRTIM_TIMDEADTIME_FALLINGSIGN(pDeadTimeCfg->FallingSign)); + assert_param(IS_HRTIM_TIMDEADTIME_FALLINGLOCK(pDeadTimeCfg->FallingLock)); + assert_param(IS_HRTIM_TIMDEADTIME_FALLINGSIGNLOCK(pDeadTimeCfg->FallingSignLock)); + + HRTIM_dtr = HRTIMx->HRTIM_TIMERx[TimerIdx].DTxR; + + /* Clear timer dead times configuration */ + HRTIM_dtr &= ~(HRTIM_DTR_DTR | HRTIM_DTR_SDTR | HRTIM_DTR_DTPRSC | + HRTIM_DTR_DTRSLK | HRTIM_DTR_DTRLK | HRTIM_DTR_SDTF | + HRTIM_DTR_SDTR | HRTIM_DTR_DTFSLK | HRTIM_DTR_DTFLK); + + /* Set timer dead times configuration */ + HRTIM_dtr |= (pDeadTimeCfg->Prescaler << 10); + HRTIM_dtr |= pDeadTimeCfg->RisingValue; + HRTIM_dtr |= pDeadTimeCfg->RisingSign; + HRTIM_dtr |= pDeadTimeCfg->RisingSignLock; + HRTIM_dtr |= pDeadTimeCfg->RisingLock; + HRTIM_dtr |= (pDeadTimeCfg->FallingValue << 16); + HRTIM_dtr |= pDeadTimeCfg->FallingSign; + HRTIM_dtr |= pDeadTimeCfg->FallingSignLock; + HRTIM_dtr |= pDeadTimeCfg->FallingLock; + + /* Update the HRTIMx registers */ + HRTIMx->HRTIM_TIMERx[TimerIdx].DTxR = HRTIM_dtr; +} + +/** + * @brief Configures the chopper mode feature for a timer + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param pChopperModeCfg: pointer to the chopper mode configuration structure + * @retval None + */ +void HRTIM_ChopperModeConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + HRTIM_ChopperModeCfgTypeDef* pChopperModeCfg) +{ + uint32_t HRTIM_chpr; + + /* Check parameters */ + assert_param(IS_HRTIM_TIMING_UNIT(TimerIdx)); + + HRTIM_chpr = HRTIMx->HRTIM_TIMERx[TimerIdx].CHPxR; + + /* Clear timer chopper mode configuration */ + HRTIM_chpr &= ~(HRTIM_CHPR_CARFRQ | HRTIM_CHPR_CARDTY | HRTIM_CHPR_STRPW); + + /* Set timer chopper mode configuration */ + HRTIM_chpr |= pChopperModeCfg->CarrierFreq; + HRTIM_chpr |= (pChopperModeCfg->DutyCycle << 4); + HRTIM_chpr |= (pChopperModeCfg->StartPulse << 7); + + /* Update the HRTIMx registers */ + HRTIMx->HRTIM_TIMERx[TimerIdx].CHPxR = HRTIM_chpr; +} + +/** + * @brief Configures the burst DMA controller for a timer + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x5 for master timer + * @arg 0x0 to 0x4 for timers A to E + * @param RegistersToUpdate: registers to be written by DMA + * This parameter can be any combination of the following values: + * @arg HRTIM_BURSTDMA_CR: HRTIM_MCR or HRTIM_TIMxCR + * @arg HRTIM_BURSTDMA_ICR: HRTIM_MICR or HRTIM_TIMxICR + * @arg HRTIM_BURSTDMA_DIER: HRTIM_MDIER or HRTIM_TIMxDIER + * @arg HRTIM_BURSTDMA_CNT: HRTIM_MCNT or HRTIM_TIMxCNT + * @arg HRTIM_BURSTDMA_PER: HRTIM_MPER or HRTIM_TIMxPER + * @arg HRTIM_BURSTDMA_REP: HRTIM_MREP or HRTIM_TIMxREP + * @arg HRTIM_BURSTDMA_CMP1: HRTIM_MCMP1 or HRTIM_TIMxCMP1 + * @arg HRTIM_BURSTDMA_CMP2: HRTIM_MCMP2 or HRTIM_TIMxCMP2 + * @arg HRTIM_BURSTDMA_CMP3: HRTIM_MCMP3 or HRTIM_TIMxCMP3 + * @arg HRTIM_BURSTDMA_CMP4: HRTIM_MCMP4 or HRTIM_TIMxCMP4 + * @arg HRTIM_BURSTDMA_DTR: HRTIM_TIMxDTR + * @arg HRTIM_BURSTDMA_SET1R: HRTIM_TIMxSET1R + * @arg HRTIM_BURSTDMA_RST1R: HRTIM_TIMxRST1R + * @arg HRTIM_BURSTDMA_SET2R: HRTIM_TIMxSET2R + * @arg HRTIM_BURSTDMA_RST2R: HRTIM_TIMxRST2R + * @arg HRTIM_BURSTDMA_EEFR1: HRTIM_TIMxEEFR1 + * @arg HRTIM_BURSTDMA_EEFR2: HRTIM_TIMxEEFR2 + * @arg HRTIM_BURSTDMA_RSTR: HRTIM_TIMxRSTR + * @arg HRTIM_BURSTDMA_CHPR: HRTIM_TIMxCHPR + * @arg HRTIM_BURSTDMA_OUTR: HRTIM_TIMxOUTR + * @arg HRTIM_BURSTDMA_FLTR: HRTIM_TIMxFLTR + * @retval None + */ +void HRTIM_BurstDMAConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t RegistersToUpdate) +{ + /* Check parameters */ + assert_param(IS_HRTIM_TIMER_BURSTDMA(TimerIdx, RegistersToUpdate)); + + /* Set the burst DMA timer update register */ + switch (TimerIdx) + { + case HRTIM_TIMERINDEX_TIMER_A: + { + HRTIMx->HRTIM_COMMON.BDTAUPR = RegistersToUpdate; + } + break; + case HRTIM_TIMERINDEX_TIMER_B: + { + HRTIMx->HRTIM_COMMON.BDTBUPR = RegistersToUpdate; + } + break; + case HRTIM_TIMERINDEX_TIMER_C: + { + HRTIMx->HRTIM_COMMON.BDTCUPR = RegistersToUpdate; + } + break; + case HRTIM_TIMERINDEX_TIMER_D: + { + HRTIMx->HRTIM_COMMON.BDTDUPR = RegistersToUpdate; + } + break; + case HRTIM_TIMERINDEX_TIMER_E: + { + HRTIMx->HRTIM_COMMON.BDTEUPR = RegistersToUpdate; + } + break; + case HRTIM_TIMERINDEX_MASTER: + { + HRTIMx->HRTIM_COMMON.BDMUPDR = RegistersToUpdate; + } + break; + default: + break; + } +} + +/** + * @brief Configures the external input/output synchronization of the HRTIMx + * @param HRTIMx: pointer to HRTIMx peripheral + * @param pSynchroCfg: pointer to the input/output synchronization configuration structure + * @retval None + */ +void HRTIM_SynchronizationConfig(HRTIM_TypeDef *HRTIMx, HRTIM_SynchroCfgTypeDef * pSynchroCfg) +{ + uint32_t HRTIM_mcr; + + /* Check parameters */ + assert_param(IS_HRTIM_SYNCINPUTSOURCE(pSynchroCfg->SyncInputSource)); + assert_param(IS_HRTIM_SYNCOUTPUTSOURCE(pSynchroCfg->SyncOutputSource)); + assert_param(IS_HRTIM_SYNCOUTPUTPOLARITY(pSynchroCfg->SyncOutputPolarity)); + + HRTIM_mcr = HRTIMx->HRTIM_MASTER.MCR; + + /* Set the synchronization input source */ + HRTIM_mcr &= ~(HRTIM_MCR_SYNC_IN); + HRTIM_mcr |= pSynchroCfg->SyncInputSource; + + /* Set the event to be sent on the synchronization output */ + HRTIM_mcr &= ~(HRTIM_MCR_SYNC_SRC); + HRTIM_mcr |= pSynchroCfg->SyncOutputSource; + + /* Set the polarity of the synchronization output */ + HRTIM_mcr &= ~(HRTIM_MCR_SYNC_OUT); + HRTIM_mcr |= pSynchroCfg->SyncOutputPolarity; + + /* Update the HRTIMx registers */ + HRTIMx->HRTIM_MASTER.MCR = HRTIM_mcr; +} + +/** + * @brief Configures the burst mode feature of the HRTIMx + * @param HRTIMx: pointer to HRTIMx peripheral + * @param pBurstModeCfg: pointer to the burst mode configuration structure + * @retval None + */ +void HRTIM_BurstModeConfig(HRTIM_TypeDef * HRTIMx, + HRTIM_BurstModeCfgTypeDef* pBurstModeCfg) +{ + uint32_t HRTIM_bmcr; + + /* Check parameters */ + assert_param(IS_HRTIM_BURSTMODE(pBurstModeCfg->Mode)); + assert_param(IS_HRTIM_BURSTMODECLOCKSOURCE(pBurstModeCfg->ClockSource)); + assert_param(IS_HRTIM_HRTIM_BURSTMODEPRESCALER(pBurstModeCfg->Prescaler)); + assert_param(IS_HRTIM_BURSTMODEPRELOAD(pBurstModeCfg->PreloadEnable)); + + HRTIM_bmcr = HRTIMx->HRTIM_COMMON.BMCR; + + /* Set the burst mode operating mode */ + HRTIM_bmcr &= ~(HRTIM_BMCR_BMOM); + HRTIM_bmcr |= pBurstModeCfg->Mode; + + /* Set the burst mode clock source */ + HRTIM_bmcr &= ~(HRTIM_BMCR_BMCLK); + HRTIM_bmcr |= pBurstModeCfg->ClockSource; + + /* Set the burst mode prescaler */ + HRTIM_bmcr &= ~(HRTIM_BMCR_BMPSC); + HRTIM_bmcr |= pBurstModeCfg->Prescaler; + + /* Enable/disable burst mode registers preload */ + HRTIM_bmcr &= ~(HRTIM_BMCR_BMPREN); + HRTIM_bmcr |= pBurstModeCfg->PreloadEnable; + + /* Set the burst mode trigger */ + HRTIMx->HRTIM_COMMON.BMTRGR = pBurstModeCfg->Trigger; + + /* Set the burst mode compare value */ + HRTIMx->HRTIM_COMMON.BMCMPR = pBurstModeCfg->IdleDuration; + + /* Set the burst mode period */ + HRTIMx->HRTIM_COMMON.BMPER = pBurstModeCfg->Period; + + /* Update the HRTIMx registers */ + HRTIMx->HRTIM_COMMON.BMCR = HRTIM_bmcr; +} + +/** + * @brief Configures the conditioning of an external event + * @param HRTIMx: pointer to HRTIMx peripheral + * @param Event: external event to configure + * This parameter can be one of the following values: + * @arg HRTIM_EVENT_1: External event 1 + * @arg HRTIM_EVENT_2: External event 2 + * @arg HRTIM_EVENT_3: External event 3 + * @arg HRTIM_EVENT_4: External event 4 + * @arg HRTIM_EVENT_5: External event 5 + * @arg HRTIM_EVENT_6: External event 6 + * @arg HRTIM_EVENT_7: External event 7 + * @arg HRTIM_EVENT_8: External event 8 + * @arg HRTIM_EVENT_9: External event 9 + * @arg HRTIM_EVENT_10: External event 10 + * @param pEventCfg: pointer to the event conditioning configuration structure + * @retval None + */ +void HRTIM_EventConfig(HRTIM_TypeDef * HRTIMx, + uint32_t Event, + HRTIM_EventCfgTypeDef* pEventCfg) +{ + /* Check parameters */ + assert_param(IS_HRTIM_EVENTSRC(pEventCfg->Source)); + assert_param(IS_HRTIM_EVENTPOLARITY(pEventCfg->Polarity)); + assert_param(IS_HRTIM_EVENTSENSITIVITY(pEventCfg->Sensitivity)); + assert_param(IS_HRTIM_EVENTFASTMODE(pEventCfg->FastMode)); + assert_param(IS_HRTIM_EVENTFILTER(pEventCfg->Filter)); + + /* Configure the event channel */ + HRTIM_ExternalEventConfig(HRTIMx, Event, pEventCfg); + +} + +/** + * @brief Configures the external event conditioning block prescaler + * @param HRTIMx: pointer to HRTIMx peripheral + * @param Prescaler: Prescaler value + * This parameter can be one of the following values: + * @arg HRTIM_EVENTPRESCALER_DIV1: fEEVS=fHRTIMx + * @arg HRTIM_EVENTPRESCALER_DIV2: fEEVS=fHRTIMx / 2 + * @arg HRTIM_EVENTPRESCALER_DIV4: fEEVS=fHRTIMx / 4 + * @arg HRTIM_EVENTPRESCALER_DIV8: fEEVS=fHRTIMx / 8 + * @retval None + */ +void HRTIM_EventPrescalerConfig(HRTIM_TypeDef * HRTIMx, + uint32_t Prescaler) +{ + uint32_t HRTIM_eecr3; + + /* Check parameters */ + assert_param(IS_HRTIM_EVENTPRESCALER(Prescaler)); + + /* Set the external event prescaler */ + HRTIM_eecr3 = HRTIMx->HRTIM_COMMON.EECR3; + HRTIM_eecr3 &= ~(HRTIM_EECR3_EEVSD); + HRTIM_eecr3 |= Prescaler; + + /* Update the HRTIMx registers */ + HRTIMx->HRTIM_COMMON.EECR3 = HRTIM_eecr3; +} + +/** + * @brief Configures the conditioning of fault input + * @param HRTIMx: pointer to HRTIMx peripheral + * @param Fault: fault input to configure + * This parameter can be one of the following values: + * @arg HRTIM_FAULT_1: Fault input 1 + * @arg HRTIM_FAULT_2: Fault input 2 + * @arg HRTIM_FAULT_3: Fault input 3 + * @arg HRTIM_FAULT_4: Fault input 4 + * @arg HRTIM_FAULT_5: Fault input 5 + * @param pFaultCfg: pointer to the fault conditioning configuration structure + * @retval None + */ +void HRTIM_FaultConfig(HRTIM_TypeDef * HRTIMx, + HRTIM_FaultCfgTypeDef* pFaultCfg, + uint32_t Fault) +{ + uint32_t HRTIM_fltinr1; + uint32_t HRTIM_fltinr2; + + /* Check parameters */ + assert_param(IS_HRTIM_FAULT(Fault)); + assert_param(IS_HRTIM_FAULTSOURCE(pFaultCfg->Source)); + assert_param(IS_HRTIM_FAULTPOLARITY(pFaultCfg->Polarity)); + assert_param(IS_HRTIM_FAULTFILTER(pFaultCfg->Filter)); + assert_param(IS_HRTIM_FAULTLOCK(pFaultCfg->Lock)); + + /* Configure fault channel */ + HRTIM_fltinr1 = HRTIMx->HRTIM_COMMON.FLTINxR1; + HRTIM_fltinr2 = HRTIMx->HRTIM_COMMON.FLTINxR2; + + switch (Fault) + { + case HRTIM_FAULT_1: + { + HRTIM_fltinr1 &= ~(HRTIM_FLTINR1_FLT1P | HRTIM_FLTINR1_FLT1SRC | HRTIM_FLTINR1_FLT1F | HRTIM_FLTINR1_FLT1LCK); + HRTIM_fltinr1 |= pFaultCfg->Polarity; + HRTIM_fltinr1 |= pFaultCfg->Source; + HRTIM_fltinr1 |= pFaultCfg->Filter; + HRTIM_fltinr1 |= pFaultCfg->Lock; + } + break; + case HRTIM_FAULT_2: + { + HRTIM_fltinr1 &= ~(HRTIM_FLTINR1_FLT2P | HRTIM_FLTINR1_FLT2SRC | HRTIM_FLTINR1_FLT2F | HRTIM_FLTINR1_FLT2LCK); + HRTIM_fltinr1 |= (pFaultCfg->Polarity << 8); + HRTIM_fltinr1 |= (pFaultCfg->Source << 8); + HRTIM_fltinr1 |= (pFaultCfg->Filter << 8); + HRTIM_fltinr1 |= (pFaultCfg->Lock << 8); + } + break; + case HRTIM_FAULT_3: + { + HRTIM_fltinr1 &= ~(HRTIM_FLTINR1_FLT3P | HRTIM_FLTINR1_FLT3SRC | HRTIM_FLTINR1_FLT3F | HRTIM_FLTINR1_FLT3LCK); + HRTIM_fltinr1 |= (pFaultCfg->Polarity << 16); + HRTIM_fltinr1 |= (pFaultCfg->Source << 16); + HRTIM_fltinr1 |= (pFaultCfg->Filter << 16); + HRTIM_fltinr1 |= (pFaultCfg->Lock << 16); + } + break; + case HRTIM_FAULT_4: + { + HRTIM_fltinr1 &= ~(HRTIM_FLTINR1_FLT4P | HRTIM_FLTINR1_FLT4SRC | HRTIM_FLTINR1_FLT4F | HRTIM_FLTINR1_FLT4LCK); + HRTIM_fltinr1 |= (pFaultCfg->Polarity << 24); + HRTIM_fltinr1 |= (pFaultCfg->Source << 24); + HRTIM_fltinr1 |= (pFaultCfg->Filter << 24); + HRTIM_fltinr1 |= (pFaultCfg->Lock << 24); + } + break; + case HRTIM_FAULT_5: + { + HRTIM_fltinr2 &= ~(HRTIM_FLTINR2_FLT5P | HRTIM_FLTINR2_FLT5SRC | HRTIM_FLTINR2_FLT5F | HRTIM_FLTINR2_FLT5LCK); + HRTIM_fltinr2 |= pFaultCfg->Polarity; + HRTIM_fltinr2 |= pFaultCfg->Source; + HRTIM_fltinr2 |= pFaultCfg->Filter; + HRTIM_fltinr2 |= pFaultCfg->Lock; + } + break; + default: + break; + } + + /* Update the HRTIMx registers */ + HRTIMx->HRTIM_COMMON.FLTINxR1 = HRTIM_fltinr1; + HRTIMx->HRTIM_COMMON.FLTINxR2 = HRTIM_fltinr2; +} + +/** + * @brief Configures the fault conditioning block prescaler + * @param HRTIMx: pointer to HRTIMx peripheral + * @param Prescaler: Prescaler value + * This parameter can be one of the following values: + * @arg HRTIM_FAULTPRESCALER_DIV1: fFLTS=fHRTIMx + * @arg HRTIM_FAULTPRESCALER_DIV2: fFLTS=fHRTIMx / 2 + * @arg HRTIM_FAULTPRESCALER_DIV4: fFLTS=fHRTIMx / 4 + * @arg HRTIM_FAULTPRESCALER_DIV8: fFLTS=fHRTIMx / 8 + * @retval None + */ +void HRTIM_FaultPrescalerConfig(HRTIM_TypeDef * HRTIMx, + uint32_t Prescaler) +{ + uint32_t HRTIM_fltinr2; + + /* Check parameters */ + assert_param(IS_HRTIM_FAULTPRESCALER(Prescaler)); + + /* Set the external event prescaler */ + HRTIM_fltinr2 = HRTIMx->HRTIM_COMMON.FLTINxR2; + HRTIM_fltinr2 &= ~(HRTIM_FLTINR2_FLTSD); + HRTIM_fltinr2 |= Prescaler; + + /* Update the HRTIMx registers */ + HRTIMx->HRTIM_COMMON.FLTINxR2 = HRTIM_fltinr2; +} + +/** + * @brief Enables or disables the HRTIMx Fault mode. + * @param HRTIMx: pointer to HRTIMx peripheral + * @param Fault: fault input to configure + * This parameter can be one of the following values: + * @arg HRTIM_FAULT_1: Fault input 1 + * @arg HRTIM_FAULT_2: Fault input 2 + * @arg HRTIM_FAULT_3: Fault input 3 + * @arg HRTIM_FAULT_4: Fault input 4 + * @arg HRTIM_FAULT_5: Fault input 5 + * @param Enable: Fault mode controller enabling + * This parameter can be one of the following values: + * @arg HRTIM_FAULT_ENABLED: Fault mode enabled + * @arg HRTIM_FAULT_DISABLED: Fault mode disabled + * @retval None + */ +void HRTIM_FaultModeCtl(HRTIM_TypeDef * HRTIMx, uint32_t Fault, uint32_t Enable) +{ + uint32_t HRTIM_fltinr1; + uint32_t HRTIM_fltinr2; + + /* Check parameters */ + assert_param(IS_HRTIM_FAULT(Fault)); + assert_param(IS_HRTIM_FAULTCTL(Enable)); + + /* Configure fault channel */ + HRTIM_fltinr1 = HRTIMx->HRTIM_COMMON.FLTINxR1; + HRTIM_fltinr2 = HRTIMx->HRTIM_COMMON.FLTINxR2; + + switch (Fault) + { + case HRTIM_FAULT_1: + { + HRTIM_fltinr1 &= ~HRTIM_FLTINR1_FLT1E; + HRTIM_fltinr1 |= Enable; + } + break; + case HRTIM_FAULT_2: + { + HRTIM_fltinr1 &= ~HRTIM_FLTINR1_FLT2E; + HRTIM_fltinr1 |= (Enable<< 8); + } + break; + case HRTIM_FAULT_3: + { + HRTIM_fltinr1 &= ~HRTIM_FLTINR1_FLT3E; + HRTIM_fltinr1 |= (Enable << 16); + } + break; + case HRTIM_FAULT_4: + { + HRTIM_fltinr1 &= ~HRTIM_FLTINR1_FLT4E; + HRTIM_fltinr1 |= (Enable << 24); + } + break; + case HRTIM_FAULT_5: + { + HRTIM_fltinr2 &= ~HRTIM_FLTINR2_FLT5E; + HRTIM_fltinr2 |= Enable; + } + break; + default: + break; + } + + /* Update the HRTIMx registers */ + HRTIMx->HRTIM_COMMON.FLTINxR1 = HRTIM_fltinr1; + HRTIMx->HRTIM_COMMON.FLTINxR2 = HRTIM_fltinr2; +} + +/** + * @brief Configures both the ADC trigger register update source and the ADC + * trigger source. + * @param HRTIMx: pointer to HRTIMx peripheral + * @param ADC trigger: ADC trigger to configure + * This parameter can be one of the following values: + * @arg HRTIM_ADCTRIGGER_1: ADC trigger 1 + * @arg HRTIM_ADCTRIGGER_2: ADC trigger 2 + * @arg HRTIM_ADCTRIGGER_3: ADC trigger 3 + * @arg HRTIM_ADCTRIGGER_4: ADC trigger 4 + * @param pADCTriggerCfg: pointer to the ADC trigger configuration structure + * @retval None + */ +void HRTIM_ADCTriggerConfig(HRTIM_TypeDef * HRTIMx, + uint32_t ADCTrigger, + HRTIM_ADCTriggerCfgTypeDef* pADCTriggerCfg) +{ + uint32_t HRTIM_cr1; + + /* Check parameters */ + assert_param(IS_HRTIM_ADCTRIGGER(ADCTrigger)); + assert_param(IS_HRTIM_ADCTRIGGERUPDATE(pADCTriggerCfg->UpdateSource)); + + /* Set the ADC trigger update source */ + HRTIM_cr1 = HRTIMx->HRTIM_COMMON.CR1; + + switch (ADCTrigger) + { + case HRTIM_ADCTRIGGER_1: + { + HRTIM_cr1 &= ~(HRTIM_CR1_ADC1USRC); + HRTIM_cr1 |= pADCTriggerCfg->UpdateSource; + + /* Set the ADC trigger 1 source */ + HRTIMx->HRTIM_COMMON.ADC1R = pADCTriggerCfg->Trigger; + } + break; + case HRTIM_ADCTRIGGER_2: + { + HRTIM_cr1 &= ~(HRTIM_CR1_ADC2USRC); + HRTIM_cr1 |= (pADCTriggerCfg->UpdateSource << 3); + + /* Set the ADC trigger 2 source */ + HRTIMx->HRTIM_COMMON.ADC2R = pADCTriggerCfg->Trigger; + } + break; + case HRTIM_ADCTRIGGER_3: + { + HRTIM_cr1 &= ~(HRTIM_CR1_ADC3USRC); + HRTIM_cr1 |= (pADCTriggerCfg->UpdateSource << 6); + + /* Set the ADC trigger 3 source */ + HRTIMx->HRTIM_COMMON.ADC3R = pADCTriggerCfg->Trigger; + } + case HRTIM_ADCTRIGGER_4: + { + HRTIM_cr1 &= ~(HRTIM_CR1_ADC4USRC); + HRTIM_cr1 |= (pADCTriggerCfg->UpdateSource << 9); + + /* Set the ADC trigger 4 source */ + HRTIMx->HRTIM_COMMON.ADC4R = pADCTriggerCfg->Trigger; + } + break; + default: + break; + } + + /* Update the HRTIMx registers */ + HRTIMx->HRTIM_COMMON.CR1 = HRTIM_cr1; +} + + +/** + * @brief Enables or disables the HRTIMx burst mode controller. + * @param HRTIMx: pointer to HRTIMx peripheral + * @param Enable: Burst mode controller enabling + * This parameter can be one of the following values: + * @arg HRTIM_BURSTMODECTL_ENABLED: Burst mode enabled + * @arg HRTIM_BURSTMODECTL_DISABLED: Burst mode disabled + * @retval None + */ +void HRTIM_BurstModeCtl(HRTIM_TypeDef * HRTIMx, uint32_t Enable) +{ + uint32_t HRTIM_bmcr; + + /* Check parameters */ + assert_param(IS_HRTIM_BURSTMODECTL(Enable)); + + /* Enable/Disable the burst mode controller */ + HRTIM_bmcr = HRTIMx->HRTIM_COMMON.BMCR; + HRTIM_bmcr &= ~(HRTIM_BMCR_BME); + HRTIM_bmcr |= Enable; + + /* Update the HRTIMx registers */ + HRTIMx->HRTIM_COMMON.BMCR = HRTIM_bmcr; +} + +/** + * @brief Triggers a software capture on the designed capture unit + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param CaptureUnit: Capture unit to trig + * This parameter can be one of the following values: + * @arg HRTIM_CAPTUREUNIT_1: Capture unit 1 + * @arg HRTIM_CAPTUREUNIT_2: Capture unit 2 + * @retval None + * @note The 'software capture' bit in the capure configuration register is + * automatically reset by hardware + */ +void HRTIM_SoftwareCapture(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t CaptureUnit) +{ + /* Check parameters */ + assert_param(IS_HRTIM_TIMING_UNIT(TimerIdx)); + assert_param(IS_HRTIM_CAPTUREUNIT(CaptureUnit)); + + /* Force a software capture on concerned capture unit */ + switch (CaptureUnit) + { + case HRTIM_CAPTUREUNIT_1: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CPT1xCR |= HRTIM_CPT1CR_SWCPT; + } + break; + case HRTIM_CAPTUREUNIT_2: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CPT2xCR |= HRTIM_CPT2CR_SWCPT; + } + break; + default: + break; + } +} + +/** + * @brief Triggers the update of the registers of one or several timers + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimersToUpdate: timers concerned with the software register update + * This parameter can be any combination of the following values: + * @arg HRTIM_TIMERUPDATE_MASTER + * @arg HRTIM_TIMERUPDATE_A + * @arg HRTIM_TIMERUPDATE_B + * @arg HRTIM_TIMERUPDATE_C + * @arg HRTIM_TIMERUPDATE_D + * @arg HRTIM_TIMERUPDATE_E + * @retval None + * @note The 'software update' bits in the HRTIMx control register 2 register are + * automatically reset by hardware + */ +void HRTIM_SoftwareUpdate(HRTIM_TypeDef * HRTIMx, + uint32_t TimersToUpdate) +{ + /* Check parameters */ + assert_param(IS_HRTIM_TIMERUPDATE(TimersToUpdate)); + + /* Force timer(s) registers update */ + HRTIMx->HRTIM_COMMON.CR2 |= TimersToUpdate; + +} + +/** + * @brief Triggers the reset of one or several timers + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimersToUpdate: timers concerned with the software counter reset + * This parameter can be any combination of the following values: + * @arg HRTIM_TIMER_MASTER + * @arg HRTIM_TIMER_A + * @arg HRTIM_TIMER_B + * @arg HRTIM_TIMER_C + * @arg HRTIM_TIMER_D + * @arg HRTIM_TIMER_E + * @retval None + * @note The 'software reset' bits in the HRTIMx control register 2 are + * automatically reset by hardware + */ +void HRTIM_SoftwareReset(HRTIM_TypeDef * HRTIMx, + uint32_t TimersToReset) +{ + /* Check parameters */ + assert_param(IS_HRTIM_TIMERRESET(TimersToReset)); + + /* Force timer(s) registers update */ + HRTIMx->HRTIM_COMMON.CR2 |= TimersToReset; + +} + +/** + * @brief Forces the timer output to its active or inactive state + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param Output: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TE1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TE2: Timer E - Output 2 + * @param OutputLevel: indicates whether the output is forced to its active or inactive state + * This parameter can be one of the following values: + * @arg HRTIM_OUTPUTLEVEL_ACTIVE: output is forced to its active state + * @arg HRTIM_OUTPUTLEVEL_INACTIVE: output is forced to its inactive state + * @retval None + * @note The 'software set/reset trigger' bit in the output set/reset registers + * is automatically reset by hardware + */ +void HRTIM_WaveformSetOutputLevel(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t Output, + uint32_t OutputLevel) +{ + /* Check parameters */ + assert_param(IS_HRTIM_TIMER_OUTPUT(TimerIdx, Output)); + assert_param(IS_HRTIM_OUTPUTLEVEL(OutputLevel)); + + /* Force timer output level */ + switch (Output) + { + case HRTIM_OUTPUT_TA1: + case HRTIM_OUTPUT_TB1: + case HRTIM_OUTPUT_TC1: + case HRTIM_OUTPUT_TD1: + case HRTIM_OUTPUT_TE1: + { + if (OutputLevel == HRTIM_OUTPUTLEVEL_ACTIVE) + { + /* Force output to its active state */ + HRTIMx->HRTIM_TIMERx[TimerIdx].SETx1R |= HRTIM_SET1R_SST; + } + else + { + /* Force output to its inactive state */ + HRTIMx->HRTIM_TIMERx[TimerIdx].RSTx1R |= HRTIM_RST1R_SRT; + } + } + break; + case HRTIM_OUTPUT_TA2: + case HRTIM_OUTPUT_TB2: + case HRTIM_OUTPUT_TC2: + case HRTIM_OUTPUT_TD2: + case HRTIM_OUTPUT_TE2: + { + if (OutputLevel == HRTIM_OUTPUTLEVEL_ACTIVE) + { + /* Force output to its active state */ + HRTIMx->HRTIM_TIMERx[TimerIdx].SETx2R |= HRTIM_SET2R_SST; + } + else + { + /* Force output to its inactive state */ + HRTIMx->HRTIM_TIMERx[TimerIdx].RSTx2R |= HRTIM_RST2R_SRT; + } + } + break; + default: + break; + } +} + + +/** + * @} + */ + +/** @defgroup HRTIM_Group4 Peripheral State methods + * @brief Peripheral State functions + * +@verbatim + =============================================================================== + ##### Peripheral State methods ##### + =============================================================================== + [..] + This subsection permit to get in run-time the status of the peripheral + and the data flow. + +@endverbatim + * @{ + */ + +/** + * @brief Returns actual value of the capture register of the designated capture unit + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param CaptureUnit: Capture unit to trig + * This parameter can be one of the following values: + * @arg HRTIM_CAPTUREUNIT_1: Capture unit 1 + * @arg HRTIM_CAPTUREUNIT_2: Capture unit 2 + * @retval Captured value + */ +uint32_t HRTIM_GetCapturedValue(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t CaptureUnit) +{ + uint32_t captured_value = 0; + + /* Check parameters */ + assert_param(IS_HRTIM_TIMING_UNIT(TimerIdx)); + assert_param(IS_HRTIM_CAPTUREUNIT(CaptureUnit)); + + /* Read captured value */ + switch (CaptureUnit) + { + case HRTIM_CAPTUREUNIT_1: + { + captured_value = HRTIMx->HRTIM_TIMERx[TimerIdx].CPT1xR; + } + break; + case HRTIM_CAPTUREUNIT_2: + { + captured_value = HRTIMx->HRTIM_TIMERx[TimerIdx].CPT2xR; + } + break; + default: + break; + } + + return captured_value; +} + +/** + * @brief Returns actual level (active or inactive) of the designated output + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param Output: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TE1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TE2: Timer E - Output 2 + * @retval Output level + * @note Returned output level is taken before the output stage (chopper, + * polarity). + */ +uint32_t HRTIM_WaveformGetOutputLevel(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t Output) +{ + uint32_t output_level = HRTIM_OUTPUTLEVEL_INACTIVE; + + /* Check parameters */ + assert_param(IS_HRTIM_TIMER_OUTPUT(TimerIdx, Output)); + + /* Read the output level */ + switch (Output) + { + case HRTIM_OUTPUT_TA1: + case HRTIM_OUTPUT_TB1: + case HRTIM_OUTPUT_TC1: + case HRTIM_OUTPUT_TD1: + case HRTIM_OUTPUT_TE1: + { + if ((HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxISR & HRTIM_TIMISR_O1CPY) != RESET) + { + output_level = HRTIM_OUTPUTLEVEL_ACTIVE; + } + else + { + output_level = HRTIM_OUTPUTLEVEL_INACTIVE; + } + } + break; + case HRTIM_OUTPUT_TA2: + case HRTIM_OUTPUT_TB2: + case HRTIM_OUTPUT_TC2: + case HRTIM_OUTPUT_TD2: + case HRTIM_OUTPUT_TE2: + { + if ((HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxISR & HRTIM_TIMISR_O2CPY) != RESET) + { + output_level = HRTIM_OUTPUTLEVEL_ACTIVE; + } + else + { + output_level = HRTIM_OUTPUTLEVEL_INACTIVE; + } + } + break; + default: + break; + } + + return output_level; +} + +/** + * @brief Returns actual state (RUN, IDLE, FAULT) of the designated output + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param Output: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TE1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TE2: Timer E - Output 2 + * @retval Output state + */ +#ifdef __GNUC__ +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wunused-parameter" +#endif +uint32_t HRTIM_WaveformGetOutputState(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t Output) +{ + uint32_t output_bit = 0; + uint32_t output_state = HRTIM_OUTPUTSTATE_IDLE; + + /* Check parameters */ + assert_param(IS_HRTIM_TIMER_OUTPUT(TimerIdx, Output)); + + /* Set output state according to output control status and output disable status */ + switch (Output) + { + case HRTIM_OUTPUT_TA1: + { + output_bit = HRTIM_OENR_TA1OEN; + } + break; + case HRTIM_OUTPUT_TA2: + { + output_bit = HRTIM_OENR_TA2OEN; + } + break; + case HRTIM_OUTPUT_TB1: + { + output_bit = HRTIM_OENR_TB1OEN; + } + break; + case HRTIM_OUTPUT_TB2: + { + output_bit = HRTIM_OENR_TB2OEN; + } + break; + case HRTIM_OUTPUT_TC1: + { + output_bit = HRTIM_OENR_TC1OEN; + } + break; + case HRTIM_OUTPUT_TC2: + { + output_bit = HRTIM_OENR_TC2OEN; + } + break; + case HRTIM_OUTPUT_TD1: + { + output_bit = HRTIM_OENR_TD1OEN; + } + break; + case HRTIM_OUTPUT_TD2: + { + output_bit = HRTIM_OENR_TD2OEN; + } + break; + case HRTIM_OUTPUT_TE1: + { + output_bit = HRTIM_OENR_TE1OEN; + } + break; + case HRTIM_OUTPUT_TE2: + { + output_bit = HRTIM_OENR_TE2OEN; + } + break; + default: + break; + } + + if ((HRTIMx->HRTIM_COMMON.OENR & output_bit) != RESET) + { + /* Output is enabled: output in RUN state (whatever ouput disable status is)*/ + output_state = HRTIM_OUTPUTSTATE_RUN; + } + else + { + if ((HRTIMx->HRTIM_COMMON.ODSR & output_bit) != RESET) + { + /* Output is disabled: output in FAULT state */ + output_state = HRTIM_OUTPUTSTATE_FAULT; + } + else + { + /* Output is disabled: output in IDLE state */ + output_state = HRTIM_OUTPUTSTATE_IDLE; + } + } + + return(output_state); +} +#ifdef __GNUC__ +# pragma GCC diagnostic pop +#endif + +/** + * @brief Returns the level (active or inactive) of the designated output + * when the delayed protection was triggered + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @param Output: Timer output + * This parameter can be one of the following values: + * @arg HRTIM_OUTPUT_TA1: Timer A - Output 1 + * @arg HRTIM_OUTPUT_TA2: Timer A - Output 2 + * @arg HRTIM_OUTPUT_TB1: Timer B - Output 1 + * @arg HRTIM_OUTPUT_TB2: Timer B - Output 2 + * @arg HRTIM_OUTPUT_TC1: Timer C - Output 1 + * @arg HRTIM_OUTPUT_TC2: Timer C - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer D - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer D - Output 2 + * @arg HRTIM_OUTPUT_TD1: Timer E - Output 1 + * @arg HRTIM_OUTPUT_TD2: Timer E - Output 2 + * @retval Delayed protection status + */ +uint32_t HRTIM_GetDelayedProtectionStatus(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t Output) +{ + uint32_t delayed_protection_status = HRTIM_OUTPUTLEVEL_INACTIVE; + + /* Check parameters */ + assert_param(IS_HRTIM_TIMER_OUTPUT(TimerIdx, Output)); + + /* Read the delayed protection status */ + switch (Output) + { + case HRTIM_OUTPUT_TA1: + case HRTIM_OUTPUT_TB1: + case HRTIM_OUTPUT_TC1: + case HRTIM_OUTPUT_TD1: + case HRTIM_OUTPUT_TE1: + { + if ((HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxISR & HRTIM_TIMISR_O1STAT) != RESET) + { + /* Output 1 was active when the delayed idle protection was triggered */ + delayed_protection_status = HRTIM_OUTPUTLEVEL_ACTIVE; + } + else + { + /* Output 1 was inactive when the delayed idle protection was triggered */ + delayed_protection_status = HRTIM_OUTPUTLEVEL_INACTIVE; + } + } + break; + case HRTIM_OUTPUT_TA2: + case HRTIM_OUTPUT_TB2: + case HRTIM_OUTPUT_TC2: + case HRTIM_OUTPUT_TD2: + case HRTIM_OUTPUT_TE2: + { + if ((HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxISR & HRTIM_TIMISR_O2STAT) != RESET) + { + /* Output 2 was active when the delayed idle protection was triggered */ + delayed_protection_status = HRTIM_OUTPUTLEVEL_ACTIVE; + } + else + { + /* Output 2 was inactive when the delayed idle protection was triggered */ + delayed_protection_status = HRTIM_OUTPUTLEVEL_INACTIVE; + } + } + break; + default: + break; + } + + return delayed_protection_status; +} + +/** + * @brief Returns the actual status (active or inactive) of the burst mode controller + * @param HRTIMx: pointer to HRTIMx peripheral + * @retval Burst mode controller status + */ +uint32_t HRTIM_GetBurstStatus(HRTIM_TypeDef * HRTIMx) +{ + uint32_t burst_mode_status; + + /* Read burst mode status */ + burst_mode_status = (HRTIMx->HRTIM_COMMON.BMCR & HRTIM_BMCR_BMSTAT); + + return burst_mode_status; +} + +/** + * @brief Indicates on which output the signal is currently active (when the + * push pull mode is enabled) + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @retval Burst mode controller status + */ +uint32_t HRTIM_GetCurrentPushPullStatus(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx) +{ + uint32_t current_pushpull_status; + + /* Check the parameters */ + assert_param(IS_HRTIM_TIMING_UNIT(TimerIdx)); + + /* Read current push pull status */ + current_pushpull_status = (HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxISR & HRTIM_TIMISR_CPPSTAT); + + return current_pushpull_status; +} + + +/** + * @brief Indicates on which output the signal was applied, in push-pull mode + balanced fault mode or delayed idle mode, when the protection was triggered + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * This parameter can be one of the following values: + * @arg 0x0 to 0x4 for timers A to E + * @retval Idle Push Pull Status + */ +uint32_t HRTIM_GetIdlePushPullStatus(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx) +{ + uint32_t idle_pushpull_status; + + /* Check the parameters */ + assert_param(IS_HRTIM_TIMING_UNIT(TimerIdx)); + + /* Read current push pull status */ + idle_pushpull_status = (HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxISR & HRTIM_TIMISR_IPPSTAT); + + return idle_pushpull_status; +} + +/** + * @brief Configures the master timer time base + * @param HRTIMx: pointer to HRTIMx peripheral + * @retval None + */ +void HRTIM_MasterBase_Config(HRTIM_TypeDef * HRTIMx, HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruct) +{ + /* Set the prescaler ratio */ + HRTIMx->HRTIM_MASTER.MCR &= (uint32_t) ~(HRTIM_MCR_CK_PSC); + HRTIMx->HRTIM_MASTER.MCR |= (uint32_t)HRTIM_BaseInitStruct->PrescalerRatio; + + /* Set the operating mode */ + HRTIMx->HRTIM_MASTER.MCR &= (uint32_t) ~(HRTIM_MCR_CONT | HRTIM_MCR_RETRIG); + HRTIMx->HRTIM_MASTER.MCR |= (uint32_t)HRTIM_BaseInitStruct->Mode; + + /* Update the HRTIMx registers */ + HRTIMx->HRTIM_MASTER.MPER = HRTIM_BaseInitStruct->Period; + HRTIMx->HRTIM_MASTER.MREP = HRTIM_BaseInitStruct->RepetitionCounter; +} + +/** + * @brief Configures timing unit (timer A to timer E) time base + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * @retval None + */ +void HRTIM_TimingUnitBase_Config(HRTIM_TypeDef * HRTIMx, uint32_t TimerIdx, HRTIM_BaseInitTypeDef* HRTIM_BaseInitStruct) +{ + /* Set the prescaler ratio */ + HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxCR &= (uint32_t) ~(HRTIM_TIMCR_CK_PSC); + HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxCR |= (uint32_t)HRTIM_BaseInitStruct->PrescalerRatio; + + /* Set the operating mode */ + HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxCR &= (uint32_t) ~(HRTIM_TIMCR_CONT | HRTIM_TIMCR_RETRIG); + HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxCR |= (uint32_t)HRTIM_BaseInitStruct->Mode; + + /* Update the HRTIMx registers */ + HRTIMx->HRTIM_TIMERx[TimerIdx].PERxR = HRTIM_BaseInitStruct->Period; + HRTIMx->HRTIM_TIMERx[TimerIdx].REPxR = HRTIM_BaseInitStruct->RepetitionCounter; +} + +/** + * @brief Configures the master timer in waveform mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * @param pTimerInit: pointer to the timer initialization data structure + * @retval None + */ +void HRTIM_MasterWaveform_Config(HRTIM_TypeDef * HRTIMx, + HRTIM_TimerInitTypeDef * pTimerInit) +{ + uint32_t HRTIM_mcr; + uint32_t HRTIM_bmcr; + + /* Configure master timer */ + HRTIM_mcr = HRTIMx->HRTIM_MASTER.MCR; + HRTIM_bmcr = HRTIMx->HRTIM_COMMON.BMCR; + + /* Enable/Disable the half mode */ + HRTIM_mcr &= ~(HRTIM_MCR_HALF); + HRTIM_mcr |= pTimerInit->HalfModeEnable; + + /* Enable/Disable the timer start upon synchronization event reception */ + HRTIM_mcr &= ~(HRTIM_MCR_SYNCSTRTM); + HRTIM_mcr |= pTimerInit->StartOnSync; + + /* Enable/Disable the timer reset upon synchronization event reception */ + HRTIM_mcr &= ~(HRTIM_MCR_SYNCRSTM); + HRTIM_mcr |= pTimerInit->ResetOnSync; + + /* Enable/Disable the DAC synchronization event generation */ + HRTIM_mcr &= ~(HRTIM_MCR_DACSYNC); + HRTIM_mcr |= pTimerInit->DACSynchro; + + /* Enable/Disable preload mechanism for timer registers */ + HRTIM_mcr &= ~(HRTIM_MCR_PREEN); + HRTIM_mcr |= pTimerInit->PreloadEnable; + + /* Master timer registers update handling */ + HRTIM_mcr &= ~(HRTIM_MCR_BRSTDMA); + HRTIM_mcr |= (pTimerInit->UpdateGating << 2); + + /* Enable/Disable registers update on repetition */ + HRTIM_mcr &= ~(HRTIM_MCR_MREPU); + HRTIM_mcr |= pTimerInit->RepetitionUpdate; + + /* Set the timer burst mode */ + HRTIM_bmcr &= ~(HRTIM_BMCR_MTBM); + HRTIM_bmcr |= pTimerInit->BurstMode; + + /* Update the HRTIMx registers */ + HRTIMx->HRTIM_MASTER.MCR = HRTIM_mcr; + HRTIMx->HRTIM_COMMON.BMCR = HRTIM_bmcr; + +} + +/** + * @brief Configures timing unit (timer A to timer E) in waveform mode + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * @param pTimerInit: pointer to the timer initialization data structure + * @retval None + */ +void HRTIM_TimingUnitWaveform_Config(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + HRTIM_TimerInitTypeDef * pTimerInit) +{ + uint32_t HRTIM_timcr; + uint32_t HRTIM_bmcr; + + /* Configure timing unit */ + HRTIM_timcr = HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxCR; + HRTIM_bmcr = HRTIMx->HRTIM_COMMON.BMCR; + + /* Enable/Disable the half mode */ + HRTIM_timcr &= ~(HRTIM_TIMCR_HALF); + HRTIM_timcr |= pTimerInit->HalfModeEnable; + + /* Enable/Disable the timer start upon synchronization event reception */ + HRTIM_timcr &= ~(HRTIM_TIMCR_SYNCSTRT); + HRTIM_timcr |= pTimerInit->StartOnSync; + + /* Enable/Disable the timer reset upon synchronization event reception */ + HRTIM_timcr &= ~(HRTIM_TIMCR_SYNCRST); + HRTIM_timcr |= pTimerInit->ResetOnSync; + + /* Enable/Disable the DAC synchronization event generation */ + HRTIM_timcr &= ~(HRTIM_TIMCR_DACSYNC); + HRTIM_timcr |= pTimerInit->DACSynchro; + + /* Enable/Disable preload mechanism for timer registers */ + HRTIM_timcr &= ~(HRTIM_TIMCR_PREEN); + HRTIM_timcr |= pTimerInit->PreloadEnable; + + /* Timing unit registers update handling */ + HRTIM_timcr &= ~(HRTIM_TIMCR_UPDGAT); + HRTIM_timcr |= pTimerInit->UpdateGating; + + /* Enable/Disable registers update on repetition */ + HRTIM_timcr &= ~(HRTIM_TIMCR_TREPU); + if (pTimerInit->RepetitionUpdate == HRTIM_UPDATEONREPETITION_ENABLED) + { + HRTIM_timcr |= HRTIM_TIMCR_TREPU; + } + + /* Set the timer burst mode */ + switch (TimerIdx) + { + case HRTIM_TIMERINDEX_TIMER_A: + { + HRTIM_bmcr &= ~(HRTIM_BMCR_TABM); + HRTIM_bmcr |= ( pTimerInit->BurstMode << 1); + } + break; + case HRTIM_TIMERINDEX_TIMER_B: + { + HRTIM_bmcr &= ~(HRTIM_BMCR_TBBM); + HRTIM_bmcr |= ( pTimerInit->BurstMode << 2); + } + break; + case HRTIM_TIMERINDEX_TIMER_C: + { + HRTIM_bmcr &= ~(HRTIM_BMCR_TCBM); + HRTIM_bmcr |= ( pTimerInit->BurstMode << 3); + } + break; + case HRTIM_TIMERINDEX_TIMER_D: + { + HRTIM_bmcr &= ~(HRTIM_BMCR_TDBM); + HRTIM_bmcr |= ( pTimerInit->BurstMode << 4); + } + break; + case HRTIM_TIMERINDEX_TIMER_E: + { + HRTIM_bmcr &= ~(HRTIM_BMCR_TEBM); + HRTIM_bmcr |= ( pTimerInit->BurstMode << 5); + } + break; + default: + break; + } + + /* Update the HRTIMx registers */ + HRTIMx->HRTIM_TIMERx[TimerIdx].TIMxCR = HRTIM_timcr; + HRTIMx->HRTIM_COMMON.BMCR = HRTIM_bmcr; +} + +/** + * @brief Configures a compare unit + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * @param CompareUnit: Compare unit identifier + * @param pCompareCfg: pointer to the compare unit configuration data structure + * @retval None + */ +void HRTIM_CompareUnitConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t CompareUnit, + HRTIM_CompareCfgTypeDef * pCompareCfg) +{ + if (TimerIdx == HRTIM_TIMERINDEX_MASTER) + { + /* Configure the compare unit of the master timer */ + switch (CompareUnit) + { + case HRTIM_COMPAREUNIT_1: + { + HRTIMx->HRTIM_MASTER.MCMP1R = pCompareCfg->CompareValue; + } + break; + case HRTIM_COMPAREUNIT_2: + { + HRTIMx->HRTIM_MASTER.MCMP2R = pCompareCfg->CompareValue; + } + break; + case HRTIM_COMPAREUNIT_3: + { + HRTIMx->HRTIM_MASTER.MCMP3R = pCompareCfg->CompareValue; + } + break; + case HRTIM_COMPAREUNIT_4: + { + HRTIMx->HRTIM_MASTER.MCMP4R = pCompareCfg->CompareValue; + } + break; + default: + break; + } + } + else + { + /* Configure the compare unit of the timing unit */ + switch (CompareUnit) + { + case HRTIM_COMPAREUNIT_1: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP1xR = pCompareCfg->CompareValue; + } + break; + case HRTIM_COMPAREUNIT_2: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP2xR = pCompareCfg->CompareValue; + } + break; + case HRTIM_COMPAREUNIT_3: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP3xR = pCompareCfg->CompareValue; + } + break; + case HRTIM_COMPAREUNIT_4: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CMP4xR = pCompareCfg->CompareValue; + } + break; + default: + break; + } + } +} + +/** + * @brief Configures a capture unit + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * @param CaptureUnit: Capture unit identifier + * @param pCaptureCfg: pointer to the compare unit configuration data structure + * @retval None + */ +void HRTIM_CaptureUnitConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t CaptureUnit, + uint32_t Event) +{ + uint32_t CaptureTrigger = HRTIM_CAPTURETRIGGER_EEV_1; + + switch (Event) + { + case HRTIM_EVENT_1: + { + CaptureTrigger = HRTIM_CAPTURETRIGGER_EEV_1; + } + break; + case HRTIM_EVENT_2: + { + CaptureTrigger = HRTIM_CAPTURETRIGGER_EEV_2; + } + break; + case HRTIM_EVENT_3: + { + CaptureTrigger = HRTIM_CAPTURETRIGGER_EEV_3; + } + break; + case HRTIM_EVENT_4: + { + CaptureTrigger = HRTIM_CAPTURETRIGGER_EEV_4; + } + break; + case HRTIM_EVENT_5: + { + CaptureTrigger = HRTIM_CAPTURETRIGGER_EEV_5; + } + break; + case HRTIM_EVENT_6: + { + CaptureTrigger = HRTIM_CAPTURETRIGGER_EEV_6; + } + break; + case HRTIM_EVENT_7: + { + CaptureTrigger = HRTIM_CAPTURETRIGGER_EEV_7; + } + break; + case HRTIM_EVENT_8: + { + CaptureTrigger = HRTIM_CAPTURETRIGGER_EEV_8; + } + break; + case HRTIM_EVENT_9: + { + CaptureTrigger = HRTIM_CAPTURETRIGGER_EEV_9; + } + break; + case HRTIM_EVENT_10: + { + CaptureTrigger = HRTIM_CAPTURETRIGGER_EEV_10; + } + break; + default: + break; + + } + switch (CaptureUnit) + { + case HRTIM_CAPTUREUNIT_1: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CPT1xCR = CaptureTrigger; + } + break; + case HRTIM_CAPTUREUNIT_2: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].CPT2xCR = CaptureTrigger; + } + break; + default: + break; + } +} + +/** + * @brief Configures the output of a timing unit + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * @param Output: timing unit output identifier + * @param pOutputCfg: pointer to the output configuration data structure + * @retval None + */ +void HRTIM_OutputConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t Output, + HRTIM_OutputCfgTypeDef * pOutputCfg) +{ + uint32_t HRTIM_outr; + uint32_t shift = 0; + + HRTIM_outr = HRTIMx->HRTIM_TIMERx[TimerIdx].OUTxR; + + switch (Output) + { + case HRTIM_OUTPUT_TA1: + case HRTIM_OUTPUT_TB1: + case HRTIM_OUTPUT_TC1: + case HRTIM_OUTPUT_TD1: + case HRTIM_OUTPUT_TE1: + { + /* Set the output set/reset crossbar */ + HRTIMx->HRTIM_TIMERx[TimerIdx].SETx1R = pOutputCfg->SetSource; + HRTIMx->HRTIM_TIMERx[TimerIdx].RSTx1R = pOutputCfg->ResetSource; + + shift = 0; + } + break; + case HRTIM_OUTPUT_TA2: + case HRTIM_OUTPUT_TB2: + case HRTIM_OUTPUT_TC2: + case HRTIM_OUTPUT_TD2: + case HRTIM_OUTPUT_TE2: + { + /* Set the output set/reset crossbar */ + HRTIMx->HRTIM_TIMERx[TimerIdx].SETx2R = pOutputCfg->SetSource; + HRTIMx->HRTIM_TIMERx[TimerIdx].RSTx2R = pOutputCfg->ResetSource; + + shift = 16; + } + break; + default: + break; + } + + /* Clear output config */ + HRTIM_outr &= ~((HRTIM_OUTR_POL1 | + HRTIM_OUTR_IDLM1 | + HRTIM_OUTR_IDLES1| + HRTIM_OUTR_FAULT1| + HRTIM_OUTR_CHP1 | + HRTIM_OUTR_DIDL1) << shift); + + /* Set the polarity */ + HRTIM_outr |= (pOutputCfg->Polarity << shift); + + /* Set the IDLE mode */ + HRTIM_outr |= (pOutputCfg->IdleMode << shift); + + /* Set the IDLE state */ + HRTIM_outr |= (pOutputCfg->IdleState << shift); + + /* Set the FAULT state */ + HRTIM_outr |= (pOutputCfg->FaultState << shift); + + /* Set the chopper mode */ + HRTIM_outr |= (pOutputCfg->ChopperModeEnable << shift); + + /* Set the burst mode entry mode */ + HRTIM_outr |= (pOutputCfg->BurstModeEntryDelayed << shift); + + /* Update HRTIMx register */ + HRTIMx->HRTIM_TIMERx[TimerIdx].OUTxR = HRTIM_outr; +} + +/** + * @brief Configures an external event channel + * @param HRTIMx: pointer to HRTIMx peripheral + * @param Event: Event channel identifier + * @param pEventCfg: pointer to the event channel configuration data structure + * @retval None + */ +static void HRTIM_ExternalEventConfig(HRTIM_TypeDef * HRTIMx, + uint32_t Event, + HRTIM_EventCfgTypeDef *pEventCfg) +{ + uint32_t hrtim_eecr1; + uint32_t hrtim_eecr2; + uint32_t hrtim_eecr3; + + /* Configure external event channel */ + hrtim_eecr1 = HRTIMx->HRTIM_COMMON.EECR1; + hrtim_eecr2 = HRTIMx->HRTIM_COMMON.EECR2; + hrtim_eecr3 = HRTIMx->HRTIM_COMMON.EECR3; + + switch (Event) + { + case HRTIM_EVENT_1: + { + hrtim_eecr1 &= ~(HRTIM_EECR1_EE1SRC | HRTIM_EECR1_EE1POL | HRTIM_EECR1_EE1SNS | HRTIM_EECR1_EE1FAST); + hrtim_eecr1 |= pEventCfg->Source; + hrtim_eecr1 |= pEventCfg->Polarity; + hrtim_eecr1 |= pEventCfg->Sensitivity; + /* Update the HRTIM registers (all bit fields but EE1FAST bit) */ + HRTIMx->HRTIM_COMMON.EECR1 = hrtim_eecr1; + /* Update the HRTIM registers (EE1FAST bit) */ + hrtim_eecr1 |= pEventCfg->FastMode; + HRTIMx->HRTIM_COMMON.EECR1 = hrtim_eecr1; + } + break; + case HRTIM_EVENT_2: + { + hrtim_eecr1 &= ~(HRTIM_EECR1_EE2SRC | HRTIM_EECR1_EE2POL | HRTIM_EECR1_EE2SNS | HRTIM_EECR1_EE2FAST); + hrtim_eecr1 |= (pEventCfg->Source << 6); + hrtim_eecr1 |= (pEventCfg->Polarity << 6); + hrtim_eecr1 |= (pEventCfg->Sensitivity << 6); + /* Update the HRTIM registers (all bit fields but EE2FAST bit) */ + HRTIMx->HRTIM_COMMON.EECR1 = hrtim_eecr1; + /* Update the HRTIM registers (EE2FAST bit) */ + hrtim_eecr1 |= (pEventCfg->FastMode << 6); + HRTIMx->HRTIM_COMMON.EECR1 = hrtim_eecr1; + } + break; + case HRTIM_EVENT_3: + { + hrtim_eecr1 &= ~(HRTIM_EECR1_EE3SRC | HRTIM_EECR1_EE3POL | HRTIM_EECR1_EE3SNS | HRTIM_EECR1_EE3FAST); + hrtim_eecr1 |= (pEventCfg->Source << 12); + hrtim_eecr1 |= (pEventCfg->Polarity << 12); + hrtim_eecr1 |= (pEventCfg->Sensitivity << 12); + /* Update the HRTIM registers (all bit fields but EE3FAST bit) */ + HRTIMx->HRTIM_COMMON.EECR1 = hrtim_eecr1; + /* Update the HRTIM registers (EE3FAST bit) */ + hrtim_eecr1 |= (pEventCfg->FastMode << 12); + HRTIMx->HRTIM_COMMON.EECR1 = hrtim_eecr1; + } + break; + case HRTIM_EVENT_4: + { + hrtim_eecr1 &= ~(HRTIM_EECR1_EE4SRC | HRTIM_EECR1_EE4POL | HRTIM_EECR1_EE4SNS | HRTIM_EECR1_EE4FAST); + hrtim_eecr1 |= (pEventCfg->Source << 18); + hrtim_eecr1 |= (pEventCfg->Polarity << 18); + hrtim_eecr1 |= (pEventCfg->Sensitivity << 18); + /* Update the HRTIM registers (all bit fields but EE4FAST bit) */ + HRTIMx->HRTIM_COMMON.EECR1 = hrtim_eecr1; + /* Update the HRTIM registers (EE4FAST bit) */ + hrtim_eecr1 |= (pEventCfg->FastMode << 18); + HRTIMx->HRTIM_COMMON.EECR1 = hrtim_eecr1; + } + break; + case HRTIM_EVENT_5: + { + hrtim_eecr1 &= ~(HRTIM_EECR1_EE5SRC | HRTIM_EECR1_EE5POL | HRTIM_EECR1_EE5SNS | HRTIM_EECR1_EE5FAST); + hrtim_eecr1 |= (pEventCfg->Source << 24); + hrtim_eecr1 |= (pEventCfg->Polarity << 24); + hrtim_eecr1 |= (pEventCfg->Sensitivity << 24); + /* Update the HRTIM registers (all bit fields but EE5FAST bit) */ + HRTIMx->HRTIM_COMMON.EECR1 = hrtim_eecr1; + /* Update the HRTIM registers (EE5FAST bit) */ + hrtim_eecr1 |= (pEventCfg->FastMode << 24); + HRTIMx->HRTIM_COMMON.EECR1 = hrtim_eecr1; + } + break; + case HRTIM_EVENT_6: + { + hrtim_eecr2 &= ~(HRTIM_EECR2_EE6SRC | HRTIM_EECR2_EE6POL | HRTIM_EECR2_EE6SNS); + hrtim_eecr2 |= pEventCfg->Source; + hrtim_eecr2 |= pEventCfg->Polarity; + hrtim_eecr2 |= pEventCfg->Sensitivity; + hrtim_eecr3 &= ~(HRTIM_EECR3_EE6F); + hrtim_eecr3 |= pEventCfg->Filter; + /* Update the HRTIM registers */ + HRTIMx->HRTIM_COMMON.EECR2 = hrtim_eecr2; + HRTIMx->HRTIM_COMMON.EECR3 = hrtim_eecr3; + } + break; + case HRTIM_EVENT_7: + { + hrtim_eecr2 &= ~(HRTIM_EECR2_EE7SRC | HRTIM_EECR2_EE7POL | HRTIM_EECR2_EE7SNS); + hrtim_eecr2 |= (pEventCfg->Source << 6); + hrtim_eecr2 |= (pEventCfg->Polarity << 6); + hrtim_eecr2 |= (pEventCfg->Sensitivity << 6); + hrtim_eecr3 &= ~(HRTIM_EECR3_EE7F); + hrtim_eecr3 |= (pEventCfg->Filter << 6); + /* Update the HRTIM registers */ + HRTIMx->HRTIM_COMMON.EECR2 = hrtim_eecr2; + HRTIMx->HRTIM_COMMON.EECR3 = hrtim_eecr3; + } + break; + case HRTIM_EVENT_8: + { + hrtim_eecr2 &= ~(HRTIM_EECR2_EE8SRC | HRTIM_EECR2_EE8POL | HRTIM_EECR2_EE8SNS); + hrtim_eecr2 |= (pEventCfg->Source << 12); + hrtim_eecr2 |= (pEventCfg->Polarity << 12); + hrtim_eecr2 |= (pEventCfg->Sensitivity << 12); + hrtim_eecr3 &= ~(HRTIM_EECR3_EE8F); + hrtim_eecr3 |= (pEventCfg->Filter << 12); + /* Update the HRTIM registers */ + HRTIMx->HRTIM_COMMON.EECR2 = hrtim_eecr2; + HRTIMx->HRTIM_COMMON.EECR3 = hrtim_eecr3; + } + break; + case HRTIM_EVENT_9: + { + hrtim_eecr2 &= ~(HRTIM_EECR2_EE9SRC | HRTIM_EECR2_EE9POL | HRTIM_EECR2_EE9SNS); + hrtim_eecr2 |= (pEventCfg->Source << 18); + hrtim_eecr2 |= (pEventCfg->Polarity << 18); + hrtim_eecr2 |= (pEventCfg->Sensitivity << 18); + hrtim_eecr3 &= ~(HRTIM_EECR3_EE9F); + hrtim_eecr3 |= (pEventCfg->Filter << 18); + /* Update the HRTIM registers */ + HRTIMx->HRTIM_COMMON.EECR2 = hrtim_eecr2; + HRTIMx->HRTIM_COMMON.EECR3 = hrtim_eecr3; + } + break; + case HRTIM_EVENT_10: + { + hrtim_eecr2 &= ~(HRTIM_EECR2_EE10SRC | HRTIM_EECR2_EE10POL | HRTIM_EECR2_EE10SNS); + hrtim_eecr2 |= (pEventCfg->Source << 24); + hrtim_eecr2 |= (pEventCfg->Polarity << 24); + hrtim_eecr2 |= (pEventCfg->Sensitivity << 24); + hrtim_eecr3 &= ~(HRTIM_EECR3_EE10F); + hrtim_eecr3 |= (pEventCfg->Filter << 24); + /* Update the HRTIM registers */ + HRTIMx->HRTIM_COMMON.EECR2 = hrtim_eecr2; + HRTIMx->HRTIM_COMMON.EECR3 = hrtim_eecr3; + } + break; + default: + break; + } +} + +/** + * @brief Configures the timer counter reset + * @param HRTIMx: pointer to HRTIMx peripheral + * @param TimerIdx: Timer index + * @param Event: Event channel identifier + * @retval None + */ +void HRTIM_TIM_ResetConfig(HRTIM_TypeDef * HRTIMx, + uint32_t TimerIdx, + uint32_t Event) +{ + switch (Event) + { + case HRTIM_EVENT_1: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].RSTxR = HRTIM_TIMRESETTRIGGER_EEV_1; + } + break; + case HRTIM_EVENT_2: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].RSTxR = HRTIM_TIMRESETTRIGGER_EEV_2; + } + break; + case HRTIM_EVENT_3: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].RSTxR = HRTIM_TIMRESETTRIGGER_EEV_3; + } + break; + case HRTIM_EVENT_4: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].RSTxR = HRTIM_TIMRESETTRIGGER_EEV_4; + } + break; + case HRTIM_EVENT_5: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].RSTxR = HRTIM_TIMRESETTRIGGER_EEV_5; + } + break; + case HRTIM_EVENT_6: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].RSTxR = HRTIM_TIMRESETTRIGGER_EEV_6; + } + break; + case HRTIM_EVENT_7: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].RSTxR = HRTIM_TIMRESETTRIGGER_EEV_7; + } + break; + case HRTIM_EVENT_8: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].RSTxR = HRTIM_TIMRESETTRIGGER_EEV_8; + } + break; + case HRTIM_EVENT_9: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].RSTxR = HRTIM_TIMRESETTRIGGER_EEV_9; + } + break; + case HRTIM_EVENT_10: + { + HRTIMx->HRTIM_TIMERx[TimerIdx].RSTxR = HRTIM_TIMRESETTRIGGER_EEV_10; + } + break; + default: + break; + } +} +/** + * @} + */ +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_i2c.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_i2c.c new file mode 100644 index 0000000..e50ccf2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_i2c.c @@ -0,0 +1,1585 @@ +/** + ****************************************************************************** + * @file stm32f30x_i2c.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the Inter-Integrated circuit (I2C): + * + Initialization and Configuration + * + Communications handling + * + SMBUS management + * + I2C registers management + * + Data transfers management + * + DMA transfers management + * + Interrupts and flags management + * + * @verbatim + ============================================================================ + ##### How to use this driver ##### + ============================================================================ + [..] + (#) Enable peripheral clock using RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2Cx, ENABLE) + function for I2C1 or I2C2. + (#) Enable SDA, SCL and SMBA (when used) GPIO clocks using + RCC_AHBPeriphClockCmd() function. + (#) Peripherals alternate function: + (++) Connect the pin to the desired peripherals' Alternate + Function (AF) using GPIO_PinAFConfig() function. + (++) Configure the desired pin in alternate function by: + GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF + (++) Select the type, OpenDrain and speed via + GPIO_PuPd, GPIO_OType and GPIO_Speed members + (++) Call GPIO_Init() function. + (#) Program the Mode, Timing , Own address, Ack and Acknowledged Address + using the I2C_Init() function. + (#) Optionally you can enable/configure the following parameters without + re-initialization (i.e there is no need to call again I2C_Init() function): + (++) Enable the acknowledge feature using I2C_AcknowledgeConfig() function. + (++) Enable the dual addressing mode using I2C_DualAddressCmd() function. + (++) Enable the general call using the I2C_GeneralCallCmd() function. + (++) Enable the clock stretching using I2C_StretchClockCmd() function. + (++) Enable the PEC Calculation using I2C_CalculatePEC() function. + (++) For SMBus Mode: + (+++) Enable the SMBusAlert pin using I2C_SMBusAlertCmd() function. + (#) Enable the NVIC and the corresponding interrupt using the function + I2C_ITConfig() if you need to use interrupt mode. + (#) When using the DMA mode + (++) Configure the DMA using DMA_Init() function. + (++) Active the needed channel Request using I2C_DMACmd() function. + (#) Enable the I2C using the I2C_Cmd() function. + (#) Enable the DMA using the DMA_Cmd() function when using DMA mode in the + transfers. + [..] + (@) When using I2C in Fast Mode Plus, SCL and SDA pin 20mA current drive capability + must be enabled by setting the driving capability control bit in SYSCFG. + + @endverbatim + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_i2c.h" +#include "stm32f30x_rcc.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup I2C + * @brief I2C driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +#define CR1_CLEAR_MASK ((uint32_t)0x00CFE0FF) /*I2C_AnalogFilter)); + assert_param(IS_I2C_DIGITAL_FILTER(I2C_InitStruct->I2C_DigitalFilter)); + assert_param(IS_I2C_MODE(I2C_InitStruct->I2C_Mode)); + assert_param(IS_I2C_OWN_ADDRESS1(I2C_InitStruct->I2C_OwnAddress1)); + assert_param(IS_I2C_ACK(I2C_InitStruct->I2C_Ack)); + assert_param(IS_I2C_ACKNOWLEDGE_ADDRESS(I2C_InitStruct->I2C_AcknowledgedAddress)); + + /* Disable I2Cx Peripheral */ + I2Cx->CR1 &= (uint32_t)~((uint32_t)I2C_CR1_PE); + + /*---------------------------- I2Cx FILTERS Configuration ------------------*/ + /* Get the I2Cx CR1 value */ + tmpreg = I2Cx->CR1; + /* Clear I2Cx CR1 register */ + tmpreg &= CR1_CLEAR_MASK; + /* Configure I2Cx: analog and digital filter */ + /* Set ANFOFF bit according to I2C_AnalogFilter value */ + /* Set DFN bits according to I2C_DigitalFilter value */ + tmpreg |= (uint32_t)I2C_InitStruct->I2C_AnalogFilter |(I2C_InitStruct->I2C_DigitalFilter << 8); + + /* Write to I2Cx CR1 */ + I2Cx->CR1 = tmpreg; + + /*---------------------------- I2Cx TIMING Configuration -------------------*/ + /* Configure I2Cx: Timing */ + /* Set TIMINGR bits according to I2C_Timing */ + /* Write to I2Cx TIMING */ + I2Cx->TIMINGR = I2C_InitStruct->I2C_Timing & TIMING_CLEAR_MASK; + + /* Enable I2Cx Peripheral */ + I2Cx->CR1 |= I2C_CR1_PE; + + /*---------------------------- I2Cx OAR1 Configuration ---------------------*/ + /* Clear tmpreg local variable */ + tmpreg = 0; + /* Clear OAR1 register */ + I2Cx->OAR1 = (uint32_t)tmpreg; + /* Clear OAR2 register */ + I2Cx->OAR2 = (uint32_t)tmpreg; + /* Configure I2Cx: Own Address1 and acknowledged address */ + /* Set OA1MODE bit according to I2C_AcknowledgedAddress value */ + /* Set OA1 bits according to I2C_OwnAddress1 value */ + tmpreg = (uint32_t)((uint32_t)I2C_InitStruct->I2C_AcknowledgedAddress | \ + (uint32_t)I2C_InitStruct->I2C_OwnAddress1); + /* Write to I2Cx OAR1 */ + I2Cx->OAR1 = tmpreg; + /* Enable Own Address1 acknowledgement */ + I2Cx->OAR1 |= I2C_OAR1_OA1EN; + + /*---------------------------- I2Cx MODE Configuration ---------------------*/ + /* Configure I2Cx: mode */ + /* Set SMBDEN and SMBHEN bits according to I2C_Mode value */ + tmpreg = I2C_InitStruct->I2C_Mode; + /* Write to I2Cx CR1 */ + I2Cx->CR1 |= tmpreg; + + /*---------------------------- I2Cx ACK Configuration ----------------------*/ + /* Get the I2Cx CR2 value */ + tmpreg = I2Cx->CR2; + /* Clear I2Cx CR2 register */ + tmpreg &= CR2_CLEAR_MASK; + /* Configure I2Cx: acknowledgement */ + /* Set NACK bit according to I2C_Ack value */ + tmpreg |= I2C_InitStruct->I2C_Ack; + /* Write to I2Cx CR2 */ + I2Cx->CR2 = tmpreg; +} + +/** + * @brief Fills each I2C_InitStruct member with its default value. + * @param I2C_InitStruct: pointer to an I2C_InitTypeDef structure which will be initialized. + * @retval None + */ +void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct) +{ + /*---------------- Reset I2C init structure parameters values --------------*/ + /* Initialize the I2C_Timing member */ + I2C_InitStruct->I2C_Timing = 0; + /* Initialize the I2C_AnalogFilter member */ + I2C_InitStruct->I2C_AnalogFilter = I2C_AnalogFilter_Enable; + /* Initialize the I2C_DigitalFilter member */ + I2C_InitStruct->I2C_DigitalFilter = 0; + /* Initialize the I2C_Mode member */ + I2C_InitStruct->I2C_Mode = I2C_Mode_I2C; + /* Initialize the I2C_OwnAddress1 member */ + I2C_InitStruct->I2C_OwnAddress1 = 0; + /* Initialize the I2C_Ack member */ + I2C_InitStruct->I2C_Ack = I2C_Ack_Disable; + /* Initialize the I2C_AcknowledgedAddress member */ + I2C_InitStruct->I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; +} + +/** + * @brief Enables or disables the specified I2C peripheral. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C peripheral */ + I2Cx->CR1 |= I2C_CR1_PE; + } + else + { + /* Disable the selected I2C peripheral */ + I2Cx->CR1 &= (uint32_t)~((uint32_t)I2C_CR1_PE); + } +} + + +/** + * @brief Enables or disables the specified I2C software reset. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @retval None + */ +void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + /* Disable peripheral */ + I2Cx->CR1 &= (uint32_t)~((uint32_t)I2C_CR1_PE); + + /* Perform a dummy read to delay the disable of peripheral for minimum + 3 APB clock cycles to perform the software reset functionality */ + *(__IO uint32_t *)(uint32_t)I2Cx; + + /* Enable peripheral */ + I2Cx->CR1 |= I2C_CR1_PE; +} + +/** + * @brief Enables or disables the specified I2C interrupts. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_IT: specifies the I2C interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg I2C_IT_ERRI: Error interrupt mask + * @arg I2C_IT_TCI: Transfer Complete interrupt mask + * @arg I2C_IT_STOPI: Stop Detection interrupt mask + * @arg I2C_IT_NACKI: Not Acknowledge received interrupt mask + * @arg I2C_IT_ADDRI: Address Match interrupt mask + * @arg I2C_IT_RXI: RX interrupt mask + * @arg I2C_IT_TXI: TX interrupt mask + * @param NewState: new state of the specified I2C interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_ITConfig(I2C_TypeDef* I2Cx, uint32_t I2C_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_I2C_CONFIG_IT(I2C_IT)); + + if (NewState != DISABLE) + { + /* Enable the selected I2C interrupts */ + I2Cx->CR1 |= I2C_IT; + } + else + { + /* Disable the selected I2C interrupts */ + I2Cx->CR1 &= (uint32_t)~((uint32_t)I2C_IT); + } +} + +/** + * @brief Enables or disables the I2C Clock stretching. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx Clock stretching. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable clock stretching */ + I2Cx->CR1 &= (uint32_t)~((uint32_t)I2C_CR1_NOSTRETCH); + } + else + { + /* Disable clock stretching */ + I2Cx->CR1 |= I2C_CR1_NOSTRETCH; + } +} + +/** + * @brief Enables or disables I2C wakeup from stop mode. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx stop mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_StopModeCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable wakeup from stop mode */ + I2Cx->CR1 |= I2C_CR1_WUPEN; + } + else + { + /* Disable wakeup from stop mode */ + I2Cx->CR1 &= (uint32_t)~((uint32_t)I2C_CR1_WUPEN); + } +} + +/** + * @brief Enables or disables the I2C own address 2. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C own address 2. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable own address 2 */ + I2Cx->OAR2 |= I2C_OAR2_OA2EN; + } + else + { + /* Disable own address 2 */ + I2Cx->OAR2 &= (uint32_t)~((uint32_t)I2C_OAR2_OA2EN); + } +} + +/** + * @brief Configures the I2C slave own address 2 and mask. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Address: specifies the slave address to be programmed. + * @param Mask: specifies own address 2 mask to be programmed. + * This parameter can be one of the following values: + * @arg I2C_OA2_NoMask: no mask. + * @arg I2C_OA2_Mask01: OA2[1] is masked and don't care. + * @arg I2C_OA2_Mask02: OA2[2:1] are masked and don't care. + * @arg I2C_OA2_Mask03: OA2[3:1] are masked and don't care. + * @arg I2C_OA2_Mask04: OA2[4:1] are masked and don't care. + * @arg I2C_OA2_Mask05: OA2[5:1] are masked and don't care. + * @arg I2C_OA2_Mask06: OA2[6:1] are masked and don't care. + * @arg I2C_OA2_Mask07: OA2[7:1] are masked and don't care. + * @retval None + */ +void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint16_t Address, uint8_t Mask) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_OWN_ADDRESS2(Address)); + assert_param(IS_I2C_OWN_ADDRESS2_MASK(Mask)); + + /* Get the old register value */ + tmpreg = I2Cx->OAR2; + + /* Reset I2Cx OA2 bit [7:1] and OA2MSK bit [1:0] */ + tmpreg &= (uint32_t)~((uint32_t)(I2C_OAR2_OA2 | I2C_OAR2_OA2MSK)); + + /* Set I2Cx SADD */ + tmpreg |= (uint32_t)(((uint32_t)Address & I2C_OAR2_OA2) | \ + (((uint32_t)Mask << 8) & I2C_OAR2_OA2MSK)) ; + + /* Store the new register value */ + I2Cx->OAR2 = tmpreg; +} + +/** + * @brief Enables or disables the I2C general call mode. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C general call mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable general call mode */ + I2Cx->CR1 |= I2C_CR1_GCEN; + } + else + { + /* Disable general call mode */ + I2Cx->CR1 &= (uint32_t)~((uint32_t)I2C_CR1_GCEN); + } +} + +/** + * @brief Enables or disables the I2C slave byte control. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C slave byte control. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_SlaveByteControlCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable slave byte control */ + I2Cx->CR1 |= I2C_CR1_SBC; + } + else + { + /* Disable slave byte control */ + I2Cx->CR1 &= (uint32_t)~((uint32_t)I2C_CR1_SBC); + } +} + +/** + * @brief Configures the slave address to be transmitted after start generation. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Address: specifies the slave address to be programmed. + * @note This function should be called before generating start condition. + * @retval None + */ +void I2C_SlaveAddressConfig(I2C_TypeDef* I2Cx, uint16_t Address) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_SLAVE_ADDRESS(Address)); + + /* Get the old register value */ + tmpreg = I2Cx->CR2; + + /* Reset I2Cx SADD bit [9:0] */ + tmpreg &= (uint32_t)~((uint32_t)I2C_CR2_SADD); + + /* Set I2Cx SADD */ + tmpreg |= (uint32_t)((uint32_t)Address & I2C_CR2_SADD); + + /* Store the new register value */ + I2Cx->CR2 = tmpreg; +} + +/** + * @brief Enables or disables the I2C 10-bit addressing mode for the master. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C 10-bit addressing mode. + * This parameter can be: ENABLE or DISABLE. + * @note This function should be called before generating start condition. + * @retval None + */ +void I2C_10BitAddressingModeCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable 10-bit addressing mode */ + I2Cx->CR2 |= I2C_CR2_ADD10; + } + else + { + /* Disable 10-bit addressing mode */ + I2Cx->CR2 &= (uint32_t)~((uint32_t)I2C_CR2_ADD10); + } +} + +/** + * @} + */ + + +/** @defgroup I2C_Group2 Communications handling functions + * @brief Communications handling functions + * +@verbatim + =============================================================================== + ##### Communications handling functions ##### + =============================================================================== + [..] This section provides a set of functions that handles I2C communication. + + [..] Automatic End mode is enabled using I2C_AutoEndCmd() function. When Reload + mode is enabled via I2C_ReloadCmd() AutoEnd bit has no effect. + + [..] I2C_NumberOfBytesConfig() function set the number of bytes to be transferred, + this configuration should be done before generating start condition in master + mode. + + [..] When switching from master write operation to read operation in 10Bit addressing + mode, master can only sends the 1st 7 bits of the 10 bit address, followed by + Read direction by enabling HEADR bit using I2C_10BitAddressHeader() function. + + [..] In master mode, when transferring more than 255 bytes Reload mode should be used + to handle communication. In the first phase of transfer, Nbytes should be set to + 255. After transferring these bytes TCR flag is set and I2C_TransferHandling() + function should be called to handle remaining communication. + + [..] In master mode, when software end mode is selected when all data is transferred + TC flag is set I2C_TransferHandling() function should be called to generate STOP + or generate ReStart. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the I2C automatic end mode (stop condition is + * automatically sent when nbytes data are transferred). + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C automatic end mode. + * This parameter can be: ENABLE or DISABLE. + * @note This function has effect if Reload mode is disabled. + * @retval None + */ +void I2C_AutoEndCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable Auto end mode */ + I2Cx->CR2 |= I2C_CR2_AUTOEND; + } + else + { + /* Disable Auto end mode */ + I2Cx->CR2 &= (uint32_t)~((uint32_t)I2C_CR2_AUTOEND); + } +} + +/** + * @brief Enables or disables the I2C nbytes reload mode. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the nbytes reload mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_ReloadCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable Auto Reload mode */ + I2Cx->CR2 |= I2C_CR2_RELOAD; + } + else + { + /* Disable Auto Reload mode */ + I2Cx->CR2 &= (uint32_t)~((uint32_t)I2C_CR2_RELOAD); + } +} + +/** + * @brief Configures the number of bytes to be transmitted/received. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Number_Bytes: specifies the number of bytes to be programmed. + * @retval None + */ +void I2C_NumberOfBytesConfig(I2C_TypeDef* I2Cx, uint8_t Number_Bytes) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + /* Get the old register value */ + tmpreg = I2Cx->CR2; + + /* Reset I2Cx Nbytes bit [7:0] */ + tmpreg &= (uint32_t)~((uint32_t)I2C_CR2_NBYTES); + + /* Set I2Cx Nbytes */ + tmpreg |= (uint32_t)(((uint32_t)Number_Bytes << 16 ) & I2C_CR2_NBYTES); + + /* Store the new register value */ + I2Cx->CR2 = tmpreg; +} + +/** + * @brief Configures the type of transfer request for the master. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_Direction: specifies the transfer request direction to be programmed. + * This parameter can be one of the following values: + * @arg I2C_Direction_Transmitter: Master request a write transfer + * @arg I2C_Direction_Receiver: Master request a read transfer + * @retval None + */ +void I2C_MasterRequestConfig(I2C_TypeDef* I2Cx, uint16_t I2C_Direction) +{ +/* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_DIRECTION(I2C_Direction)); + + /* Test on the direction to set/reset the read/write bit */ + if (I2C_Direction == I2C_Direction_Transmitter) + { + /* Request a write Transfer */ + I2Cx->CR2 &= (uint32_t)~((uint32_t)I2C_CR2_RD_WRN); + } + else + { + /* Request a read Transfer */ + I2Cx->CR2 |= I2C_CR2_RD_WRN; + } +} + +/** + * @brief Generates I2Cx communication START condition. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C START condition generation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Generate a START condition */ + I2Cx->CR2 |= I2C_CR2_START; + } + else + { + /* Disable the START condition generation */ + I2Cx->CR2 &= (uint32_t)~((uint32_t)I2C_CR2_START); + } +} + +/** + * @brief Generates I2Cx communication STOP condition. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C STOP condition generation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Generate a STOP condition */ + I2Cx->CR2 |= I2C_CR2_STOP; + } + else + { + /* Disable the STOP condition generation */ + I2Cx->CR2 &= (uint32_t)~((uint32_t)I2C_CR2_STOP); + } +} + +/** + * @brief Enables or disables the I2C 10-bit header only mode with read direction. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C 10-bit header only mode. + * This parameter can be: ENABLE or DISABLE. + * @note This mode can be used only when switching from master transmitter mode + * to master receiver mode. + * @retval None + */ +void I2C_10BitAddressHeaderCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable 10-bit header only mode */ + I2Cx->CR2 |= I2C_CR2_HEAD10R; + } + else + { + /* Disable 10-bit header only mode */ + I2Cx->CR2 &= (uint32_t)~((uint32_t)I2C_CR2_HEAD10R); + } +} + +/** + * @brief Generates I2C communication Acknowledge. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the Acknowledge. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable ACK generation */ + I2Cx->CR2 &= (uint32_t)~((uint32_t)I2C_CR2_NACK); + } + else + { + /* Enable NACK generation */ + I2Cx->CR2 |= I2C_CR2_NACK; + } +} + +/** + * @brief Returns the I2C slave matched address . + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @retval The value of the slave matched address . + */ +uint8_t I2C_GetAddressMatched(I2C_TypeDef* I2Cx) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + /* Return the slave matched address in the SR1 register */ + return (uint8_t)(((uint32_t)I2Cx->ISR & I2C_ISR_ADDCODE) >> 16) ; +} + +/** + * @brief Returns the I2C slave received request. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @retval The value of the received request. + */ +uint16_t I2C_GetTransferDirection(I2C_TypeDef* I2Cx) +{ + uint32_t tmpreg = 0; + uint16_t direction = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + /* Return the slave matched address in the SR1 register */ + tmpreg = (uint32_t)(I2Cx->ISR & I2C_ISR_DIR); + + /* If write transfer is requested */ + if (tmpreg == 0) + { + /* write transfer is requested */ + direction = I2C_Direction_Transmitter; + } + else + { + /* Read transfer is requested */ + direction = I2C_Direction_Receiver; + } + return direction; +} + +/** + * @brief Handles I2Cx communication when starting transfer or during transfer (TC or TCR flag are set). + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Address: specifies the slave address to be programmed. + * @param Number_Bytes: specifies the number of bytes to be programmed. + * This parameter must be a value between 0 and 255. + * @param ReloadEndMode: new state of the I2C START condition generation. + * This parameter can be one of the following values: + * @arg I2C_Reload_Mode: Enable Reload mode . + * @arg I2C_AutoEnd_Mode: Enable Automatic end mode. + * @arg I2C_SoftEnd_Mode: Enable Software end mode. + * @param StartStopMode: new state of the I2C START condition generation. + * This parameter can be one of the following values: + * @arg I2C_No_StartStop: Don't Generate stop and start condition. + * @arg I2C_Generate_Stop: Generate stop condition (Number_Bytes should be set to 0). + * @arg I2C_Generate_Start_Read: Generate Restart for read request. + * @arg I2C_Generate_Start_Write: Generate Restart for write request. + * @retval None + */ +void I2C_TransferHandling(I2C_TypeDef* I2Cx, uint16_t Address, uint8_t Number_Bytes, uint32_t ReloadEndMode, uint32_t StartStopMode) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_SLAVE_ADDRESS(Address)); + assert_param(IS_RELOAD_END_MODE(ReloadEndMode)); + assert_param(IS_START_STOP_MODE(StartStopMode)); + + /* Get the CR2 register value */ + tmpreg = I2Cx->CR2; + + /* clear tmpreg specific bits */ + tmpreg &= (uint32_t)~((uint32_t)(I2C_CR2_SADD | I2C_CR2_NBYTES | I2C_CR2_RELOAD | I2C_CR2_AUTOEND | I2C_CR2_RD_WRN | I2C_CR2_START | I2C_CR2_STOP)); + + /* update tmpreg */ + tmpreg |= (uint32_t)(((uint32_t)Address & I2C_CR2_SADD) | (((uint32_t)Number_Bytes << 16 ) & I2C_CR2_NBYTES) | \ + (uint32_t)ReloadEndMode | (uint32_t)StartStopMode); + + /* update CR2 register */ + I2Cx->CR2 = tmpreg; +} + +/** + * @} + */ + + +/** @defgroup I2C_Group3 SMBUS management functions + * @brief SMBUS management functions + * +@verbatim + =============================================================================== + ##### SMBUS management functions ##### + =============================================================================== + [..] This section provides a set of functions that handles SMBus communication + and timeouts detection. + + [..] The SMBus Device default address (0b1100 001) is enabled by calling I2C_Init() + function and setting I2C_Mode member of I2C_InitTypeDef() structure to + I2C_Mode_SMBusDevice. + + [..] The SMBus Host address (0b0001 000) is enabled by calling I2C_Init() + function and setting I2C_Mode member of I2C_InitTypeDef() structure to + I2C_Mode_SMBusHost. + + [..] The Alert Response Address (0b0001 100) is enabled using I2C_SMBusAlertCmd() + function. + + [..] To detect cumulative SCL stretch in master and slave mode, TIMEOUTB should be + configured (in accordance to SMBus specification) using I2C_TimeoutBConfig() + function then I2C_ExtendedClockTimeoutCmd() function should be called to enable + the detection. + + [..] SCL low timeout is detected by configuring TIMEOUTB using I2C_TimeoutBConfig() + function followed by the call of I2C_ClockTimeoutCmd(). When adding to this + procedure the call of I2C_IdleClockTimeoutCmd() function, Bus Idle condition + (both SCL and SDA high) is detected also. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables I2C SMBus alert. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx SMBus alert. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_SMBusAlertCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable SMBus alert */ + I2Cx->CR1 |= I2C_CR1_ALERTEN; + } + else + { + /* Disable SMBus alert */ + I2Cx->CR1 &= (uint32_t)~((uint32_t)I2C_CR1_ALERTEN); + } +} + +/** + * @brief Enables or disables I2C Clock Timeout (SCL Timeout detection). + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx clock Timeout. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_ClockTimeoutCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable Clock Timeout */ + I2Cx->TIMEOUTR |= I2C_TIMEOUTR_TIMOUTEN; + } + else + { + /* Disable Clock Timeout */ + I2Cx->TIMEOUTR &= (uint32_t)~((uint32_t)I2C_TIMEOUTR_TIMOUTEN); + } +} + +/** + * @brief Enables or disables I2C Extended Clock Timeout (SCL cumulative Timeout detection). + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx Extended clock Timeout. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_ExtendedClockTimeoutCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable Clock Timeout */ + I2Cx->TIMEOUTR |= I2C_TIMEOUTR_TEXTEN; + } + else + { + /* Disable Clock Timeout */ + I2Cx->TIMEOUTR &= (uint32_t)~((uint32_t)I2C_TIMEOUTR_TEXTEN); + } +} + +/** + * @brief Enables or disables I2C Idle Clock Timeout (Bus idle SCL and SDA + * high detection). + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx Idle clock Timeout. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_IdleClockTimeoutCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable Clock Timeout */ + I2Cx->TIMEOUTR |= I2C_TIMEOUTR_TIDLE; + } + else + { + /* Disable Clock Timeout */ + I2Cx->TIMEOUTR &= (uint32_t)~((uint32_t)I2C_TIMEOUTR_TIDLE); + } +} + +/** + * @brief Configures the I2C Bus Timeout A (SCL Timeout when TIDLE = 0 or Bus + * idle SCL and SDA high when TIDLE = 1). + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Timeout: specifies the TimeoutA to be programmed. + * @retval None + */ +void I2C_TimeoutAConfig(I2C_TypeDef* I2Cx, uint16_t Timeout) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_TIMEOUT(Timeout)); + + /* Get the old register value */ + tmpreg = I2Cx->TIMEOUTR; + + /* Reset I2Cx TIMEOUTA bit [11:0] */ + tmpreg &= (uint32_t)~((uint32_t)I2C_TIMEOUTR_TIMEOUTA); + + /* Set I2Cx TIMEOUTA */ + tmpreg |= (uint32_t)((uint32_t)Timeout & I2C_TIMEOUTR_TIMEOUTA) ; + + /* Store the new register value */ + I2Cx->TIMEOUTR = tmpreg; +} + +/** + * @brief Configures the I2C Bus Timeout B (SCL cumulative Timeout). + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Timeout: specifies the TimeoutB to be programmed. + * @retval None + */ +void I2C_TimeoutBConfig(I2C_TypeDef* I2Cx, uint16_t Timeout) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_TIMEOUT(Timeout)); + + /* Get the old register value */ + tmpreg = I2Cx->TIMEOUTR; + + /* Reset I2Cx TIMEOUTB bit [11:0] */ + tmpreg &= (uint32_t)~((uint32_t)I2C_TIMEOUTR_TIMEOUTB); + + /* Set I2Cx TIMEOUTB */ + tmpreg |= (uint32_t)(((uint32_t)Timeout << 16) & I2C_TIMEOUTR_TIMEOUTB) ; + + /* Store the new register value */ + I2Cx->TIMEOUTR = tmpreg; +} + +/** + * @brief Enables or disables I2C PEC calculation. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx PEC calculation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable PEC calculation */ + I2Cx->CR1 |= I2C_CR1_PECEN; + } + else + { + /* Disable PEC calculation */ + I2Cx->CR1 &= (uint32_t)~((uint32_t)I2C_CR1_PECEN); + } +} + +/** + * @brief Enables or disables I2C PEC transmission/reception request. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx PEC request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_PECRequestCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable PEC transmission/reception request */ + I2Cx->CR1 |= I2C_CR2_PECBYTE; + } + else + { + /* Disable PEC transmission/reception request */ + I2Cx->CR1 &= (uint32_t)~((uint32_t)I2C_CR2_PECBYTE); + } +} + +/** + * @brief Returns the I2C PEC. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @retval The value of the PEC . + */ +uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + /* Return the slave matched address in the SR1 register */ + return (uint8_t)((uint32_t)I2Cx->PECR & I2C_PECR_PEC); +} + +/** + * @} + */ + + +/** @defgroup I2C_Group4 I2C registers management functions + * @brief I2C registers management functions + * +@verbatim + =============================================================================== + ##### I2C registers management functions ##### + =============================================================================== + [..] This section provides a functions that allow user the management of + I2C registers. + +@endverbatim + * @{ + */ + + /** + * @brief Reads the specified I2C register and returns its value. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_Register: specifies the register to read. + * This parameter can be one of the following values: + * @arg I2C_Register_CR1: CR1 register. + * @arg I2C_Register_CR2: CR2 register. + * @arg I2C_Register_OAR1: OAR1 register. + * @arg I2C_Register_OAR2: OAR2 register. + * @arg I2C_Register_TIMINGR: TIMING register. + * @arg I2C_Register_TIMEOUTR: TIMEOUTR register. + * @arg I2C_Register_ISR: ISR register. + * @arg I2C_Register_ICR: ICR register. + * @arg I2C_Register_PECR: PECR register. + * @arg I2C_Register_RXDR: RXDR register. + * @arg I2C_Register_TXDR: TXDR register. + * @retval The value of the read register. + */ +uint32_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_REGISTER(I2C_Register)); + + tmp = (uint32_t)I2Cx; + tmp += I2C_Register; + + /* Return the selected register value */ + return (*(__IO uint32_t *) tmp); +} + +/** + * @} + */ + +/** @defgroup I2C_Group5 Data transfers management functions + * @brief Data transfers management functions + * +@verbatim + =============================================================================== + ##### Data transfers management functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to manage + the I2C data transfers. + + [..] The read access of the I2C_RXDR register can be done using + the I2C_ReceiveData() function and returns the received value. + Whereas a write access to the I2C_TXDR can be done using I2C_SendData() + function and stores the written data into TXDR. +@endverbatim + * @{ + */ + +/** + * @brief Sends a data byte through the I2Cx peripheral. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Data: Byte to be transmitted.. + * @retval None + */ +void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + /* Write in the DR register the data to be sent */ + I2Cx->TXDR = (uint8_t)Data; +} + +/** + * @brief Returns the most recent received data by the I2Cx peripheral. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @retval The value of the received data. + */ +uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + /* Return the data in the DR register */ + return (uint8_t)I2Cx->RXDR; +} + +/** + * @} + */ + + +/** @defgroup I2C_Group6 DMA transfers management functions + * @brief DMA transfers management functions + * +@verbatim + =============================================================================== + ##### DMA transfers management functions ##### + =============================================================================== + [..] This section provides two functions that can be used only in DMA mode. + [..] In DMA Mode, the I2C communication can be managed by 2 DMA Channel + requests: + (#) I2C_DMAReq_Tx: specifies the Tx buffer DMA transfer request. + (#) I2C_DMAReq_Rx: specifies the Rx buffer DMA transfer request. + [..] In this Mode it is advised to use the following function: + (+) I2C_DMACmd(I2C_TypeDef* I2Cx, uint32_t I2C_DMAReq, FunctionalState NewState); +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the I2C DMA interface. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_DMAReq: specifies the I2C DMA transfer request to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg I2C_DMAReq_Tx: Tx DMA transfer request + * @arg I2C_DMAReq_Rx: Rx DMA transfer request + * @param NewState: new state of the selected I2C DMA transfer request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_DMACmd(I2C_TypeDef* I2Cx, uint32_t I2C_DMAReq, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_I2C_DMA_REQ(I2C_DMAReq)); + + if (NewState != DISABLE) + { + /* Enable the selected I2C DMA requests */ + I2Cx->CR1 |= I2C_DMAReq; + } + else + { + /* Disable the selected I2C DMA requests */ + I2Cx->CR1 &= (uint32_t)~I2C_DMAReq; + } +} +/** + * @} + */ + + +/** @defgroup I2C_Group7 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + ##### Interrupts and flags management functions ##### + =============================================================================== + [..] This section provides functions allowing to configure the I2C Interrupts + sources and check or clear the flags or pending bits status. + The user should identify which mode will be used in his application to manage + the communication: Polling mode, Interrupt mode or DMA mode(refer I2C_Group6) . + + *** Polling Mode *** + ==================== + [..] In Polling Mode, the I2C communication can be managed by 15 flags: + (#) I2C_FLAG_TXE: to indicate the status of Transmit data register empty flag. + (#) I2C_FLAG_TXIS: to indicate the status of Transmit interrupt status flag . + (#) I2C_FLAG_RXNE: to indicate the status of Receive data register not empty flag. + (#) I2C_FLAG_ADDR: to indicate the status of Address matched flag (slave mode). + (#) I2C_FLAG_NACKF: to indicate the status of NACK received flag. + (#) I2C_FLAG_STOPF: to indicate the status of STOP detection flag. + (#) I2C_FLAG_TC: to indicate the status of Transfer complete flag(master mode). + (#) I2C_FLAG_TCR: to indicate the status of Transfer complete reload flag. + (#) I2C_FLAG_BERR: to indicate the status of Bus error flag. + (#) I2C_FLAG_ARLO: to indicate the status of Arbitration lost flag. + (#) I2C_FLAG_OVR: to indicate the status of Overrun/Underrun flag. + (#) I2C_FLAG_PECERR: to indicate the status of PEC error in reception flag. + (#) I2C_FLAG_TIMEOUT: to indicate the status of Timeout or Tlow detection flag. + (#) I2C_FLAG_ALERT: to indicate the status of SMBus Alert flag. + (#) I2C_FLAG_BUSY: to indicate the status of Bus busy flag. + + [..] In this Mode it is advised to use the following functions: + (+) FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG); + (+) void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG); + + [..] + (@)Do not use the BUSY flag to handle each data transmission or reception.It is + better to use the TXIS and RXNE flags instead. + + *** Interrupt Mode *** + ====================== + [..] In Interrupt Mode, the I2C communication can be managed by 7 interrupt sources + and 15 pending bits: + [..] Interrupt Source: + (#) I2C_IT_ERRI: specifies the interrupt source for the Error interrupt. + (#) I2C_IT_TCI: specifies the interrupt source for the Transfer Complete interrupt. + (#) I2C_IT_STOPI: specifies the interrupt source for the Stop Detection interrupt. + (#) I2C_IT_NACKI: specifies the interrupt source for the Not Acknowledge received interrupt. + (#) I2C_IT_ADDRI: specifies the interrupt source for the Address Match interrupt. + (#) I2C_IT_RXI: specifies the interrupt source for the RX interrupt. + (#) I2C_IT_TXI: specifies the interrupt source for the TX interrupt. + + [..] Pending Bits: + (#) I2C_IT_TXIS: to indicate the status of Transmit interrupt status flag. + (#) I2C_IT_RXNE: to indicate the status of Receive data register not empty flag. + (#) I2C_IT_ADDR: to indicate the status of Address matched flag (slave mode). + (#) I2C_IT_NACKF: to indicate the status of NACK received flag. + (#) I2C_IT_STOPF: to indicate the status of STOP detection flag. + (#) I2C_IT_TC: to indicate the status of Transfer complete flag (master mode). + (#) I2C_IT_TCR: to indicate the status of Transfer complete reload flag. + (#) I2C_IT_BERR: to indicate the status of Bus error flag. + (#) I2C_IT_ARLO: to indicate the status of Arbitration lost flag. + (#) I2C_IT_OVR: to indicate the status of Overrun/Underrun flag. + (#) I2C_IT_PECERR: to indicate the status of PEC error in reception flag. + (#) I2C_IT_TIMEOUT: to indicate the status of Timeout or Tlow detection flag. + (#) I2C_IT_ALERT: to indicate the status of SMBus Alert flag. + + [..] In this Mode it is advised to use the following functions: + (+) void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT); + (+) ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT); + +@endverbatim + * @{ + */ + +/** + * @brief Checks whether the specified I2C flag is set or not. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg I2C_FLAG_TXE: Transmit data register empty + * @arg I2C_FLAG_TXIS: Transmit interrupt status + * @arg I2C_FLAG_RXNE: Receive data register not empty + * @arg I2C_FLAG_ADDR: Address matched (slave mode) + * @arg I2C_FLAG_NACKF: NACK received flag + * @arg I2C_FLAG_STOPF: STOP detection flag + * @arg I2C_FLAG_TC: Transfer complete (master mode) + * @arg I2C_FLAG_TCR: Transfer complete reload + * @arg I2C_FLAG_BERR: Bus error + * @arg I2C_FLAG_ARLO: Arbitration lost + * @arg I2C_FLAG_OVR: Overrun/Underrun + * @arg I2C_FLAG_PECERR: PEC error in reception + * @arg I2C_FLAG_TIMEOUT: Timeout or Tlow detection flag + * @arg I2C_FLAG_ALERT: SMBus Alert + * @arg I2C_FLAG_BUSY: Bus busy + * @retval The new state of I2C_FLAG (SET or RESET). + */ +FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG) +{ + uint32_t tmpreg = 0; + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_GET_FLAG(I2C_FLAG)); + + /* Get the ISR register value */ + tmpreg = I2Cx->ISR; + + /* Get flag status */ + tmpreg &= I2C_FLAG; + + if(tmpreg != 0) + { + /* I2C_FLAG is set */ + bitstatus = SET; + } + else + { + /* I2C_FLAG is reset */ + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the I2Cx's pending flags. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg I2C_FLAG_ADDR: Address matched (slave mode) + * @arg I2C_FLAG_NACKF: NACK received flag + * @arg I2C_FLAG_STOPF: STOP detection flag + * @arg I2C_FLAG_BERR: Bus error + * @arg I2C_FLAG_ARLO: Arbitration lost + * @arg I2C_FLAG_OVR: Overrun/Underrun + * @arg I2C_FLAG_PECERR: PEC error in reception + * @arg I2C_FLAG_TIMEOUT: Timeout or Tlow detection flag + * @arg I2C_FLAG_ALERT: SMBus Alert + * @retval The new state of I2C_FLAG (SET or RESET). + */ +void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_CLEAR_FLAG(I2C_FLAG)); + + /* Clear the selected flag */ + I2Cx->ICR = I2C_FLAG; + } + +/** + * @brief Checks whether the specified I2C interrupt has occurred or not. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_IT: specifies the interrupt source to check. + * This parameter can be one of the following values: + * @arg I2C_IT_TXIS: Transmit interrupt status + * @arg I2C_IT_RXNE: Receive data register not empty + * @arg I2C_IT_ADDR: Address matched (slave mode) + * @arg I2C_IT_NACKF: NACK received flag + * @arg I2C_IT_STOPF: STOP detection flag + * @arg I2C_IT_TC: Transfer complete (master mode) + * @arg I2C_IT_TCR: Transfer complete reload + * @arg I2C_IT_BERR: Bus error + * @arg I2C_IT_ARLO: Arbitration lost + * @arg I2C_IT_OVR: Overrun/Underrun + * @arg I2C_IT_PECERR: PEC error in reception + * @arg I2C_IT_TIMEOUT: Timeout or Tlow detection flag + * @arg I2C_IT_ALERT: SMBus Alert + * @retval The new state of I2C_IT (SET or RESET). + */ +ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT) +{ + uint32_t tmpreg = 0; + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_GET_IT(I2C_IT)); + + /* Check if the interrupt source is enabled or not */ + /* If Error interrupt */ + if((uint32_t)(I2C_IT & ERROR_IT_MASK)) + { + enablestatus = (uint32_t)((I2C_CR1_ERRIE) & (I2Cx->CR1)); + } + /* If TC interrupt */ + else if((uint32_t)(I2C_IT & TC_IT_MASK)) + { + enablestatus = (uint32_t)((I2C_CR1_TCIE) & (I2Cx->CR1)); + } + else + { + enablestatus = (uint32_t)((I2C_IT) & (I2Cx->CR1)); + } + + /* Get the ISR register value */ + tmpreg = I2Cx->ISR; + + /* Get flag status */ + tmpreg &= I2C_IT; + + /* Check the status of the specified I2C flag */ + if((tmpreg != RESET) && enablestatus) + { + /* I2C_IT is set */ + bitstatus = SET; + } + else + { + /* I2C_IT is reset */ + bitstatus = RESET; + } + + /* Return the I2C_IT status */ + return bitstatus; +} + +/** + * @brief Clears the I2Cx's interrupt pending bits. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_IT: specifies the interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg I2C_IT_ADDR: Address matched (slave mode) + * @arg I2C_IT_NACKF: NACK received flag + * @arg I2C_IT_STOPF: STOP detection flag + * @arg I2C_IT_BERR: Bus error + * @arg I2C_IT_ARLO: Arbitration lost + * @arg I2C_IT_OVR: Overrun/Underrun + * @arg I2C_IT_PECERR: PEC error in reception + * @arg I2C_IT_TIMEOUT: Timeout or Tlow detection flag + * @arg I2C_IT_ALERT: SMBus Alert + * @retval The new state of I2C_IT (SET or RESET). + */ +void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_CLEAR_IT(I2C_IT)); + + /* Clear the selected flag */ + I2Cx->ICR = I2C_IT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_iwdg.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_iwdg.c new file mode 100644 index 0000000..c82e3e8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_iwdg.c @@ -0,0 +1,288 @@ +/** + ****************************************************************************** + * @file stm32f30x_iwdg.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the Independent watchdog (IWDG) peripheral: + * + Prescaler and Counter configuration + * + IWDG activation + * + Flag management + * + @verbatim + + =============================================================================== + ##### IWDG features ##### + =============================================================================== + [..] The IWDG can be started by either software or hardware (configurable + through option byte). + [..] The IWDG is clocked by its own dedicated low-speed clock (LSI) and + thus stays active even if the main clock fails. + Once the IWDG is started, the LSI is forced ON and cannot be disabled + (LSI cannot be disabled too), and the counter starts counting down from + the reset value of 0xFFF. When it reaches the end of count value (0x000) + a system reset is generated. + The IWDG counter should be reloaded at regular intervals to prevent + an MCU reset. + [..] The IWDG is implemented in the VDD voltage domain that is still functional + in STOP and STANDBY mode (IWDG reset can wake-up from STANDBY). + [..] IWDGRST flag in RCC_CSR register can be used to inform when a IWDG + reset occurs. + [..] Min-max timeout value @41KHz (LSI): ~0.1ms / ~25.5s + The IWDG timeout may vary due to LSI frequency dispersion. STM32F30x + devices provide the capability to measure the LSI frequency (LSI clock + connected internally to TIM16 CH1 input capture). The measured value + can be used to have an IWDG timeout with an acceptable accuracy. + For more information, please refer to the STM32F30x Reference manual. + + ##### How to use this driver ##### + =============================================================================== + [..] This driver allows to use IWDG peripheral with either window option enabled + or disabled. To do so follow one of the two procedures below. + (#) Window option is enabled: + (++) Start the IWDG using IWDG_Enable() function, when the IWDG is used + in software mode (no need to enable the LSI, it will be enabled + by hardware). + (++) Enable write access to IWDG_PR and IWDG_RLR registers using + IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable) function. + (++) Configure the IWDG prescaler using IWDG_SetPrescaler() function. + (++) Configure the IWDG counter value using IWDG_SetReload() function. + This value will be loaded in the IWDG counter each time the counter + is reloaded, then the IWDG will start counting down from this value. + (++) Wait for the IWDG registers to be updated using IWDG_GetFlagStatus() function. + (++) Configure the IWDG refresh window using IWDG_SetWindowValue() function. + + (#) Window option is disabled: + (++) Enable write access to IWDG_PR and IWDG_RLR registers using + IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable) function. + (++) Configure the IWDG prescaler using IWDG_SetPrescaler() function. + (++) Configure the IWDG counter value using IWDG_SetReload() function. + This value will be loaded in the IWDG counter each time the counter + is reloaded, then the IWDG will start counting down from this value. + (++) Wait for the IWDG registers to be updated using IWDG_GetFlagStatus() function. + (++) reload the IWDG counter at regular intervals during normal operation + to prevent an MCU reset, using IWDG_ReloadCounter() function. + (++) Start the IWDG using IWDG_Enable() function, when the IWDG is used + in software mode (no need to enable the LSI, it will be enabled + by hardware). + + @endverbatim + + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_iwdg.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup IWDG + * @brief IWDG driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* ---------------------- IWDG registers bit mask ----------------------------*/ +/* KR register bit mask */ +#define KR_KEY_RELOAD ((uint16_t)0xAAAA) +#define KR_KEY_ENABLE ((uint16_t)0xCCCC) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup IWDG_Private_Functions + * @{ + */ + +/** @defgroup IWDG_Group1 Prescaler and Counter configuration functions + * @brief Prescaler and Counter configuration functions + * +@verbatim + =============================================================================== + ##### Prescaler and Counter configuration functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables write access to IWDG_PR and IWDG_RLR registers. + * @param IWDG_WriteAccess: new state of write access to IWDG_PR and IWDG_RLR registers. + * This parameter can be one of the following values: + * @arg IWDG_WriteAccess_Enable: Enable write access to IWDG_PR and IWDG_RLR registers + * @arg IWDG_WriteAccess_Disable: Disable write access to IWDG_PR and IWDG_RLR registers + * @retval None + */ +void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess) +{ + /* Check the parameters */ + assert_param(IS_IWDG_WRITE_ACCESS(IWDG_WriteAccess)); + IWDG->KR = IWDG_WriteAccess; +} + +/** + * @brief Sets IWDG Prescaler value. + * @param IWDG_Prescaler: specifies the IWDG Prescaler value. + * This parameter can be one of the following values: + * @arg IWDG_Prescaler_4: IWDG prescaler set to 4 + * @arg IWDG_Prescaler_8: IWDG prescaler set to 8 + * @arg IWDG_Prescaler_16: IWDG prescaler set to 16 + * @arg IWDG_Prescaler_32: IWDG prescaler set to 32 + * @arg IWDG_Prescaler_64: IWDG prescaler set to 64 + * @arg IWDG_Prescaler_128: IWDG prescaler set to 128 + * @arg IWDG_Prescaler_256: IWDG prescaler set to 256 + * @retval None + */ +void IWDG_SetPrescaler(uint8_t IWDG_Prescaler) +{ + /* Check the parameters */ + assert_param(IS_IWDG_PRESCALER(IWDG_Prescaler)); + IWDG->PR = IWDG_Prescaler; +} + +/** + * @brief Sets IWDG Reload value. + * @param Reload: specifies the IWDG Reload value. + * This parameter must be a number between 0 and 0x0FFF. + * @retval None + */ +void IWDG_SetReload(uint16_t Reload) +{ + /* Check the parameters */ + assert_param(IS_IWDG_RELOAD(Reload)); + IWDG->RLR = Reload; +} + +/** + * @brief Reloads IWDG counter with value defined in the reload register + * (write access to IWDG_PR and IWDG_RLR registers disabled). + * @param None + * @retval None + */ +void IWDG_ReloadCounter(void) +{ + IWDG->KR = KR_KEY_RELOAD; +} + + +/** + * @brief Sets the IWDG window value. + * @param WindowValue: specifies the window value to be compared to the downcounter. + * @retval None + */ +void IWDG_SetWindowValue(uint16_t WindowValue) +{ + /* Check the parameters */ + assert_param(IS_IWDG_WINDOW_VALUE(WindowValue)); + IWDG->WINR = WindowValue; +} + +/** + * @} + */ + +/** @defgroup IWDG_Group2 IWDG activation function + * @brief IWDG activation function + * +@verbatim + =============================================================================== + ##### IWDG activation function ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables IWDG (write access to IWDG_PR and IWDG_RLR registers disabled). + * @param None + * @retval None + */ +void IWDG_Enable(void) +{ + IWDG->KR = KR_KEY_ENABLE; +} + +/** + * @} + */ + +/** @defgroup IWDG_Group3 Flag management function + * @brief Flag management function + * +@verbatim + =============================================================================== + ##### Flag management function ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Checks whether the specified IWDG flag is set or not. + * @param IWDG_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg IWDG_FLAG_PVU: Prescaler Value Update on going + * @arg IWDG_FLAG_RVU: Reload Value Update on going + * @arg IWDG_FLAG_WVU: Counter Window Value Update on going + * @retval The new state of IWDG_FLAG (SET or RESET). + */ +FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_IWDG_FLAG(IWDG_FLAG)); + if ((IWDG->SR & IWDG_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_misc.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_misc.c new file mode 100644 index 0000000..b4a2978 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_misc.c @@ -0,0 +1,230 @@ +/** + ****************************************************************************** + * @file stm32f30x_misc.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides all the miscellaneous firmware functions (add-on + * to CMSIS functions). + * + @verbatim + + =============================================================================== + ##### How to configure Interrupts using driver ##### + =============================================================================== + [..] This section provide functions allowing to configure the NVIC interrupts + (IRQ). The Cortex-M4 exceptions are managed by CMSIS functions. + (#) Configure the NVIC Priority Grouping using NVIC_PriorityGroupConfig() + function according to the following table. + The table below gives the allowed values of the pre-emption priority + and subpriority according to the Priority Grouping configuration + performed by NVIC_PriorityGroupConfig function. + + (#) Enable and Configure the priority of the selected IRQ Channels. + [..] + (@) When the NVIC_PriorityGroup_0 is selected, it will no any nested interrupt, + the IRQ priority will be managed only by subpriority. + The sub-priority is only used to sort pending exception priorities, + and does not affect active exceptions. + (@) Lower priority values gives higher priority. + (@) Priority Order: + (#@) Lowest Preemption priority. + (#@) Lowest Subpriority. + (#@) Lowest hardware priority (IRQn position). + + @endverbatim + + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_misc.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup MISC + * @brief MISC driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup MISC_Private_Functions + * @{ + */ + +/** + * @brief Configures the priority grouping: pre-emption priority and subpriority. + * @param NVIC_PriorityGroup: specifies the priority grouping bits length. + * This parameter can be one of the following values: + * @arg NVIC_PriorityGroup_0: 0 bits for pre-emption priority. + * 4 bits for subpriority. + * @arg NVIC_PriorityGroup_1: 1 bits for pre-emption priority. + * 3 bits for subpriority. + * @arg NVIC_PriorityGroup_2: 2 bits for pre-emption priority. + * 2 bits for subpriority. + * @arg NVIC_PriorityGroup_3: 3 bits for pre-emption priority. + * 1 bits for subpriority. + * @arg NVIC_PriorityGroup_4: 4 bits for pre-emption priority. + * 0 bits for subpriority. + * @note When NVIC_PriorityGroup_0 is selected, it will no be any nested + * interrupt. This interrupts priority is managed only with subpriority. + * @retval None + */ +void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup) +{ + /* Check the parameters */ + assert_param(IS_NVIC_PRIORITY_GROUP(NVIC_PriorityGroup)); + + /* Set the PRIGROUP[10:8] bits according to NVIC_PriorityGroup value */ + SCB->AIRCR = AIRCR_VECTKEY_MASK | NVIC_PriorityGroup; +} + +/** + * @brief Initializes the NVIC peripheral according to the specified + * parameters in the NVIC_InitStruct. + * @note To configure interrupts priority correctly, the NVIC_PriorityGroupConfig() + * function should be called before. + * @param NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure that contains + * the configuration information for the specified NVIC peripheral. + * @retval None + */ +void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct) +{ + uint32_t tmppriority = 0x00, tmppre = 0x00, tmpsub = 0x0F; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NVIC_InitStruct->NVIC_IRQChannelCmd)); + assert_param(IS_NVIC_PREEMPTION_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority)); + assert_param(IS_NVIC_SUB_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelSubPriority)); + + if (NVIC_InitStruct->NVIC_IRQChannelCmd != DISABLE) + { + /* Compute the Corresponding IRQ Priority --------------------------------*/ + tmppriority = (0x700 - ((SCB->AIRCR) & (uint32_t)0x700))>> 0x08; + tmppre = (0x4 - tmppriority); + tmpsub = tmpsub >> tmppriority; + + tmppriority = (uint32_t)NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority << tmppre; + tmppriority |= NVIC_InitStruct->NVIC_IRQChannelSubPriority & tmpsub; + tmppriority = tmppriority << 0x04; + + NVIC->IP[NVIC_InitStruct->NVIC_IRQChannel] = tmppriority; + + /* Enable the Selected IRQ Channels --------------------------------------*/ + NVIC->ISER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] = + (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F); + } + else + { + /* Disable the Selected IRQ Channels -------------------------------------*/ + NVIC->ICER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] = + (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F); + } +} + +/** + * @brief Sets the vector table location and Offset. + * @param NVIC_VectTab: specifies if the vector table is in RAM or FLASH memory. + * This parameter can be one of the following values: + * @arg NVIC_VectTab_RAM + * @arg NVIC_VectTab_FLASH + * @param Offset: Vector Table base offset field. This value must be a multiple of 0x200. + * @retval None + */ +void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset) +{ + /* Check the parameters */ + assert_param(IS_NVIC_VECTTAB(NVIC_VectTab)); + assert_param(IS_NVIC_OFFSET(Offset)); + + SCB->VTOR = NVIC_VectTab | (Offset & (uint32_t)0x1FFFFF80); +} + +/** + * @brief Selects the condition for the system to enter low power mode. + * @param LowPowerMode: Specifies the new mode for the system to enter low power mode. + * This parameter can be one of the following values: + * @arg NVIC_LP_SEVONPEND + * @arg NVIC_LP_SLEEPDEEP + * @arg NVIC_LP_SLEEPONEXIT + * @param NewState: new state of LP condition. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_NVIC_LP(LowPowerMode)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + SCB->SCR |= LowPowerMode; + } + else + { + SCB->SCR &= (uint32_t)(~(uint32_t)LowPowerMode); + } +} + +/** + * @brief Configures the SysTick clock source. + * @param SysTick_CLKSource: specifies the SysTick clock source. + * This parameter can be one of the following values: + * @arg SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8 selected as SysTick clock source. + * @arg SysTick_CLKSource_HCLK: AHB clock selected as SysTick clock source. + * @retval None + */ +void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource) +{ + /* Check the parameters */ + assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource)); + if (SysTick_CLKSource == SysTick_CLKSource_HCLK) + { + SysTick->CTRL |= SysTick_CLKSource_HCLK; + } + else + { + SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_opamp.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_opamp.c new file mode 100644 index 0000000..aae4187 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_opamp.c @@ -0,0 +1,575 @@ +/** + ****************************************************************************** + * @file stm32f30x_opamp.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the operational amplifiers (OPAMP1,...OPAMP4) peripheral: + * + OPAMP Configuration + * + OPAMP calibration + * + @verbatim + + ============================================================================== + ##### OPAMP Peripheral Features ##### + ============================================================================== + + [..] + The device integrates 4 operational amplifiers OPAMP1, OPAMP2, OPAMP3 and OPAMP4: + + (+) The OPAMPs non inverting input can be selected among the list shown by + table below. + + (+) The OPAMPs inverting input can be selected among the list shown by + table below. + + (+) The OPAMPs outputs can be internally connected to the inverting input + (follower mode) + (+) The OPAMPs outputs can be internally connected to resistor feedback + output (Programmable Gain Amplifier mode) + + (+) The OPAMPs outputs can be internally connected to ADC + + (+) The OPAMPs can be calibrated to compensate the offset compensation + + (+) Timer-controlled Mux for automatic switch of inverting and + non-inverting input + + OPAMPs inverting/non-inverting inputs: + +--------------------------------------------------------------+ + | | | OPAMP1 | OPAMP2 | OPAMP3 | OPAMP4 | + |-----------------|--------|--------|--------|--------|--------| + | | PGA | OK | OK | OK | OK | + | Inverting Input | Vout | OK | OK | OK | OK | + | | IO1 | PC5 | PC5 | PB10 | PB10 | + | | IO2 | PA3 | PA5 | PB2 | PD8 | + |-----------------|--------|--------|--------|--------|--------| + | | IO1 | PA7 | PD14 | PB13 | PD11 | + | Non Inverting | IO2 | PA5 | PB14 | PA5 | PB11 | + | Input | IO3 | PA3 | PB0 | PA1 | PA4 | + | | IO4 | PA1 | PA7 | PB0 | PB13 | + +--------------------------------------------------------------+ + + ##### How to use this driver ##### + ============================================================================== + [..] + This driver provides functions to configure and program the OPAMP + of all STM32F30x devices. + + To use the OPAMP, perform the following steps: + + (#) Enable the SYSCFG APB clock to get write access to OPAMP + register using RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); + + (#) Configure the OPAMP input in analog mode using GPIO_Init() + + (#) Configure the OPAMP using OPAMP_Init() function: + (++) Select the inverting input + (++) Select the non-inverting inverting input + + (#) Enable the OPAMP using OPAMP_Cmd() function + + @endverbatim + + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_opamp.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup OPAMP + * @brief OPAMP driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define OPAMP_CSR_DEFAULT_MASK ((uint32_t)0xFFFFFF93) +#define OPAMP_CSR_TIMERMUX_MASK ((uint32_t)0xFFFFF8FF) +#define OPAMP_CSR_TRIMMING_MASK ((uint32_t)0x0000001F) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup OPAMP_Private_Functions + * @{ + */ + +/** @defgroup OPAMP_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes OPAMP peripheral registers to their default reset values. + * @note Deinitialization can't be performed if the OPAMP configuration is locked. + * To unlock the configuration, perform a system reset. + * @param OPAMP_Selection: the selected OPAMP. + * This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4 + * to select the OPAMP peripheral. + * @param None + * @retval None + */ +void OPAMP_DeInit(uint32_t OPAMP_Selection) +{ + /*!< Set OPAMP_CSR register to reset value */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) = ((uint32_t)0x00000000); +} + +/** + * @brief Initializes the OPAMP peripheral according to the specified parameters + * in OPAMP_InitStruct + * @note If the selected OPAMP is locked, initialization can't be performed. + * To unlock the configuration, perform a system reset. + * @param OPAMP_Selection: the selected OPAMP. + * This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4 + * to select the OPAMP peripheral. + * @param OPAMP_InitStruct: pointer to an OPAMP_InitTypeDef structure that contains + * the configuration information for the specified OPAMP peripheral. + * - OPAMP_InvertingInput specifies the inverting input of OPAMP + * - OPAMP_NonInvertingInput specifies the non inverting input of OPAMP + * @retval None + */ +void OPAMP_Init(uint32_t OPAMP_Selection, OPAMP_InitTypeDef* OPAMP_InitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection)); + assert_param(IS_OPAMP_INVERTING_INPUT(OPAMP_InitStruct->OPAMP_InvertingInput)); + assert_param(IS_OPAMP_NONINVERTING_INPUT(OPAMP_InitStruct->OPAMP_NonInvertingInput)); + + /*!< Get the OPAMPx_CSR register value */ + tmpreg = *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection); + + /*!< Clear the inverting and non inverting bits selection bits */ + tmpreg &= (uint32_t) (OPAMP_CSR_DEFAULT_MASK); + + /*!< Configure OPAMP: inverting and non inverting inputs */ + tmpreg |= (uint32_t)(OPAMP_InitStruct->OPAMP_InvertingInput | OPAMP_InitStruct->OPAMP_NonInvertingInput); + + /*!< Write to OPAMPx_CSR register */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) = tmpreg; +} + +/** + * @brief Fills each OPAMP_InitStruct member with its default value. + * @param OPAMP_InitStruct: pointer to an OPAMP_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void OPAMP_StructInit(OPAMP_InitTypeDef* OPAMP_InitStruct) +{ + OPAMP_InitStruct->OPAMP_NonInvertingInput = OPAMP_NonInvertingInput_IO1; + OPAMP_InitStruct->OPAMP_InvertingInput = OPAMP_InvertingInput_IO1; +} + +/** + * @brief Configure the feedback resistor gain. + * @note If the selected OPAMP is locked, gain configuration can't be performed. + * To unlock the configuration, perform a system reset. + * @param OPAMP_Selection: the selected OPAMP. + * This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4 + * to select the OPAMP peripheral. + * @param NewState: new state of the OPAMP peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void OPAMP_PGAConfig(uint32_t OPAMP_Selection, uint32_t OPAMP_PGAGain, uint32_t OPAMP_PGAConnect) +{ + /* Check the parameters */ + assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection)); + assert_param(IS_OPAMP_PGAGAIN(OPAMP_PGAGain)); + assert_param(IS_OPAMP_PGACONNECT(OPAMP_PGAConnect)); + + /* Reset the configuration bits */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) &= (uint32_t)(~OPAMP_CSR_PGGAIN); + + /* Set the new configuration */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) |= (uint32_t) (OPAMP_PGAGain | OPAMP_PGAConnect); +} + +/** + * @brief Configure the OPAMP's internal reference. + * @note This feature is used when calibration enabled or OPAMP's reference + * connected to the non inverting input. + * @note If the selected OPAMP is locked, Vref configuration can't be performed. + * To unlock the configuration, perform a system reset. + * @param OPAMP_Selection: the selected OPAMP. + * This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4 + * to select the OPAMP peripheral. + * @param OPAMP_Vref: This parameter can be: + * OPAMP_Vref_3VDDA: OPMAP Vref = 3.3% VDDA + * OPAMP_Vref_10VDDA: OPMAP Vref = 10% VDDA + * OPAMP_Vref_50VDDA: OPMAP Vref = 50% VDDA + * OPAMP_Vref_90VDDA: OPMAP Vref = 90% VDDA + * @retval None + */ +void OPAMP_VrefConfig(uint32_t OPAMP_Selection, uint32_t OPAMP_Vref) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection)); + assert_param(IS_OPAMP_VREF(OPAMP_Vref)); + + /*!< Get the OPAMPx_CSR register value */ + tmpreg = *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection); + + /*!< Clear the CALSEL bits */ + tmpreg &= (uint32_t) (~OPAMP_CSR_CALSEL); + + /*!< Configure OPAMP reference */ + tmpreg |= (uint32_t)(OPAMP_Vref); + + /*!< Write to OPAMPx_CSR register */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) = tmpreg; +} + +/** + * @brief Connnect the internal reference to the OPAMP's non inverting input. + * @note If the selected OPAMP is locked, Vref configuration can't be performed. + * To unlock the configuration, perform a system reset. + * @param OPAMP_Selection: the selected OPAMP. + * This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4 + * to select the OPAMP peripheral. + * @param NewState: new state of the OPAMP peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void OPAMP_VrefConnectNonInvertingInput(uint32_t OPAMP_Selection, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Connnect the internal reference to the OPAMP's non inverting input */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) |= (uint32_t) (OPAMP_CSR_FORCEVP); + } + else + { + /* Disconnnect the internal reference to the OPAMP's non inverting input */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) &= (uint32_t)(~OPAMP_CSR_FORCEVP); + } +} + +/** + * @brief Enables or disables connecting the OPAMP's internal reference to ADC. + * @note If the selected OPAMP is locked, Vref connection can't be performed. + * To unlock the configuration, perform a system reset. + * @param NewState: new state of the Vrefint output. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void OPAMP_VrefConnectADCCmd(uint32_t OPAMP_Selection, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable output internal reference */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) |= (uint32_t) (OPAMP_CSR_TSTREF); + } + else + { + /* Disable output internal reference */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) &= (uint32_t)(~OPAMP_CSR_TSTREF); + } +} + +/** + * @brief Configure the OPAMP peripheral (secondary inputs) for timer-controlled + * mux mode according to the specified parameters in OPAMP_InitStruct. + * @note If the selected OPAMP is locked, timer-controlled mux configuration + * can't be performed. + * To unlock the configuration, perform a system reset. + * @param OPAMP_Selection: the selected OPAMP. + * This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4 + * to select the OPAMP peripheral. + * @param OPAMP_InitStruct: pointer to an OPAMP_InitTypeDef structure that contains + * the configuration information for the specified OPAMP peripheral. + * - OPAMP_InvertingInput specifies the inverting input of OPAMP + * - OPAMP_NonInvertingInput specifies the non inverting input of OPAMP + * @note PGA and Vout can't be selected as seconadry inverting input. + * @retval None + */ +void OPAMP_TimerControlledMuxConfig(uint32_t OPAMP_Selection, OPAMP_InitTypeDef* OPAMP_InitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection)); + assert_param(IS_OPAMP_SECONDARY_INVINPUT(OPAMP_InitStruct->OPAMP_InvertingInput)); + assert_param(IS_OPAMP_NONINVERTING_INPUT(OPAMP_InitStruct->OPAMP_NonInvertingInput)); + + /*!< Get the OPAMPx_CSR register value */ + tmpreg = *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection); + + /*!< Clear the secondary inverting bit, secondary non inverting bit and TCMEN bits */ + tmpreg &= (uint32_t) (OPAMP_CSR_TIMERMUX_MASK); + + /*!< Configure OPAMP: secondary inverting and non inverting inputs */ + tmpreg |= (uint32_t)((uint32_t)(OPAMP_InitStruct->OPAMP_InvertingInput<<3) | (uint32_t)(OPAMP_InitStruct->OPAMP_NonInvertingInput<<7)); + + /*!< Write to OPAMPx_CSR register */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) = tmpreg; +} + +/** + * @brief Enable or disable the timer-controlled mux mode. + * @note If the selected OPAMP is locked, enable/disable can't be performed. + * To unlock the configuration, perform a system reset. + * @param OPAMP_Selection: the selected OPAMP. + * This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4 + * to select the OPAMP peripheral. + * @param NewState: new state of the OPAMP peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void OPAMP_TimerControlledMuxCmd(uint32_t OPAMP_Selection, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the timer-controlled Mux mode */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) |= (uint32_t) (OPAMP_CSR_TCMEN); + } + else + { + /* Disable the timer-controlled Mux mode */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) &= (uint32_t)(~OPAMP_CSR_TCMEN); + } +} + +/** + * @brief Enable or disable the OPAMP peripheral. + * @note If the selected OPAMP is locked, enable/disable can't be performed. + * To unlock the configuration, perform a system reset. + * @param OPAMP_Selection: the selected OPAMP. + * This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4 + * to select the OPAMP peripheral. + * @param NewState: new state of the OPAMP peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void OPAMP_Cmd(uint32_t OPAMP_Selection, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected OPAMPx peripheral */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) |= (uint32_t) (OPAMP_CSR_OPAMPxEN); + } + else + { + /* Disable the selected OPAMPx peripheral */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) &= (uint32_t)(~OPAMP_CSR_OPAMPxEN); + } +} + +/** + * @brief Return the output level (high or low) during calibration of the selected OPAMP. + * @param OPAMP_Selection: the selected OPAMP. + * This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4 + * to select the OPAMP peripheral. + * - OPAMP output is low when the non-inverting input is at a lower + * voltage than the inverting input + * - OPAMP output is high when the non-inverting input is at a higher + * voltage than the inverting input + * @note OPAMP ouput level is provided only during calibration phase. + * @retval Returns the selected OPAMP output level: low or high. + * + */ +uint32_t OPAMP_GetOutputLevel(uint32_t OPAMP_Selection) +{ + uint32_t opampout = 0x0; + + /* Check the parameters */ + assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection)); + + /* Check if selected OPAMP output is high */ + if ((*(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) & (OPAMP_CSR_OUTCAL)) != 0) + { + opampout = OPAMP_OutputLevel_High; + } + else + { + opampout = OPAMP_OutputLevel_Low; + } + + /* Return the OPAMP output level */ + return (uint32_t)(opampout); +} + +/** + * @brief Select the trimming mode. + * @param OffsetTrimming: the selected offset trimming mode. + * This parameter can be one of the following values: + * @arg OPAMP_Trimming_Factory: factory trimming values are used for offset + * calibration + * @arg OPAMP_Trimming_User: user trimming values are used for offset + * calibration + * @note When OffsetTrimming_User is selected, use OPAMP_OffsetTrimConfig() + * function or OPAMP_OffsetTrimLowPowerConfig() function to adjust + * trimming value. + * @retval None + */ +void OPAMP_OffsetTrimModeSelect(uint32_t OPAMP_Selection, uint32_t OPAMP_Trimming) +{ + /* Check the parameters */ + assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection)); + assert_param(IS_OPAMP_TRIMMING(OPAMP_Trimming)); + + /* Reset USERTRIM bit */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) &= (~(uint32_t) (OPAMP_CSR_USERTRIM)); + + /* Select trimming mode */ + *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection) |= OPAMP_Trimming; +} + +/** + * @brief Configure the trimming value of the OPAMP. + * @param OPAMP_Selection: the selected OPAMP. + * This parameter can be OPAMP_Selection_OPAMPx where x can be 1 to 4 + * to select the OPAMP peripheral. + * @param OPAMP_Input: the selected OPAMP input. + * This parameter can be one of the following values: + * @arg OPAMP_Input_Inverting: Inverting input is selected to configure the trimming value + * @arg OPAMP_Input_NonInverting: Non inverting input is selected to configure the trimming value + * @param OPAMP_TrimValue: the trimming value. This parameter can be any value lower + * or equal to 0x0000001F. + * @retval None + */ +void OPAMP_OffsetTrimConfig(uint32_t OPAMP_Selection, uint32_t OPAMP_Input, uint32_t OPAMP_TrimValue) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_OPAMP_ALL_PERIPH(OPAMP_Selection)); + assert_param(IS_OPAMP_INPUT(OPAMP_Input)); + assert_param(IS_OPAMP_TRIMMINGVALUE(OPAMP_TrimValue)); + + /*!< Get the OPAMPx_CSR register value */ + tmpreg = *(__IO uint32_t *) (OPAMP_BASE + OPAMP_Selection); + + /*!< Clear the trimming bits */ + tmpreg &= ((uint32_t)~(OPAMP_CSR_TRIMMING_MASK<
    © COPYRIGHT 2014 STMicroelectronics
    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_pwr.h" +#include "stm32f30x_rcc.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup PWR + * @brief PWR driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* --------- PWR registers bit address in the alias region ---------- */ +#define PWR_OFFSET (PWR_BASE - PERIPH_BASE) + +/* --- CR Register ---*/ + +/* Alias word address of DBP bit */ +#define CR_OFFSET (PWR_OFFSET + 0x00) +#define DBP_BitNumber 0x08 +#define CR_DBP_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4)) + +/* Alias word address of PVDE bit */ +#define PVDE_BitNumber 0x04 +#define CR_PVDE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4)) + +/* ------------------ PWR registers bit mask ------------------------ */ + +/* CR register bit mask */ +#define CR_DS_MASK ((uint32_t)0xFFFFFFFC) +#define CR_PLS_MASK ((uint32_t)0xFFFFFF1F) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup PWR_Private_Functions + * @{ + */ + +/** @defgroup PWR_Group1 Backup Domain Access function + * @brief Backup Domain Access function + * +@verbatim + ============================================================================== + ##### Backup Domain Access function ##### + ============================================================================== + + [..] After reset, the Backup Domain Registers (RCC BDCR Register, RTC registers + and RTC backup registers) are protected against possible stray write accesses. + [..] To enable access to Backup domain use the PWR_BackupAccessCmd(ENABLE) function. + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the PWR peripheral registers to their default reset values. + * @param None + * @retval None + */ +void PWR_DeInit(void) +{ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, DISABLE); +} + +/** + * @brief Enables or disables access to the RTC and backup registers. + * @note If the HSE divided by 32 is used as the RTC clock, the + * Backup Domain Access should be kept enabled. + * @param NewState: new state of the access to the RTC and backup registers. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_BackupAccessCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_DBP_BB = (uint32_t)NewState; +} + +/** + * @} + */ + +/** @defgroup PWR_Group2 PVD configuration functions + * @brief PVD configuration functions + * +@verbatim + =============================================================================== + ##### PVD configuration functions ##### + ============================================================================== + [..] + (+) The PVD is used to monitor the VDD power supply by comparing it to a threshold + selected by the PVD Level (PLS[2:0] bits in the PWR_CR). + (+) A PVDO flag is available to indicate if VDD/VDDA is higher or lower than the + PVD threshold. This event is internally connected to the EXTI line16 + and can generate an interrupt if enabled through the EXTI registers. + (+) The PVD is stopped in Standby mode. + +@endverbatim + * @{ + */ + +/** + * @brief Configures the voltage threshold detected by the Power Voltage Detector(PVD). + * @param PWR_PVDLevel: specifies the PVD detection level + * This parameter can be one of the following values: + * @arg PWR_PVDLevel_0: PVD detection level set to 2.18V + * @arg PWR_PVDLevel_1: PVD detection level set to 2.28V + * @arg PWR_PVDLevel_2: PVD detection level set to 2.38V + * @arg PWR_PVDLevel_3: PVD detection level set to 2.48V + * @arg PWR_PVDLevel_4: PVD detection level set to 2.58V + * @arg PWR_PVDLevel_5: PVD detection level set to 2.68V + * @arg PWR_PVDLevel_6: PVD detection level set to 2.78V + * @arg PWR_PVDLevel_7: PVD detection level set to 2.88V + * @retval None + */ +void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel)); + + tmpreg = PWR->CR; + + /* Clear PLS[7:5] bits */ + tmpreg &= CR_PLS_MASK; + + /* Set PLS[7:5] bits according to PWR_PVDLevel value */ + tmpreg |= PWR_PVDLevel; + + /* Store the new value */ + PWR->CR = tmpreg; +} + +/** + * @brief Enables or disables the Power Voltage Detector(PVD). + * @param NewState: new state of the PVD. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_PVDCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)NewState; +} + +/** + * @} + */ + +/** @defgroup PWR_Group3 WakeUp pins configuration functions + * @brief WakeUp pins configuration functions + * +@verbatim + =============================================================================== + ##### WakeUp pins configuration functions ##### + =============================================================================== + [..] + (+) WakeUp pins are used to wakeup the system from Standby mode. These pins are + forced in input pull down configuration and are active on rising edges. + (+) There are three WakeUp pins: WakeUp Pin 1 on PA.00, WakeUp Pin 2 on PC.13 and + WakeUp Pin 3 on PE.06. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the WakeUp Pin functionality. + * @param PWR_WakeUpPin: specifies the WakeUpPin. + * This parameter can be: PWR_WakeUpPin_1, PWR_WakeUpPin_2 or PWR_WakeUpPin_3. + * @param NewState: new state of the WakeUp Pin functionality. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_WakeUpPinCmd(uint32_t PWR_WakeUpPin, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_PWR_WAKEUP_PIN(PWR_WakeUpPin)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the EWUPx pin */ + PWR->CSR |= PWR_WakeUpPin; + } + else + { + /* Disable the EWUPx pin */ + PWR->CSR &= ~PWR_WakeUpPin; + } +} + +/** + * @} + */ + + +/** @defgroup PWR_Group4 Low Power modes configuration functions + * @brief Low Power modes configuration functions + * +@verbatim + =============================================================================== + ##### Low Power modes configuration functions ##### + ============================================================================== + + [..] The devices feature three low-power modes: + (+) Sleep mode: Cortex-M4 core stopped, peripherals kept running. + (+) Stop mode: all clocks are stopped, regulator running, regulator in low power mode + (+) Standby mode: VCORE domain powered off + + *** Sleep mode *** + ================== + [..] + (+) Entry: + (++) The Sleep mode is entered by executing the WFE() or WFI() instructions. + (+) Exit: + (++) Any peripheral interrupt acknowledged by the nested vectored interrupt + controller (NVIC) can wake up the device from Sleep mode. + + *** Stop mode *** + ================= + [..] In Stop mode, all clocks in the VCORE domain are stopped, the PLL, the HSI, + and the HSE RC oscillators are disabled. Internal SRAM and register + contents are preserved. + The voltage regulator can be configured either in normal or low-power mode. + + (+) Entry: + (++) The Stop mode is entered using the PWR_EnterSTOPMode(PWR_Regulator_LowPower,) + function with regulator in LowPower or with Regulator ON. + (+) Exit: + (++) Any EXTI Line (Internal or External) configured in Interrupt/Event mode + or any internal IPs (I2C or UASRT) wakeup event. + + *** Standby mode *** + ==================== + [..] The Standby mode allows to achieve the lowest power consumption. It is based + on the Cortex-M4 deepsleep mode, with the voltage regulator disabled. + The VCORE domain is consequently powered off. The PLL, the HSI, and the HSE + oscillator are also switched off. SRAM and register + contents are lost except for the Backup domain (RTC registers, RTC backup + registers and Standby circuitry). + + [..] The voltage regulator is OFF. + + (+) Entry: + (++) The Standby mode is entered using the PWR_EnterSTANDBYMode() function. + (+) Exit: + (++) WKUP pin rising edge, RTC alarm (Alarm A and Alarm B), RTC wakeup, + tamper event, time-stamp event, external reset in NRST pin, IWDG reset. + + *** Auto-wakeup (AWU) from low-power mode *** + ============================================= + [..] The MCU can be woken up from low-power mode by an RTC Alarm event, a tamper + event, a time-stamp event, or a comparator event, without depending on an + external interrupt (Auto-wakeup mode). + + (+) RTC auto-wakeup (AWU) from the Stop mode + (++) To wake up from the Stop mode with an RTC alarm event, it is necessary to: + (+++) Configure the EXTI Line 17 to be sensitive to rising edges (Interrupt + or Event modes) using the EXTI_Init() function. + (+++) Enable the RTC Alarm Interrupt using the RTC_ITConfig() function + (+++) Configure the RTC to generate the RTC alarm using the RTC_SetAlarm() + and RTC_AlarmCmd() functions. + (++) To wake up from the Stop mode with an RTC Tamper or time stamp event, it + is necessary to: + (+++) Configure the EXTI Line 19 to be sensitive to rising edges (Interrupt + or Event modes) using the EXTI_Init() function. + (+++) Enable the RTC Tamper or time stamp Interrupt using the RTC_ITConfig() + function. + (+++) Configure the RTC to detect the tamper or time stamp event using the + RTC_TimeStampConfig(), RTC_TamperTriggerConfig() and RTC_TamperCmd() + functions. + + (+) RTC auto-wakeup (AWU) from the Standby mode + (++) To wake up from the Standby mode with an RTC alarm event, it is necessary to: + (+++) Enable the RTC Alarm Interrupt using the RTC_ITConfig() function. + (+++) Configure the RTC to generate the RTC alarm using the RTC_SetAlarm() + and RTC_AlarmCmd() functions. + (++) To wake up from the Standby mode with an RTC Tamper or time stamp event, it + is necessary to: + (+++) Enable the RTC Tamper or time stamp Interrupt using the RTC_ITConfig() + function. + (+++) Configure the RTC to detect the tamper or time stamp event using the + RTC_TimeStampConfig(), RTC_TamperTriggerConfig() and RTC_TamperCmd() + functions. + + (+) Comparator auto-wakeup (AWU) from the Stop mode + (++) To wake up from the Stop mode with a comparator wakeup event, it is necessary to: + (+++) Configure the correspondant comparator EXTI Line to be sensitive to + the selected edges (falling, rising or falling and rising) + (Interrupt or Event modes) using the EXTI_Init() function. + (+++) Configure the comparator to generate the event. + +@endverbatim + * @{ + */ + +/** + * @brief Enters Sleep mode. + * @note In Sleep mode, all I/O pins keep the same state as in Run mode. + * @param PWR_SLEEPEntry: specifies if SLEEP mode in entered with WFI or WFE instruction. + * This parameter can be one of the following values: + * @arg PWR_SLEEPEntry_WFI: enter SLEEP mode with WFI instruction + * @arg PWR_SLEEPEntry_WFE: enter SLEEP mode with WFE instruction + * @retval None + */ +void PWR_EnterSleepMode(uint8_t PWR_SLEEPEntry) +{ + /* Check the parameters */ + assert_param(IS_PWR_SLEEP_ENTRY(PWR_SLEEPEntry)); + + /* Clear SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk); + + /* Select SLEEP mode entry -------------------------------------------------*/ + if(PWR_SLEEPEntry == PWR_SLEEPEntry_WFI) + { + /* Request Wait For Interrupt */ + __WFI(); + } + else + { + /* Request Wait For Event */ + __WFE(); + } +} + +/** + * @brief Enters STOP mode. + * @note In Stop mode, all I/O pins keep the same state as in Run mode. + * @note When exiting Stop mode by issuing an interrupt or a wakeup event, + * the HSI RC oscillator is selected as system clock. + * @note When the voltage regulator operates in low power mode, an additional + * startup delay is incurred when waking up from Stop mode. + * By keeping the internal regulator ON during Stop mode, the consumption + * is higher although the startup time is reduced. + * @param PWR_Regulator: specifies the regulator state in STOP mode. + * This parameter can be one of the following values: + * @arg PWR_Regulator_ON: STOP mode with regulator ON + * @arg PWR_Regulator_LowPower: STOP mode with regulator in low power mode + * @param PWR_STOPEntry: specifies if STOP mode in entered with WFI or WFE instruction. + * This parameter can be one of the following values: + * @arg PWR_STOPEntry_WFI: enter STOP mode with WFI instruction + * @arg PWR_STOPEntry_WFE: enter STOP mode with WFE instruction + * @retval None + */ +void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_PWR_REGULATOR(PWR_Regulator)); + assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry)); + + /* Select the regulator state in STOP mode ---------------------------------*/ + tmpreg = PWR->CR; + /* Clear PDDS and LPDSR bits */ + tmpreg &= CR_DS_MASK; + + /* Set LPDSR bit according to PWR_Regulator value */ + tmpreg |= PWR_Regulator; + + /* Store the new value */ + PWR->CR = tmpreg; + + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk; + + /* Select STOP mode entry --------------------------------------------------*/ + if(PWR_STOPEntry == PWR_STOPEntry_WFI) + { + /* Request Wait For Interrupt */ + __WFI(); + } + else + { + /* Request Wait For Event */ + __WFE(); + } + /* Reset SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk); +} + +/** + * @brief Enters STANDBY mode. + * @note In Standby mode, all I/O pins are high impedance except for: + * @note Reset pad (still available) + * @note RTC_AF1 pin (PC13) if configured for Wakeup pin 2 (WKUP2), tamper, + * time-stamp, RTC Alarm out, or RTC clock calibration out. + * @note WKUP pin 1 (PA0) and WKUP pin 3 (PE6), if enabled. + * @param None + * @retval None + */ +void PWR_EnterSTANDBYMode(void) +{ + /* Clear Wakeup flag */ + PWR->CR |= PWR_CR_CWUF; + + /* Select STANDBY mode */ + PWR->CR |= PWR_CR_PDDS; + + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk; + +/* This option is used to ensure that store operations are completed */ +#if defined ( __CC_ARM ) + __force_stores(); +#endif + /* Request Wait For Interrupt */ + __WFI(); +} + +/** + * @} + */ + +/** @defgroup PWR_Group5 Flags management functions + * @brief Flags management functions + * +@verbatim + =============================================================================== + ##### Flags management functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Checks whether the specified PWR flag is set or not. + * @param PWR_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg PWR_FLAG_WU: Wake Up flag. This flag indicates that a wakeup event + * was received from the WKUP pin or from the RTC alarm (Alarm A or Alarm B), + * RTC Tamper event, RTC TimeStamp event or RTC Wakeup. + * @arg PWR_FLAG_SB: StandBy flag. This flag indicates that the system was + * resumed from StandBy mode. + * @arg PWR_FLAG_PVDO: PVD Output. This flag is valid only if PVD is enabled + * by the PWR_PVDCmd() function. + * @arg PWR_FLAG_VREFINTRDY: Internal Voltage Reference Ready flag. This + * flag indicates the state of the internal voltage reference, VREFINT. + * @retval The new state of PWR_FLAG (SET or RESET). + */ +FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_PWR_GET_FLAG(PWR_FLAG)); + + if ((PWR->CSR & PWR_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @brief Clears the PWR's pending flags. + * @param PWR_FLAG: specifies the flag to clear. + * This parameter can be one of the following values: + * @arg PWR_FLAG_WU: Wake Up flag + * @arg PWR_FLAG_SB: StandBy flag + * @retval None + */ +void PWR_ClearFlag(uint32_t PWR_FLAG) +{ + /* Check the parameters */ + assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG)); + + PWR->CR |= PWR_FLAG << 2; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_rcc.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_rcc.c new file mode 100644 index 0000000..9880811 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_rcc.c @@ -0,0 +1,1951 @@ +/** + ****************************************************************************** + * @file stm32f30x_rcc.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the Reset and clock control (RCC) peripheral: + * + Internal/external clocks, PLL, CSS and MCO configuration + * + System, AHB and APB busses clocks configuration + * + Peripheral clocks configuration + * + Interrupts and flags management + * + @verbatim + + =============================================================================== + ##### RCC specific features ##### + =============================================================================== + [..] After reset the device is running from HSI (8 MHz) with Flash 0 WS, + all peripherals are off except internal SRAM, Flash and SWD. + (+) There is no prescaler on High speed (AHB) and Low speed (APB) busses; + all peripherals mapped on these busses are running at HSI speed. + (+) The clock for all peripherals is switched off, except the SRAM and FLASH. + (+) All GPIOs are in input floating state, except the SWD pins which + are assigned to be used for debug purpose. + [..] Once the device starts from reset, the user application has to: + (+) Configure the clock source to be used to drive the System clock + (if the application needs higher frequency/performance). + (+) Configure the System clock frequency and Flash settings. + (+) Configure the AHB and APB busses prescalers. + (+) Enable the clock for the peripheral(s) to be used. + (+) Configure the clock source(s) for peripherals which clocks are not + derived from the System clock (ADC, TIM, I2C, USART, RTC and IWDG). + + @endverbatim + + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_rcc.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup RCC + * @brief RCC driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* ------------ RCC registers bit address in the alias region ----------- */ +#define RCC_OFFSET (RCC_BASE - PERIPH_BASE) + +/* --- CR Register ---*/ + +/* Alias word address of HSION bit */ +#define CR_OFFSET (RCC_OFFSET + 0x00) +#define HSION_BitNumber 0x00 +#define CR_HSION_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4)) + +/* Alias word address of PLLON bit */ +#define PLLON_BitNumber 0x18 +#define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4)) + +/* Alias word address of CSSON bit */ +#define CSSON_BitNumber 0x13 +#define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4)) + +/* --- CFGR Register ---*/ +/* Alias word address of USBPRE bit */ +#define CFGR_OFFSET (RCC_OFFSET + 0x04) +#define USBPRE_BitNumber 0x16 +#define CFGR_USBPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (USBPRE_BitNumber * 4)) +/* Alias word address of I2SSRC bit */ +#define I2SSRC_BitNumber 0x17 +#define CFGR_I2SSRC_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (I2SSRC_BitNumber * 4)) + +/* --- BDCR Register ---*/ + +/* Alias word address of RTCEN bit */ +#define BDCR_OFFSET (RCC_OFFSET + 0x20) +#define RTCEN_BitNumber 0x0F +#define BDCR_RTCEN_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4)) + +/* Alias word address of BDRST bit */ +#define BDRST_BitNumber 0x10 +#define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4)) + +/* --- CSR Register ---*/ + +/* Alias word address of LSION bit */ +#define CSR_OFFSET (RCC_OFFSET + 0x24) +#define LSION_BitNumber 0x00 +#define CSR_LSION_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4)) + +/* ---------------------- RCC registers bit mask ------------------------ */ +/* RCC Flag Mask */ +#define FLAG_MASK ((uint8_t)0x1F) + +/* CFGR register byte 3 (Bits[31:23]) base address */ +#define CFGR_BYTE3_ADDRESS ((uint32_t)0x40021007) + +/* CIR register byte 2 (Bits[15:8]) base address */ +#define CIR_BYTE2_ADDRESS ((uint32_t)0x40021009) + +/* CIR register byte 3 (Bits[23:16]) base address */ +#define CIR_BYTE3_ADDRESS ((uint32_t)0x4002100A) + +/* CR register byte 2 (Bits[23:16]) base address */ +#define CR_BYTE2_ADDRESS ((uint32_t)0x40021002) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9}; +static __I uint16_t ADCPrescTable[16] = {1, 2, 4, 6, 8, 10, 12, 16, 32, 64, 128, 256, 0, 0, 0, 0 }; + +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup RCC_Private_Functions + * @{ + */ + +/** @defgroup RCC_Group1 Internal and external clocks, PLL, CSS and MCO configuration functions + * @brief Internal and external clocks, PLL, CSS and MCO configuration functions + * +@verbatim + =============================================================================== + ##### Internal-external clocks, PLL, CSS and MCO configuration functions ##### + =============================================================================== + [..] This section provides functions allowing to configure the internal/external + clocks, PLL, CSS and MCO. + (#) HSI (high-speed internal), 8 MHz factory-trimmed RC used directly + or through the PLL as System clock source. + The HSI clock can be used also to clock the USART and I2C peripherals. + (#) LSI (low-speed internal), 40 KHz low consumption RC used as IWDG and/or RTC + clock source. + (#) HSE (high-speed external), 4 to 32 MHz crystal oscillator used directly or + through the PLL as System clock source. Can be used also as RTC clock source. + (#) LSE (low-speed external), 32 KHz oscillator used as RTC clock source. + LSE can be used also to clock the USART peripherals. + (#) PLL (clocked by HSI or HSE), for System clock. + (#) CSS (Clock security system), once enabled and if a HSE clock failure occurs + (HSE used directly or through PLL as System clock source), the System clock + is automatically switched to HSI and an interrupt is generated if enabled. + The interrupt is linked to the Cortex-M4 NMI (Non-Maskable Interrupt) + exception vector. + (#) MCO (microcontroller clock output), used to output SYSCLK, HSI, HSE, LSI, LSE, + PLL clock on PA8 pin. + +@endverbatim + * @{ + */ + +/** + * @brief Resets the RCC clock configuration to the default reset state. + * @note The default reset state of the clock configuration is given below: + * @note HSI ON and used as system clock source + * @note HSE and PLL OFF + * @note AHB, APB1 and APB2 prescalers set to 1. + * @note CSS and MCO OFF + * @note All interrupts disabled + * @note However, this function doesn't modify the configuration of the + * @note Peripheral clocks + * @note LSI, LSE and RTC clocks + * @param None + * @retval None + */ +void RCC_DeInit(void) +{ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001; + + /* Reset SW[1:0], HPRE[3:0], PPRE[2:0] and MCOSEL[2:0] bits */ + RCC->CFGR &= (uint32_t)0xF8FFC000; + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + + /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */ + RCC->CFGR &= (uint32_t)0xFF80FFFF; + + /* Reset PREDIV1[3:0] and ADCPRE[13:4] bits */ + RCC->CFGR2 &= (uint32_t)0xFFFFC000; + + /* Reset USARTSW[1:0], I2CSW and TIMSW bits */ + RCC->CFGR3 &= (uint32_t)0xF00ECCC; + + /* Disable all interrupts */ + RCC->CIR = 0x00000000; +} + +/** + * @brief Configures the External High Speed oscillator (HSE). + * @note After enabling the HSE (RCC_HSE_ON or RCC_HSE_Bypass), the application + * software should wait on HSERDY flag to be set indicating that HSE clock + * is stable and can be used to clock the PLL and/or system clock. + * @note HSE state can not be changed if it is used directly or through the + * PLL as system clock. In this case, you have to select another source + * of the system clock then change the HSE state (ex. disable it). + * @note The HSE is stopped by hardware when entering STOP and STANDBY modes. + * @note This function resets the CSSON bit, so if the Clock security system(CSS) + * was previously enabled you have to enable it again after calling this + * function. + * @param RCC_HSE: specifies the new state of the HSE. + * This parameter can be one of the following values: + * @arg RCC_HSE_OFF: turn OFF the HSE oscillator, HSERDY flag goes low after + * 6 HSE oscillator clock cycles. + * @arg RCC_HSE_ON: turn ON the HSE oscillator + * @arg RCC_HSE_Bypass: HSE oscillator bypassed with external clock + * @retval None + */ +void RCC_HSEConfig(uint8_t RCC_HSE) +{ + /* Check the parameters */ + assert_param(IS_RCC_HSE(RCC_HSE)); + + /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/ + *(__IO uint8_t *) CR_BYTE2_ADDRESS = RCC_HSE_OFF; + + /* Set the new HSE configuration -------------------------------------------*/ + *(__IO uint8_t *) CR_BYTE2_ADDRESS = RCC_HSE; + +} + +/** + * @brief Waits for HSE start-up. + * @note This function waits on HSERDY flag to be set and return SUCCESS if + * this flag is set, otherwise returns ERROR if the timeout is reached + * and this flag is not set. The timeout value is defined by the constant + * HSE_STARTUP_TIMEOUT in stm32f30x.h file. You can tailor it depending + * on the HSE crystal used in your application. + * @param None + * @retval An ErrorStatus enumeration value: + * - SUCCESS: HSE oscillator is stable and ready to use + * - ERROR: HSE oscillator not yet ready + */ +ErrorStatus RCC_WaitForHSEStartUp(void) +{ + __IO uint32_t StartUpCounter = 0; + ErrorStatus status = ERROR; + FlagStatus HSEStatus = RESET; + + /* Wait till HSE is ready and if timeout is reached exit */ + do + { + HSEStatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY); + StartUpCounter++; + } while((StartUpCounter != HSE_STARTUP_TIMEOUT) && (HSEStatus == RESET)); + + if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET) + { + status = SUCCESS; + } + else + { + status = ERROR; + } + return (status); +} + +/** + * @brief Adjusts the Internal High Speed oscillator (HSI) calibration value. + * @note The calibration is used to compensate for the variations in voltage + * and temperature that influence the frequency of the internal HSI RC. + * Refer to the Application Note AN3300 for more details on how to + * calibrate the HSI. + * @param HSICalibrationValue: specifies the HSI calibration trimming value. + * This parameter must be a number between 0 and 0x1F. + * @retval None + */ +void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_HSI_CALIBRATION_VALUE(HSICalibrationValue)); + + tmpreg = RCC->CR; + + /* Clear HSITRIM[4:0] bits */ + tmpreg &= ~RCC_CR_HSITRIM; + + /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */ + tmpreg |= (uint32_t)HSICalibrationValue << 3; + + /* Store the new value */ + RCC->CR = tmpreg; +} + +/** + * @brief Enables or disables the Internal High Speed oscillator (HSI). + * @note After enabling the HSI, the application software should wait on + * HSIRDY flag to be set indicating that HSI clock is stable and can + * be used to clock the PLL and/or system clock. + * @note HSI can not be stopped if it is used directly or through the PLL + * as system clock. In this case, you have to select another source + * of the system clock then stop the HSI. + * @note The HSI is stopped by hardware when entering STOP and STANDBY modes. + * @note When the HSI is stopped, HSIRDY flag goes low after 6 HSI oscillator + * clock cycles. + * @param NewState: new state of the HSI. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_HSICmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CR_HSION_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the External Low Speed oscillator (LSE). + * @note As the LSE is in the Backup domain and write access is denied to this + * domain after reset, you have to enable write access using + * PWR_BackupAccessCmd(ENABLE) function before to configure the LSE + * (to be done once after reset). + * @note After enabling the LSE (RCC_LSE_ON or RCC_LSE_Bypass), the application + * software should wait on LSERDY flag to be set indicating that LSE clock + * is stable and can be used to clock the RTC. + * @param RCC_LSE: specifies the new state of the LSE. + * This parameter can be one of the following values: + * @arg RCC_LSE_OFF: turn OFF the LSE oscillator, LSERDY flag goes low after + * 6 LSE oscillator clock cycles. + * @arg RCC_LSE_ON: turn ON the LSE oscillator + * @arg RCC_LSE_Bypass: LSE oscillator bypassed with external clock + * @retval None + */ +void RCC_LSEConfig(uint32_t RCC_LSE) +{ + /* Check the parameters */ + assert_param(IS_RCC_LSE(RCC_LSE)); + + /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/ + /* Reset LSEON bit */ + RCC->BDCR &= ~(RCC_BDCR_LSEON); + + /* Reset LSEBYP bit */ + RCC->BDCR &= ~(RCC_BDCR_LSEBYP); + + /* Configure LSE */ + RCC->BDCR |= RCC_LSE; +} + +/** + * @brief Configures the External Low Speed oscillator (LSE) drive capability. + * @param RCC_LSEDrive: specifies the new state of the LSE drive capability. + * This parameter can be one of the following values: + * @arg RCC_LSEDrive_Low: LSE oscillator low drive capability. + * @arg RCC_LSEDrive_MediumLow: LSE oscillator medium low drive capability. + * @arg RCC_LSEDrive_MediumHigh: LSE oscillator medium high drive capability. + * @arg RCC_LSEDrive_High: LSE oscillator high drive capability. + * @retval None + */ +void RCC_LSEDriveConfig(uint32_t RCC_LSEDrive) +{ + /* Check the parameters */ + assert_param(IS_RCC_LSE_DRIVE(RCC_LSEDrive)); + + /* Clear LSEDRV[1:0] bits */ + RCC->BDCR &= ~(RCC_BDCR_LSEDRV); + + /* Set the LSE Drive */ + RCC->BDCR |= RCC_LSEDrive; +} + +/** + * @brief Enables or disables the Internal Low Speed oscillator (LSI). + * @note After enabling the LSI, the application software should wait on + * LSIRDY flag to be set indicating that LSI clock is stable and can + * be used to clock the IWDG and/or the RTC. + * @note LSI can not be disabled if the IWDG is running. + * @note When the LSI is stopped, LSIRDY flag goes low after 6 LSI oscillator + * clock cycles. + * @param NewState: new state of the LSI. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_LSICmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the PLL clock source and multiplication factor. + * @note This function must be used only when the PLL is disabled. + * @note The minimum input clock frequency for PLL is 2 MHz (when using HSE as + * PLL source). + * @param RCC_PLLSource: specifies the PLL entry clock source. + * This parameter can be one of the following values: + * @arg RCC_PLLSource_HSI_Div2: HSI oscillator clock divided by 2 selected as + * PLL clock entry + * @arg RCC_PLLSource_PREDIV1: PREDIV1 clock selected as PLL clock source + * @param RCC_PLLMul: specifies the PLL multiplication factor, which drive the PLLVCO clock + * This parameter can be RCC_PLLMul_x where x:[2,16] + * + * @retval None + */ +void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul) +{ + /* Check the parameters */ + assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource)); + assert_param(IS_RCC_PLL_MUL(RCC_PLLMul)); + + /* Clear PLL Source [16] and Multiplier [21:18] bits */ + RCC->CFGR &= ~(RCC_CFGR_PLLMULL | RCC_CFGR_PLLSRC); + + /* Set the PLL Source and Multiplier */ + RCC->CFGR |= (uint32_t)(RCC_PLLSource | RCC_PLLMul); +} + +/** + * @brief Enables or disables the PLL. + * @note After enabling the PLL, the application software should wait on + * PLLRDY flag to be set indicating that PLL clock is stable and can + * be used as system clock source. + * @note The PLL can not be disabled if it is used as system clock source + * @note The PLL is disabled by hardware when entering STOP and STANDBY modes. + * @param NewState: new state of the PLL. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_PLLCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CR_PLLON_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the PREDIV1 division factor. + * @note This function must be used only when the PLL is disabled. + * @param RCC_PREDIV1_Div: specifies the PREDIV1 clock division factor. + * This parameter can be RCC_PREDIV1_Divx where x:[1,16] + * @retval None + */ +void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Div) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PREDIV1(RCC_PREDIV1_Div)); + + tmpreg = RCC->CFGR2; + /* Clear PREDIV1[3:0] bits */ + tmpreg &= ~(RCC_CFGR2_PREDIV1); + + /* Set the PREDIV1 division factor */ + tmpreg |= RCC_PREDIV1_Div; + + /* Store the new value */ + RCC->CFGR2 = tmpreg; +} + +/** + * @brief Enables or disables the Clock Security System. + * @note If a failure is detected on the HSE oscillator clock, this oscillator + * is automatically disabled and an interrupt is generated to inform the + * software about the failure (Clock Security System Interrupt, CSSI), + * allowing the MCU to perform rescue operations. The CSSI is linked to + * the Cortex-M4 NMI (Non-Maskable Interrupt) exception vector. + * @param NewState: new state of the Clock Security System. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_ClockSecuritySystemCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CR_CSSON_BB = (uint32_t)NewState; +} + +#ifdef STM32F303xC +/** + * @brief Selects the clock source to output on MCO pin (PA8). + * @note PA8 should be configured in alternate function mode. + * @param RCC_MCOSource: specifies the clock source to output. + * This parameter can be one of the following values: + * @arg RCC_MCOSource_NoClock: No clock selected. + * @arg RCC_MCOSource_HSI14: HSI14 oscillator clock selected. + * @arg RCC_MCOSource_LSI: LSI oscillator clock selected. + * @arg RCC_MCOSource_LSE: LSE oscillator clock selected. + * @arg RCC_MCOSource_SYSCLK: System clock selected. + * @arg RCC_MCOSource_HSI: HSI oscillator clock selected. + * @arg RCC_MCOSource_HSE: HSE oscillator clock selected. + * @arg RCC_MCOSource_PLLCLK_Div2: PLL clock divided by 2 selected. + * @arg RCC_MCOSource_PLLCLK: PLL clock selected. + * @arg RCC_MCOSource_HSI48: HSI48 clock selected. + * @retval None + */ +void RCC_MCOConfig(uint8_t RCC_MCOSource) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_MCO_SOURCE(RCC_MCOSource)); + + /* Get CFGR value */ + tmpreg = RCC->CFGR; + /* Clear MCO[3:0] bits */ + tmpreg &= ~(RCC_CFGR_MCO | RCC_CFGR_PLLNODIV); + /* Set the RCC_MCOSource */ + tmpreg |= RCC_MCOSource<<24; + /* Store the new value */ + RCC->CFGR = tmpreg; +} +#else + +/** + * @brief Selects the clock source to output on MCO pin (PA8) and the corresponding + * prescsaler. + * @note PA8 should be configured in alternate function mode. + * @param RCC_MCOSource: specifies the clock source to output. + * This parameter can be one of the following values: + * @arg RCC_MCOSource_NoClock: No clock selected. + * @arg RCC_MCOSource_HSI14: HSI14 oscillator clock selected. + * @arg RCC_MCOSource_LSI: LSI oscillator clock selected. + * @arg RCC_MCOSource_LSE: LSE oscillator clock selected. + * @arg RCC_MCOSource_SYSCLK: System clock selected. + * @arg RCC_MCOSource_HSI: HSI oscillator clock selected. + * @arg RCC_MCOSource_HSE: HSE oscillator clock selected. + * @arg RCC_MCOSource_PLLCLK_Div2: PLL clock divided by 2 selected. + * @arg RCC_MCOSource_PLLCLK: PLL clock selected. + * @arg RCC_MCOSource_HSI48: HSI48 clock selected. + * @param RCC_MCOPrescaler: specifies the prescaler on MCO pin. + * This parameter can be one of the following values: + * @arg RCC_MCOPrescaler_1: MCO clock is divided by 1. + * @arg RCC_MCOPrescaler_2: MCO clock is divided by 2. + * @arg RCC_MCOPrescaler_4: MCO clock is divided by 4. + * @arg RCC_MCOPrescaler_8: MCO clock is divided by 8. + * @arg RCC_MCOPrescaler_16: MCO clock is divided by 16. + * @arg RCC_MCOPrescaler_32: MCO clock is divided by 32. + * @arg RCC_MCOPrescaler_64: MCO clock is divided by 64. + * @arg RCC_MCOPrescaler_128: MCO clock is divided by 128. + * @retval None + */ +void RCC_MCOConfig(uint8_t RCC_MCOSource, uint32_t RCC_MCOPrescaler) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_MCO_SOURCE(RCC_MCOSource)); + assert_param(IS_RCC_MCO_PRESCALER(RCC_MCOPrescaler)); + + /* Get CFGR value */ + tmpreg = RCC->CFGR; + /* Clear MCOPRE[2:0] bits */ + tmpreg &= ~(RCC_CFGR_MCO_PRE | RCC_CFGR_MCO | RCC_CFGR_PLLNODIV); + /* Set the RCC_MCOSource and RCC_MCOPrescaler */ + tmpreg |= (RCC_MCOPrescaler | RCC_MCOSource<<24); + /* Store the new value */ + RCC->CFGR = tmpreg; +} +#endif /* STM32F303xC */ + +/** + * @} + */ + +/** @defgroup RCC_Group2 System AHB, APB1 and APB2 busses clocks configuration functions + * @brief System, AHB and APB busses clocks configuration functions + * +@verbatim + =============================================================================== + ##### System, AHB, APB1 and APB2 busses clocks configuration functions ##### + =============================================================================== + [..] This section provide functions allowing to configure the System, AHB, APB1 and + APB2 busses clocks. + (#) Several clock sources can be used to drive the System clock (SYSCLK): HSI, + HSE and PLL. + The AHB clock (HCLK) is derived from System clock through configurable prescaler + and used to clock the CPU, memory and peripherals mapped on AHB bus (DMA and GPIO). + APB1 (PCLK1) and APB2 (PCLK2) clocks are derived from AHB clock through + configurable prescalers and used to clock the peripherals mapped on these busses. + You can use "RCC_GetClocksFreq()" function to retrieve the frequencies of these clocks. + + (#) The maximum frequency of the SYSCLK, HCLK, PCLK1 and PCLK2 is 72 MHz. + Depending on the maximum frequency, the FLASH wait states (WS) should be + adapted accordingly: + +---------------------------------+ + | Wait states | HCLK clock | + | (Latency) | frequency (MHz) | + |-------------- |-----------------| + |0WS(1CPU cycle)| 0 < HCLK <= 24 | + |---------------|-----------------| + |1WS(2CPU cycle)|24 < HCLK <=48 | + |---------------|-----------------| + |2WS(3CPU cycle)|48 < HCLK <= 72 | + +---------------------------------+ + + (#) After reset, the System clock source is the HSI (8 MHz) with 0 WS and + prefetch is disabled. + [..] + (@) All the peripheral clocks are derived from the System clock (SYSCLK) + except: + (+@) The FLASH program/erase clock which is always HSI 8MHz clock. + (+@) The USB 48 MHz clock which is derived from the PLL VCO clock. + (+@) The USART clock which can be derived as well from HSI 8MHz, LSI or LSE. + (+@) The I2C clock which can be derived as well from HSI 8MHz clock. + (+@) The ADC clock which is derived from PLL output. + (+@) The RTC clock which is derived from the LSE, LSI or 1 MHz HSE_RTC + (HSE divided by a programmable prescaler). The System clock (SYSCLK) + frequency must be higher or equal to the RTC clock frequency. + (+@) IWDG clock which is always the LSI clock. + [..] It is recommended to use the following software sequences to tune the number + of wait states needed to access the Flash memory with the CPU frequency (HCLK). + (+) Increasing the CPU frequency + (++) Program the Flash Prefetch buffer, using "FLASH_PrefetchBufferCmd(ENABLE)" + function + (++) Check that Flash Prefetch buffer activation is taken into account by + reading FLASH_ACR using the FLASH_GetPrefetchBufferStatus() function + (++) Program Flash WS to 1 or 2, using "FLASH_SetLatency()" function + (++) Check that the new number of WS is taken into account by reading FLASH_ACR + (++) Modify the CPU clock source, using "RCC_SYSCLKConfig()" function + (++) If needed, modify the CPU clock prescaler by using "RCC_HCLKConfig()" function + (++) Check that the new CPU clock source is taken into account by reading + the clock source status, using "RCC_GetSYSCLKSource()" function + (+) Decreasing the CPU frequency + (++) Modify the CPU clock source, using "RCC_SYSCLKConfig()" function + (++) If needed, modify the CPU clock prescaler by using "RCC_HCLKConfig()" function + (++) Check that the new CPU clock source is taken into account by reading + the clock source status, using "RCC_GetSYSCLKSource()" function + (++) Program the new number of WS, using "FLASH_SetLatency()" function + (++) Check that the new number of WS is taken into account by reading FLASH_ACR + (++) Disable the Flash Prefetch buffer using "FLASH_PrefetchBufferCmd(DISABLE)" + function + (++) Check that Flash Prefetch buffer deactivation is taken into account by reading FLASH_ACR + using the FLASH_GetPrefetchBufferStatus() function. + +@endverbatim + * @{ + */ + +/** + * @brief Configures the system clock (SYSCLK). + * @note The HSI is used (enabled by hardware) as system clock source after + * startup from Reset, wake-up from STOP and STANDBY mode, or in case + * of failure of the HSE used directly or indirectly as system clock + * (if the Clock Security System CSS is enabled). + * @note A switch from one clock source to another occurs only if the target + * clock source is ready (clock stable after startup delay or PLL locked). + * If a clock source which is not yet ready is selected, the switch will + * occur when the clock source will be ready. + * You can use RCC_GetSYSCLKSource() function to know which clock is + * currently used as system clock source. + * @param RCC_SYSCLKSource: specifies the clock source used as system clock source + * This parameter can be one of the following values: + * @arg RCC_SYSCLKSource_HSI: HSI selected as system clock source + * @arg RCC_SYSCLKSource_HSE: HSE selected as system clock source + * @arg RCC_SYSCLKSource_PLLCLK: PLL selected as system clock source + * @retval None + */ +void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource)); + + tmpreg = RCC->CFGR; + + /* Clear SW[1:0] bits */ + tmpreg &= ~RCC_CFGR_SW; + + /* Set SW[1:0] bits according to RCC_SYSCLKSource value */ + tmpreg |= RCC_SYSCLKSource; + + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Returns the clock source used as system clock. + * @param None + * @retval The clock source used as system clock. The returned value can be one + * of the following values: + * - 0x00: HSI used as system clock + * - 0x04: HSE used as system clock + * - 0x08: PLL used as system clock + */ +uint8_t RCC_GetSYSCLKSource(void) +{ + return ((uint8_t)(RCC->CFGR & RCC_CFGR_SWS)); +} + +/** + * @brief Configures the AHB clock (HCLK). + * @note Depending on the device voltage range, the software has to set correctly + * these bits to ensure that the system frequency does not exceed the + * maximum allowed frequency (for more details refer to section above + * "CPU, AHB and APB busses clocks configuration functions"). + * @param RCC_SYSCLK: defines the AHB clock divider. This clock is derived from + * the system clock (SYSCLK). + * This parameter can be one of the following values: + * @arg RCC_SYSCLK_Div1: AHB clock = SYSCLK + * @arg RCC_SYSCLK_Div2: AHB clock = SYSCLK/2 + * @arg RCC_SYSCLK_Div4: AHB clock = SYSCLK/4 + * @arg RCC_SYSCLK_Div8: AHB clock = SYSCLK/8 + * @arg RCC_SYSCLK_Div16: AHB clock = SYSCLK/16 + * @arg RCC_SYSCLK_Div64: AHB clock = SYSCLK/64 + * @arg RCC_SYSCLK_Div128: AHB clock = SYSCLK/128 + * @arg RCC_SYSCLK_Div256: AHB clock = SYSCLK/256 + * @arg RCC_SYSCLK_Div512: AHB clock = SYSCLK/512 + * @retval None + */ +void RCC_HCLKConfig(uint32_t RCC_SYSCLK) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_HCLK(RCC_SYSCLK)); + + tmpreg = RCC->CFGR; + + /* Clear HPRE[3:0] bits */ + tmpreg &= ~RCC_CFGR_HPRE; + + /* Set HPRE[3:0] bits according to RCC_SYSCLK value */ + tmpreg |= RCC_SYSCLK; + + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Configures the Low Speed APB clock (PCLK1). + * @param RCC_HCLK: defines the APB1 clock divider. This clock is derived from + * the AHB clock (HCLK). + * This parameter can be one of the following values: + * @arg RCC_HCLK_Div1: APB1 clock = HCLK + * @arg RCC_HCLK_Div2: APB1 clock = HCLK/2 + * @arg RCC_HCLK_Div4: APB1 clock = HCLK/4 + * @arg RCC_HCLK_Div8: APB1 clock = HCLK/8 + * @arg RCC_HCLK_Div16: APB1 clock = HCLK/16 + * @retval None + */ +void RCC_PCLK1Config(uint32_t RCC_HCLK) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PCLK(RCC_HCLK)); + + tmpreg = RCC->CFGR; + /* Clear PPRE1[2:0] bits */ + tmpreg &= ~RCC_CFGR_PPRE1; + + /* Set PPRE1[2:0] bits according to RCC_HCLK value */ + tmpreg |= RCC_HCLK; + + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Configures the High Speed APB clock (PCLK2). + * @param RCC_HCLK: defines the APB2 clock divider. This clock is derived from + * the AHB clock (HCLK). + * This parameter can be one of the following values: + * @arg RCC_HCLK_Div1: APB2 clock = HCLK + * @arg RCC_HCLK_Div2: APB2 clock = HCLK/2 + * @arg RCC_HCLK_Div4: APB2 clock = HCLK/4 + * @arg RCC_HCLK_Div8: APB2 clock = HCLK/8 + * @arg RCC_HCLK_Div16: APB2 clock = HCLK/16 + * @retval None + */ +void RCC_PCLK2Config(uint32_t RCC_HCLK) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PCLK(RCC_HCLK)); + + tmpreg = RCC->CFGR; + /* Clear PPRE2[2:0] bits */ + tmpreg &= ~RCC_CFGR_PPRE2; + /* Set PPRE2[2:0] bits according to RCC_HCLK value */ + tmpreg |= RCC_HCLK << 3; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Returns the frequencies of the System, AHB, APB2 and APB1 busses clocks. + * + * @note This function returns the frequencies of : + * System, AHB, APB2 and APB1 busses clocks, ADC1/2/3/4 clocks, + * USART1/2/3/4/5 clocks, I2C1/2 clocks and TIM1/8 Clocks. + * + * @note The frequency returned by this function is not the real frequency + * in the chip. It is calculated based on the predefined constant and + * the source selected by RCC_SYSCLKConfig(). + * + * @note If SYSCLK source is HSI, function returns constant HSI_VALUE(*) + * + * @note If SYSCLK source is HSE, function returns constant HSE_VALUE(**) + * + * @note If SYSCLK source is PLL, function returns constant HSE_VALUE(**) + * or HSI_VALUE(*) multiplied by the PLL factors. + * + * @note (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value + * 8 MHz) but the real value may vary depending on the variations + * in voltage and temperature, refer to RCC_AdjustHSICalibrationValue(). + * + * @note (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value + * 8 MHz), user has to ensure that HSE_VALUE is same as the real + * frequency of the crystal used. Otherwise, this function may + * return wrong result. + * + * @note The result of this function could be not correct when using fractional + * value for HSE crystal. + * + * @param RCC_Clocks: pointer to a RCC_ClocksTypeDef structure which will hold + * the clocks frequencies. + * + * @note This function can be used by the user application to compute the + * baudrate for the communication peripherals or configure other parameters. + * @note Each time SYSCLK, HCLK, PCLK1 and/or PCLK2 clock changes, this function + * must be called to update the structure's field. Otherwise, any + * configuration based on this function will be incorrect. + * + * @retval None + */ +void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) +{ + uint32_t tmp = 0, pllmull = 0, pllsource = 0, prediv1factor = 0, presc = 0, pllclk = 0; + uint32_t apb2presc = 0, ahbpresc = 0; + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & RCC_CFGR_SWS; + + switch (tmp) + { + case 0x00: /* HSI used as system clock */ + RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; + break; + case 0x04: /* HSE used as system clock */ + RCC_Clocks->SYSCLK_Frequency = HSE_VALUE; + break; + case 0x08: /* PLL used as system clock */ + /* Get PLL clock source and multiplication factor ----------------------*/ + pllmull = RCC->CFGR & RCC_CFGR_PLLMULL; + pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; + pllmull = ( pllmull >> 18) + 2; + + if (pllsource == 0x00) + { + /* HSI oscillator clock divided by 2 selected as PLL clock entry */ + pllclk = (HSI_VALUE >> 1) * pllmull; + } + else + { + prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1; + /* HSE oscillator clock selected as PREDIV1 clock entry */ + pllclk = (HSE_VALUE / prediv1factor) * pllmull; + } + RCC_Clocks->SYSCLK_Frequency = pllclk; + break; + default: /* HSI used as system clock */ + RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; + break; + } + /* Compute HCLK, PCLK clocks frequencies -----------------------------------*/ + /* Get HCLK prescaler */ + tmp = RCC->CFGR & RCC_CFGR_HPRE; + tmp = tmp >> 4; + ahbpresc = APBAHBPrescTable[tmp]; + /* HCLK clock frequency */ + RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> ahbpresc; + + /* Get PCLK1 prescaler */ + tmp = RCC->CFGR & RCC_CFGR_PPRE1; + tmp = tmp >> 8; + presc = APBAHBPrescTable[tmp]; + /* PCLK1 clock frequency */ + RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc; + + /* Get PCLK2 prescaler */ + tmp = RCC->CFGR & RCC_CFGR_PPRE2; + tmp = tmp >> 11; + apb2presc = APBAHBPrescTable[tmp]; + /* PCLK2 clock frequency */ + RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> apb2presc; + + /* Get ADC12CLK prescaler */ + tmp = RCC->CFGR2 & RCC_CFGR2_ADCPRE12; + tmp = tmp >> 4; + presc = ADCPrescTable[tmp & 0x0F]; + if (((tmp & 0x10) != 0) && (presc != 0)) + { + /* ADC12CLK clock frequency is derived from PLL clock */ + RCC_Clocks->ADC12CLK_Frequency = pllclk / presc; + } + else + { + /* ADC12CLK clock frequency is AHB clock */ + RCC_Clocks->ADC12CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; + } + + /* Get ADC34CLK prescaler */ + tmp = RCC->CFGR2 & RCC_CFGR2_ADCPRE34; + tmp = tmp >> 9; + presc = ADCPrescTable[tmp & 0x0F]; + if (((tmp & 0x10) != 0) && (presc != 0)) + { + /* ADC34CLK clock frequency is derived from PLL clock */ + RCC_Clocks->ADC34CLK_Frequency = pllclk / presc; + } + else + { + /* ADC34CLK clock frequency is AHB clock */ + RCC_Clocks->ADC34CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; + } + + /* I2C1CLK clock frequency */ + if((RCC->CFGR3 & RCC_CFGR3_I2C1SW) != RCC_CFGR3_I2C1SW) + { + /* I2C1 Clock is HSI Osc. */ + RCC_Clocks->I2C1CLK_Frequency = HSI_VALUE; + } + else + { + /* I2C1 Clock is System Clock */ + RCC_Clocks->I2C1CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; + } + + /* I2C2CLK clock frequency */ + if((RCC->CFGR3 & RCC_CFGR3_I2C2SW) != RCC_CFGR3_I2C2SW) + { + /* I2C2 Clock is HSI Osc. */ + RCC_Clocks->I2C2CLK_Frequency = HSI_VALUE; + } + else + { + /* I2C2 Clock is System Clock */ + RCC_Clocks->I2C2CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; + } + + /* I2C3CLK clock frequency */ + if((RCC->CFGR3 & RCC_CFGR3_I2C3SW) != RCC_CFGR3_I2C3SW) + { + /* I2C3 Clock is HSI Osc. */ + RCC_Clocks->I2C3CLK_Frequency = HSI_VALUE; + } + else + { + /* I2C3 Clock is System Clock */ + RCC_Clocks->I2C3CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; + } + + /* TIM1CLK clock frequency */ + if(((RCC->CFGR3 & RCC_CFGR3_TIM1SW) == RCC_CFGR3_TIM1SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \ + && (apb2presc == ahbpresc)) + { + /* TIM1 Clock is 2 * pllclk */ + RCC_Clocks->TIM1CLK_Frequency = pllclk * 2; + } + else + { + /* TIM1 Clock is APB2 clock. */ + RCC_Clocks->TIM1CLK_Frequency = RCC_Clocks->PCLK2_Frequency; + } + + /* TIM1CLK clock frequency */ + if(((RCC->CFGR3 & RCC_CFGR3_HRTIM1SW) == RCC_CFGR3_HRTIM1SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \ + && (apb2presc == ahbpresc)) + { + /* HRTIM1 Clock is 2 * pllclk */ + RCC_Clocks->HRTIM1CLK_Frequency = pllclk * 2; + } + else + { + /* HRTIM1 Clock is APB2 clock. */ + RCC_Clocks->HRTIM1CLK_Frequency = RCC_Clocks->PCLK2_Frequency; + } + + /* TIM8CLK clock frequency */ + if(((RCC->CFGR3 & RCC_CFGR3_TIM8SW) == RCC_CFGR3_TIM8SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \ + && (apb2presc == ahbpresc)) + { + /* TIM8 Clock is 2 * pllclk */ + RCC_Clocks->TIM8CLK_Frequency = pllclk * 2; + } + else + { + /* TIM8 Clock is APB2 clock. */ + RCC_Clocks->TIM8CLK_Frequency = RCC_Clocks->PCLK2_Frequency; + } + + /* TIM15CLK clock frequency */ + if(((RCC->CFGR3 & RCC_CFGR3_TIM15SW) == RCC_CFGR3_TIM15SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \ + && (apb2presc == ahbpresc)) + { + /* TIM15 Clock is 2 * pllclk */ + RCC_Clocks->TIM15CLK_Frequency = pllclk * 2; + } + else + { + /* TIM15 Clock is APB2 clock. */ + RCC_Clocks->TIM15CLK_Frequency = RCC_Clocks->PCLK2_Frequency; + } + + /* TIM16CLK clock frequency */ + if(((RCC->CFGR3 & RCC_CFGR3_TIM16SW) == RCC_CFGR3_TIM16SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \ + && (apb2presc == ahbpresc)) + { + /* TIM16 Clock is 2 * pllclk */ + RCC_Clocks->TIM16CLK_Frequency = pllclk * 2; + } + else + { + /* TIM16 Clock is APB2 clock. */ + RCC_Clocks->TIM16CLK_Frequency = RCC_Clocks->PCLK2_Frequency; + } + + /* TIM17CLK clock frequency */ + if(((RCC->CFGR3 & RCC_CFGR3_TIM17SW) == RCC_CFGR3_TIM17SW)&& (RCC_Clocks->SYSCLK_Frequency == pllclk) \ + && (apb2presc == ahbpresc)) + { + /* TIM17 Clock is 2 * pllclk */ + RCC_Clocks->TIM17CLK_Frequency = pllclk * 2; + } + else + { + /* TIM17 Clock is APB2 clock. */ + RCC_Clocks->TIM16CLK_Frequency = RCC_Clocks->PCLK2_Frequency; + } + + /* USART1CLK clock frequency */ + if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == 0x0) + { +#if defined(STM32F303x8) || defined(STM32F334x8) || defined(STM32F301x8) || defined(STM32F302x8) + /* USART1 Clock is PCLK1 instead of PCLK2 (limitation described in the + STM32F302/01/34 x4/x6/x8 respective erratasheets) */ + RCC_Clocks->USART1CLK_Frequency = RCC_Clocks->PCLK1_Frequency; +#else + /* USART Clock is PCLK2 */ + RCC_Clocks->USART1CLK_Frequency = RCC_Clocks->PCLK2_Frequency; +#endif + } + else if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == RCC_CFGR3_USART1SW_0) + { + /* USART Clock is System Clock */ + RCC_Clocks->USART1CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; + } + else if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == RCC_CFGR3_USART1SW_1) + { + /* USART Clock is LSE Osc. */ + RCC_Clocks->USART1CLK_Frequency = LSE_VALUE; + } + else if((RCC->CFGR3 & RCC_CFGR3_USART1SW) == RCC_CFGR3_USART1SW) + { + /* USART Clock is HSI Osc. */ + RCC_Clocks->USART1CLK_Frequency = HSI_VALUE; + } + + /* USART2CLK clock frequency */ + if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == 0x0) + { + /* USART Clock is PCLK */ + RCC_Clocks->USART2CLK_Frequency = RCC_Clocks->PCLK1_Frequency; + } + else if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == RCC_CFGR3_USART2SW_0) + { + /* USART Clock is System Clock */ + RCC_Clocks->USART2CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; + } + else if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == RCC_CFGR3_USART2SW_1) + { + /* USART Clock is LSE Osc. */ + RCC_Clocks->USART2CLK_Frequency = LSE_VALUE; + } + else if((RCC->CFGR3 & RCC_CFGR3_USART2SW) == RCC_CFGR3_USART2SW) + { + /* USART Clock is HSI Osc. */ + RCC_Clocks->USART2CLK_Frequency = HSI_VALUE; + } + + /* USART3CLK clock frequency */ + if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == 0x0) + { + /* USART Clock is PCLK */ + RCC_Clocks->USART3CLK_Frequency = RCC_Clocks->PCLK1_Frequency; + } + else if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == RCC_CFGR3_USART3SW_0) + { + /* USART Clock is System Clock */ + RCC_Clocks->USART3CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; + } + else if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == RCC_CFGR3_USART3SW_1) + { + /* USART Clock is LSE Osc. */ + RCC_Clocks->USART3CLK_Frequency = LSE_VALUE; + } + else if((RCC->CFGR3 & RCC_CFGR3_USART3SW) == RCC_CFGR3_USART3SW) + { + /* USART Clock is HSI Osc. */ + RCC_Clocks->USART3CLK_Frequency = HSI_VALUE; + } + + /* UART4CLK clock frequency */ + if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == 0x0) + { + /* USART Clock is PCLK */ + RCC_Clocks->UART4CLK_Frequency = RCC_Clocks->PCLK1_Frequency; + } + else if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == RCC_CFGR3_UART4SW_0) + { + /* USART Clock is System Clock */ + RCC_Clocks->UART4CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; + } + else if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == RCC_CFGR3_UART4SW_1) + { + /* USART Clock is LSE Osc. */ + RCC_Clocks->UART4CLK_Frequency = LSE_VALUE; + } + else if((RCC->CFGR3 & RCC_CFGR3_UART4SW) == RCC_CFGR3_UART4SW) + { + /* USART Clock is HSI Osc. */ + RCC_Clocks->UART4CLK_Frequency = HSI_VALUE; + } + + /* UART5CLK clock frequency */ + if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == 0x0) + { + /* USART Clock is PCLK */ + RCC_Clocks->UART5CLK_Frequency = RCC_Clocks->PCLK1_Frequency; + } + else if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == RCC_CFGR3_UART5SW_0) + { + /* USART Clock is System Clock */ + RCC_Clocks->UART5CLK_Frequency = RCC_Clocks->SYSCLK_Frequency; + } + else if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == RCC_CFGR3_UART5SW_1) + { + /* USART Clock is LSE Osc. */ + RCC_Clocks->UART5CLK_Frequency = LSE_VALUE; + } + else if((RCC->CFGR3 & RCC_CFGR3_UART5SW) == RCC_CFGR3_UART5SW) + { + /* USART Clock is HSI Osc. */ + RCC_Clocks->UART5CLK_Frequency = HSI_VALUE; + } +} + +/** + * @} + */ + +/** @defgroup RCC_Group3 Peripheral clocks configuration functions + * @brief Peripheral clocks configuration functions + * +@verbatim + =============================================================================== + ##### Peripheral clocks configuration functions ##### + =============================================================================== + [..] This section provide functions allowing to configure the Peripheral clocks. + (#) The RTC clock which is derived from the LSE, LSI or HSE_Div32 + (HSE divided by 32). + (#) After restart from Reset or wakeup from STANDBY, all peripherals are + off except internal SRAM, Flash and SWD. Before to start using + a peripheral you have to enable its interface clock. You can do this + using RCC_AHBPeriphClockCmd(), RCC_APB2PeriphClockCmd() + and RCC_APB1PeriphClockCmd() functions. + (#) To reset the peripherals configuration (to the default state after + device reset) you can use RCC_AHBPeriphResetCmd(), RCC_APB2PeriphResetCmd() + and RCC_APB1PeriphResetCmd() functions. +@endverbatim + * @{ + */ + +/** + * @brief Configures the ADC clock (ADCCLK). + * @param RCC_PLLCLK: defines the ADC clock divider. This clock is derived from + * the PLL Clock. + * This parameter can be one of the following values: + * @arg RCC_ADC12PLLCLK_OFF: ADC12 clock disabled + * @arg RCC_ADC12PLLCLK_Div1: ADC12 clock = PLLCLK/1 + * @arg RCC_ADC12PLLCLK_Div2: ADC12 clock = PLLCLK/2 + * @arg RCC_ADC12PLLCLK_Div4: ADC12 clock = PLLCLK/4 + * @arg RCC_ADC12PLLCLK_Div6: ADC12 clock = PLLCLK/6 + * @arg RCC_ADC12PLLCLK_Div8: ADC12 clock = PLLCLK/8 + * @arg RCC_ADC12PLLCLK_Div10: ADC12 clock = PLLCLK/10 + * @arg RCC_ADC12PLLCLK_Div12: ADC12 clock = PLLCLK/12 + * @arg RCC_ADC12PLLCLK_Div16: ADC12 clock = PLLCLK/16 + * @arg RCC_ADC12PLLCLK_Div32: ADC12 clock = PLLCLK/32 + * @arg RCC_ADC12PLLCLK_Div64: ADC12 clock = PLLCLK/64 + * @arg RCC_ADC12PLLCLK_Div128: ADC12 clock = PLLCLK/128 + * @arg RCC_ADC12PLLCLK_Div256: ADC12 clock = PLLCLK/256 + * @arg RCC_ADC34PLLCLK_OFF: ADC34 clock disabled + * @arg RCC_ADC34PLLCLK_Div1: ADC34 clock = PLLCLK/1 + * @arg RCC_ADC34PLLCLK_Div2: ADC34 clock = PLLCLK/2 + * @arg RCC_ADC34PLLCLK_Div4: ADC34 clock = PLLCLK/4 + * @arg RCC_ADC34PLLCLK_Div6: ADC34 clock = PLLCLK/6 + * @arg RCC_ADC34PLLCLK_Div8: ADC34 clock = PLLCLK/8 + * @arg RCC_ADC34PLLCLK_Div10: ADC34 clock = PLLCLK/10 + * @arg RCC_ADC34PLLCLK_Div12: ADC34 clock = PLLCLK/12 + * @arg RCC_ADC34PLLCLK_Div16: ADC34 clock = PLLCLK/16 + * @arg RCC_ADC34PLLCLK_Div32: ADC34 clock = PLLCLK/32 + * @arg RCC_ADC34PLLCLK_Div64: ADC34 clock = PLLCLK/64 + * @arg RCC_ADC34PLLCLK_Div128: ADC34 clock = PLLCLK/128 + * @arg RCC_ADC34PLLCLK_Div256: ADC34 clock = PLLCLK/256 + * @retval None + */ +void RCC_ADCCLKConfig(uint32_t RCC_PLLCLK) +{ + uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_RCC_ADCCLK(RCC_PLLCLK)); + + tmp = (RCC_PLLCLK >> 28); + + /* Clears ADCPRE34 bits */ + if (tmp != 0) + { + RCC->CFGR2 &= ~RCC_CFGR2_ADCPRE34; + } + /* Clears ADCPRE12 bits */ + else + { + RCC->CFGR2 &= ~RCC_CFGR2_ADCPRE12; + } + /* Set ADCPRE bits according to RCC_PLLCLK value */ + RCC->CFGR2 |= RCC_PLLCLK; +} + +/** + * @brief Configures the I2C clock (I2CCLK). + * @param RCC_I2CCLK: defines the I2C clock source. This clock is derived + * from the HSI or System clock. + * This parameter can be one of the following values: + * @arg RCC_I2CxCLK_HSI: I2Cx clock = HSI + * @arg RCC_I2CxCLK_SYSCLK: I2Cx clock = System Clock + * (x can be 1 or 2 or 3). + * @retval None + */ +void RCC_I2CCLKConfig(uint32_t RCC_I2CCLK) +{ + uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_RCC_I2CCLK(RCC_I2CCLK)); + + tmp = (RCC_I2CCLK >> 28); + + /* Clear I2CSW bit */ + switch (tmp) + { + case 0x00: + RCC->CFGR3 &= ~RCC_CFGR3_I2C1SW; + break; + case 0x01: + RCC->CFGR3 &= ~RCC_CFGR3_I2C2SW; + break; + case 0x02: + RCC->CFGR3 &= ~RCC_CFGR3_I2C3SW; + break; + default: + break; + } + + /* Set I2CSW bits according to RCC_I2CCLK value */ + RCC->CFGR3 |= RCC_I2CCLK; +} + +/** + * @brief Configures the TIMx clock sources(TIMCLK). + * @note The configuration of the TIMx clock source is only possible when the + * SYSCLK = PLL and HCLK and PCLK2 clocks are not divided in respect to SYSCLK + * @note If one of the previous conditions is missed, the TIM clock source + * configuration is lost and calling again this function becomes mandatory. + * @param RCC_TIMCLK: defines the TIMx clock source. + * This parameter can be one of the following values: + * @arg RCC_TIMxCLK_HCLK: TIMx clock = APB high speed clock (doubled frequency + * when prescaled) + * @arg RCC_TIMxCLK_PLLCLK: TIMx clock = PLL output (running up to 144 MHz) + * (x can be 1, 8, 15, 16, 17). + * @retval None + */ +void RCC_TIMCLKConfig(uint32_t RCC_TIMCLK) +{ + uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_RCC_TIMCLK(RCC_TIMCLK)); + + tmp = (RCC_TIMCLK >> 28); + + /* Clear TIMSW bit */ + + switch (tmp) + { + case 0x00: + RCC->CFGR3 &= ~RCC_CFGR3_TIM1SW; + break; + case 0x01: + RCC->CFGR3 &= ~RCC_CFGR3_TIM8SW; + break; + case 0x02: + RCC->CFGR3 &= ~RCC_CFGR3_TIM15SW; + break; + case 0x03: + RCC->CFGR3 &= ~RCC_CFGR3_TIM16SW; + break; + case 0x04: + RCC->CFGR3 &= ~RCC_CFGR3_TIM17SW; + break; + default: + break; + } + + /* Set I2CSW bits according to RCC_TIMCLK value */ + RCC->CFGR3 |= RCC_TIMCLK; +} + +/** + * @brief Configures the HRTIM1 clock sources(HRTIM1CLK). + * @note The configuration of the HRTIM1 clock source is only possible when the + * SYSCLK = PLL and HCLK and PCLK2 clocks are not divided in respect to SYSCLK + * @note If one of the previous conditions is missed, the TIM clock source + * configuration is lost and calling again this function becomes mandatory. + * @param RCC_HRTIMCLK: defines the TIMx clock source. + * This parameter can be one of the following values: + * @arg RCC_HRTIM1CLK_HCLK: TIMx clock = APB high speed clock (doubled frequency + * when prescaled) + * @arg RCC_HRTIM1CLK_PLLCLK: TIMx clock = PLL output (running up to 144 MHz) + * (x can be 1 or 8). + * @retval None + */ +void RCC_HRTIM1CLKConfig(uint32_t RCC_HRTIMCLK) +{ + /* Check the parameters */ + assert_param(IS_RCC_HRTIMCLK(RCC_HRTIMCLK)); + + /* Clear HRTIMSW bit */ + RCC->CFGR3 &= ~RCC_CFGR3_HRTIM1SW; + + /* Set HRTIMSW bits according to RCC_HRTIMCLK value */ + RCC->CFGR3 |= RCC_HRTIMCLK; +} + +/** + * @brief Configures the USART clock (USARTCLK). + * @param RCC_USARTCLK: defines the USART clock source. This clock is derived + * from the HSI or System clock. + * This parameter can be one of the following values: + * @arg RCC_USARTxCLK_PCLK: USART clock = APB Clock (PCLK) + * @arg RCC_USARTxCLK_SYSCLK: USART clock = System Clock + * @arg RCC_USARTxCLK_LSE: USART clock = LSE Clock + * @arg RCC_USARTxCLK_HSI: USART clock = HSI Clock + * (x can be 1, 2, 3, 4 or 5). + * @retval None + */ +void RCC_USARTCLKConfig(uint32_t RCC_USARTCLK) +{ + uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_RCC_USARTCLK(RCC_USARTCLK)); + + tmp = (RCC_USARTCLK >> 28); + + /* Clear USARTSW[1:0] bit */ + switch (tmp) + { + case 0x01: /* clear USART1SW */ + RCC->CFGR3 &= ~RCC_CFGR3_USART1SW; + break; + case 0x02: /* clear USART2SW */ + RCC->CFGR3 &= ~RCC_CFGR3_USART2SW; + break; + case 0x03: /* clear USART3SW */ + RCC->CFGR3 &= ~RCC_CFGR3_USART3SW; + break; + case 0x04: /* clear UART4SW */ + RCC->CFGR3 &= ~RCC_CFGR3_UART4SW; + break; + case 0x05: /* clear UART5SW */ + RCC->CFGR3 &= ~RCC_CFGR3_UART5SW; + break; + default: + break; + } + + /* Set USARTSW bits according to RCC_USARTCLK value */ + RCC->CFGR3 |= RCC_USARTCLK; +} + +/** + * @brief Configures the USB clock (USBCLK). + * @param RCC_USBCLKSource: specifies the USB clock source. This clock is + * derived from the PLL output. + * This parameter can be one of the following values: + * @arg RCC_USBCLKSource_PLLCLK_1Div5: PLL clock divided by 1,5 selected as USB + * clock source + * @arg RCC_USBCLKSource_PLLCLK_Div1: PLL clock selected as USB clock source + * @retval None + */ +void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_USBCLK_SOURCE(RCC_USBCLKSource)); + + *(__IO uint32_t *) CFGR_USBPRE_BB = RCC_USBCLKSource; +} + +/** + * @brief Configures the RTC clock (RTCCLK). + * @note As the RTC clock configuration bits are in the Backup domain and write + * access is denied to this domain after reset, you have to enable write + * access using PWR_BackupAccessCmd(ENABLE) function before to configure + * the RTC clock source (to be done once after reset). + * @note Once the RTC clock is configured it can't be changed unless the RTC + * is reset using RCC_BackupResetCmd function, or by a Power On Reset (POR) + * + * @param RCC_RTCCLKSource: specifies the RTC clock source. + * This parameter can be one of the following values: + * @arg RCC_RTCCLKSource_LSE: LSE selected as RTC clock + * @arg RCC_RTCCLKSource_LSI: LSI selected as RTC clock + * @arg RCC_RTCCLKSource_HSE_Div32: HSE divided by 32 selected as RTC clock + * + * @note If the LSE or LSI is used as RTC clock source, the RTC continues to + * work in STOP and STANDBY modes, and can be used as wakeup source. + * However, when the HSE clock is used as RTC clock source, the RTC + * cannot be used in STOP and STANDBY modes. + * @note The maximum input clock frequency for RTC is 2MHz (when using HSE as + * RTC clock source). + * @retval None + */ +void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource)); + + /* Select the RTC clock source */ + RCC->BDCR |= RCC_RTCCLKSource; +} + +/** + * @brief Configures the I2S clock source (I2SCLK). + * @note This function must be called before enabling the SPI2 and SPI3 clocks. + * @param RCC_I2SCLKSource: specifies the I2S clock source. + * This parameter can be one of the following values: + * @arg RCC_I2S2CLKSource_SYSCLK: SYSCLK clock used as I2S clock source + * @arg RCC_I2S2CLKSource_Ext: External clock mapped on the I2S_CKIN pin + * used as I2S clock source + * @retval None + */ +void RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_I2SCLK_SOURCE(RCC_I2SCLKSource)); + + *(__IO uint32_t *) CFGR_I2SSRC_BB = RCC_I2SCLKSource; +} + +/** + * @brief Enables or disables the RTC clock. + * @note This function must be used only after the RTC clock source was selected + * using the RCC_RTCCLKConfig function. + * @param NewState: new state of the RTC clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_RTCCLKCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) BDCR_RTCEN_BB = (uint32_t)NewState; +} + +/** + * @brief Forces or releases the Backup domain reset. + * @note This function resets the RTC peripheral (including the backup registers) + * and the RTC clock source selection in RCC_BDCR register. + * @param NewState: new state of the Backup domain reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_BackupResetCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the AHB peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @param RCC_AHBPeriph: specifies the AHB peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_AHBPeriph_GPIOA + * @arg RCC_AHBPeriph_GPIOB + * @arg RCC_AHBPeriph_GPIOC + * @arg RCC_AHBPeriph_GPIOD + * @arg RCC_AHBPeriph_GPIOE + * @arg RCC_AHBPeriph_GPIOF + * @arg RCC_AHBPeriph_TS + * @arg RCC_AHBPeriph_CRC + * @arg RCC_AHBPeriph_FLITF (has effect only when the Flash memory is in power down mode) + * @arg RCC_AHBPeriph_SRAM + * @arg RCC_AHBPeriph_DMA2 + * @arg RCC_AHBPeriph_DMA1 + * @arg RCC_AHBPeriph_ADC34 + * @arg RCC_AHBPeriph_ADC12 + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB_PERIPH(RCC_AHBPeriph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->AHBENR |= RCC_AHBPeriph; + } + else + { + RCC->AHBENR &= ~RCC_AHBPeriph; + } +} + +/** + * @brief Enables or disables the High Speed APB (APB2) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @param RCC_APB2Periph: specifies the APB2 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_APB2Periph_SYSCFG + * @arg RCC_APB2Periph_SPI1 + * @arg RCC_APB2Periph_USART1 + * @arg RCC_APB2Periph_TIM15 + * @arg RCC_APB2Periph_TIM16 + * @arg RCC_APB2Periph_TIM17 + * @arg RCC_APB2Periph_TIM1 + * @arg RCC_APB2Periph_TIM8 + * @arg RCC_APB2Periph_HRTIM1 + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->APB2ENR |= RCC_APB2Periph; + } + else + { + RCC->APB2ENR &= ~RCC_APB2Periph; + } +} + +/** + * @brief Enables or disables the Low Speed APB (APB1) peripheral clock. + * @note After reset, the peripheral clock (used for registers read/write access) + * is disabled and the application software has to enable this clock before + * using it. + * @param RCC_APB1Periph: specifies the APB1 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_APB1Periph_TIM2 + * @arg RCC_APB1Periph_TIM3 + * @arg RCC_APB1Periph_TIM4 + * @arg RCC_APB1Periph_TIM6 + * @arg RCC_APB1Periph_TIM7 + * @arg RCC_APB1Periph_WWDG + * @arg RCC_APB1Periph_SPI2 + * @arg RCC_APB1Periph_SPI3 + * @arg RCC_APB1Periph_USART2 + * @arg RCC_APB1Periph_USART3 + * @arg RCC_APB1Periph_UART4 + * @arg RCC_APB1Periph_UART5 + * @arg RCC_APB1Periph_I2C1 + * @arg RCC_APB1Periph_I2C2 + * @arg RCC_APB1Periph_USB + * @arg RCC_APB1Periph_CAN1 + * @arg RCC_APB1Periph_PWR + * @arg RCC_APB1Periph_DAC1 + * @arg RCC_APB1Periph_DAC2 + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->APB1ENR |= RCC_APB1Periph; + } + else + { + RCC->APB1ENR &= ~RCC_APB1Periph; + } +} + +/** + * @brief Forces or releases AHB peripheral reset. + * @param RCC_AHBPeriph: specifies the AHB peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_AHBPeriph_GPIOA + * @arg RCC_AHBPeriph_GPIOB + * @arg RCC_AHBPeriph_GPIOC + * @arg RCC_AHBPeriph_GPIOD + * @arg RCC_AHBPeriph_GPIOE + * @arg RCC_AHBPeriph_GPIOF + * @arg RCC_AHBPeriph_TS + * @arg RCC_AHBPeriph_ADC34 + * @arg RCC_AHBPeriph_ADC12 + * @param NewState: new state of the specified peripheral reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB_RST_PERIPH(RCC_AHBPeriph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->AHBRSTR |= RCC_AHBPeriph; + } + else + { + RCC->AHBRSTR &= ~RCC_AHBPeriph; + } +} + +/** + * @brief Forces or releases High Speed APB (APB2) peripheral reset. + * @param RCC_APB2Periph: specifies the APB2 peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_APB2Periph_SYSCFG + * @arg RCC_APB2Periph_SPI1 + * @arg RCC_APB2Periph_USART1 + * @arg RCC_APB2Periph_TIM15 + * @arg RCC_APB2Periph_TIM16 + * @arg RCC_APB2Periph_TIM17 + * @arg RCC_APB2Periph_TIM1 + * @arg RCC_APB2Periph_TIM8 + * @arg RCC_APB2Periph_HRTIM1 + * @param NewState: new state of the specified peripheral reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->APB2RSTR |= RCC_APB2Periph; + } + else + { + RCC->APB2RSTR &= ~RCC_APB2Periph; + } +} + +/** + * @brief Forces or releases Low Speed APB (APB1) peripheral reset. + * @param RCC_APB1Periph: specifies the APB1 peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_APB1Periph_TIM2 + * @arg RCC_APB1Periph_TIM3 + * @arg RCC_APB1Periph_TIM4 + * @arg RCC_APB1Periph_TIM6 + * @arg RCC_APB1Periph_TIM7 + * @arg RCC_APB1Periph_WWDG + * @arg RCC_APB1Periph_SPI2 + * @arg RCC_APB1Periph_SPI3 + * @arg RCC_APB1Periph_USART2 + * @arg RCC_APB1Periph_USART3 + * @arg RCC_APB1Periph_UART4 + * @arg RCC_APB1Periph_UART5 + * @arg RCC_APB1Periph_I2C1 + * @arg RCC_APB1Periph_I2C2 + * @arg RCC_APB1Periph_I2C3 + * @arg RCC_APB1Periph_USB + * @arg RCC_APB1Periph_CAN1 + * @arg RCC_APB1Periph_PWR + * @arg RCC_APB1Periph_DAC + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->APB1RSTR |= RCC_APB1Periph; + } + else + { + RCC->APB1RSTR &= ~RCC_APB1Periph; + } +} + +/** + * @} + */ + +/** @defgroup RCC_Group4 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + ##### Interrupts and flags management functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified RCC interrupts. + * @note The CSS interrupt doesn't have an enable bit; once the CSS is enabled + * and if the HSE clock fails, the CSS interrupt occurs and an NMI is + * automatically generated. The NMI will be executed indefinitely, and + * since NMI has higher priority than any other IRQ (and main program) + * the application will be stacked in the NMI ISR unless the CSS interrupt + * pending bit is cleared. + * @param RCC_IT: specifies the RCC interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * @param NewState: new state of the specified RCC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_IT(RCC_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Perform Byte access to RCC_CIR[13:8] bits to enable the selected interrupts */ + *(__IO uint8_t *) CIR_BYTE2_ADDRESS |= RCC_IT; + } + else + { + /* Perform Byte access to RCC_CIR[13:8] bits to disable the selected interrupts */ + *(__IO uint8_t *) CIR_BYTE2_ADDRESS &= (uint8_t)~RCC_IT; + } +} + +/** + * @brief Checks whether the specified RCC flag is set or not. + * @param RCC_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready + * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready + * @arg RCC_FLAG_PLLRDY: PLL clock ready + * @arg RCC_FLAG_MCOF: MCO Flag + * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready + * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready + * @arg RCC_FLAG_OBLRST: Option Byte Loader (OBL) reset + * @arg RCC_FLAG_PINRST: Pin reset + * @arg RCC_FLAG_PORRST: POR/PDR reset + * @arg RCC_FLAG_SFTRST: Software reset + * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset + * @arg RCC_FLAG_WWDGRST: Window Watchdog reset + * @arg RCC_FLAG_LPWRRST: Low Power reset + * @retval The new state of RCC_FLAG (SET or RESET). + */ +FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG) +{ + uint32_t tmp = 0; + uint32_t statusreg = 0; + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_RCC_FLAG(RCC_FLAG)); + + /* Get the RCC register index */ + tmp = RCC_FLAG >> 5; + + if (tmp == 0) /* The flag to check is in CR register */ + { + statusreg = RCC->CR; + } + else if (tmp == 1) /* The flag to check is in BDCR register */ + { + statusreg = RCC->BDCR; + } + else if (tmp == 4) /* The flag to check is in CFGR register */ + { + statusreg = RCC->CFGR; + } + else /* The flag to check is in CSR register */ + { + statusreg = RCC->CSR; + } + + /* Get the flag position */ + tmp = RCC_FLAG & FLAG_MASK; + + if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @brief Clears the RCC reset flags. + * The reset flags are: RCC_FLAG_OBLRST, RCC_FLAG_PINRST, RCC_FLAG_PORRST, + * RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST. + * @param None + * @retval None + */ +void RCC_ClearFlag(void) +{ + /* Set RMVF bit to clear the reset flags */ + RCC->CSR |= RCC_CSR_RMVF; +} + +/** + * @brief Checks whether the specified RCC interrupt has occurred or not. + * @param RCC_IT: specifies the RCC interrupt source to check. + * This parameter can be one of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * @arg RCC_IT_CSS: Clock Security System interrupt + * @retval The new state of RCC_IT (SET or RESET). + */ +ITStatus RCC_GetITStatus(uint8_t RCC_IT) +{ + ITStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_RCC_GET_IT(RCC_IT)); + + /* Check the status of the specified RCC interrupt */ + if ((RCC->CIR & RCC_IT) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the RCC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the RCC's interrupt pending bits. + * @param RCC_IT: specifies the interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * @arg RCC_IT_CSS: Clock Security System interrupt + * @retval None + */ +void RCC_ClearITPendingBit(uint8_t RCC_IT) +{ + /* Check the parameters */ + assert_param(IS_RCC_CLEAR_IT(RCC_IT)); + + /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt + pending bits */ + *(__IO uint8_t *) CIR_BYTE3_ADDRESS = RCC_IT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_rtc.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_rtc.c new file mode 100644 index 0000000..798d755 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_rtc.c @@ -0,0 +1,2598 @@ +/** + ****************************************************************************** + * @file stm32f30x_rtc.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the Real-Time Clock (RTC) peripheral: + * + Initialization + * + Calendar (Time and Date) configuration + * + Alarms (Alarm A and Alarm B) configuration + * + WakeUp Timer configuration + * + Daylight Saving configuration + * + Output pin Configuration + * + Smooth digital Calibration configuration + * + TimeStamp configuration + * + Tampers configuration + * + Backup Data Registers configuration + * + Output Type Config configuration + * + Shift control synchronisation + * + Interrupts and flags management + * + @verbatim + + =============================================================================== + ##### RTC Operating Condition ##### + =============================================================================== + [..] The real-time clock (RTC) and the RTC backup registers can be powered + from the VBAT voltage when the main VDD supply is powered off. + To retain the content of the RTC backup registers and supply the RTC + when VDD is turned off, VBAT pin can be connected to an optional + standby voltage supplied by a battery or by another source. + + [..] To allow the RTC to operate even when the main digital supply (VDD) + is turned off, the VBAT pin powers the following blocks: + (#) The RTC + (#) The LSE oscillator + (#) PC13 to PC15 I/Os (when available) + + [..] When the backup domain is supplied by VDD (analog switch connected + to VDD), the following functions are available: + (#) PC14 and PC15 can be used as either GPIO or LSE pins + (#) PC13 can be used as a GPIO or as the RTC_AF pin + + [..] When the backup domain is supplied by VBAT (analog switch connected + to VBAT because VDD is not present), the following functions are available: + (#) PC14 and PC15 can be used as LSE pins only + (#) PC13 can be used as the RTC_AF pin + + ##### Backup Domain Reset ##### + =============================================================================== + [..] The backup domain reset sets all RTC registers and the RCC_BDCR + register to their reset values. + A backup domain reset is generated when one of the following events + occurs: + (#) Software reset, triggered by setting the BDRST bit in the + RCC Backup domain control register (RCC_BDCR). You can use the + RCC_BackupResetCmd(). + (#) VDD or VBAT power on, if both supplies have previously been + powered off. + + ##### Backup Domain Access ##### + =============================================================================== + [..] After reset, the backup domain (RTC registers and RTC backup data + registers) is protected against possible unwanted write accesses. + [..] To enable access to the Backup Domain and RTC registers, proceed as follows: + (#) Enable the Power Controller (PWR) APB1 interface clock using the + RCC_APB1PeriphClockCmd() function. + (#) Enable access to Backup domain using the PWR_BackupAccessCmd() function. + (#) Select the RTC clock source using the RCC_RTCCLKConfig() function. + (#) Enable RTC Clock using the RCC_RTCCLKCmd() function. + + ##### How to use this driver ##### + =============================================================================== + [..] + (+) Enable the backup domain access (see description in the section above) + (+) Configure the RTC Prescaler (Asynchronous and Synchronous) and + RTC hour format using the RTC_Init() function. + + *** Time and Date configuration *** + =================================== + [..] + (+) To configure the RTC Calendar (Time and Date) use the RTC_SetTime() + and RTC_SetDate() functions. + (+) To read the RTC Calendar, use the RTC_GetTime() and RTC_GetDate() + functions. + (+) To read the RTC subsecond, use the RTC_GetSubSecond() function. + (+) Use the RTC_DayLightSavingConfig() function to add or sub one + hour to the RTC Calendar. + + *** Alarm configuration *** + =========================== + [..] + (+) To configure the RTC Alarm use the RTC_SetAlarm() function. + (+) Enable the selected RTC Alarm using the RTC_AlarmCmd() function. + (+) To read the RTC Alarm, use the RTC_GetAlarm() function. + (+) To read the RTC alarm SubSecond, use the RTC_GetAlarmSubSecond() function. + + *** RTC Wakeup configuration *** + ================================ + [..] + (+) Configure the RTC Wakeup Clock source use the RTC_WakeUpClockConfig() + function. + (+) Configure the RTC WakeUp Counter using the RTC_SetWakeUpCounter() + function + (+) Enable the RTC WakeUp using the RTC_WakeUpCmd() function + (+) To read the RTC WakeUp Counter register, use the RTC_GetWakeUpCounter() + function. + + *** Outputs configuration *** + ============================= + [..] The RTC has 2 different outputs: + (+) AFO_ALARM: this output is used to manage the RTC Alarm A, Alarm B + and WaKeUp signals. + To output the selected RTC signal on RTC_AF pin, use the + RTC_OutputConfig() function. + (+) AFO_CALIB: this output is 512Hz signal or 1Hz . + To output the RTC Clock on RTC_AF pin, use the RTC_CalibOutputCmd() + function. + + *** Smooth digital Calibration configuration *** + ================================================ + [..] + (+) Configure the RTC Original Digital Calibration Value and the corresponding + calibration cycle period (32s,16s and 8s) using the RTC_SmoothCalibConfig() + function. + + *** TimeStamp configuration *** + =============================== + [..] + (+) Configure the RTC_AF trigger and enables the RTC TimeStamp + using the RTC_TimeStampCmd() function. + (+) To read the RTC TimeStamp Time and Date register, use the + RTC_GetTimeStamp() function. + (+) To read the RTC TimeStamp SubSecond register, use the + RTC_GetTimeStampSubSecond() function. + + *** Tamper configuration *** + ============================ + [..] + (+) Configure the Tamper filter count using RTC_TamperFilterConfig() + function. + (+) Configure the RTC Tamper trigger Edge or Level according to the Tamper + filter (if equal to 0 Edge else Level) value using the RTC_TamperConfig() function. + (+) Configure the Tamper sampling frequency using RTC_TamperSamplingFreqConfig() + function. + (+) Configure the Tamper precharge or discharge duration using + RTC_TamperPinsPrechargeDuration() function. + (+) Enable the Tamper Pull-UP using RTC_TamperPullUpDisableCmd() function. + (+) Enable the RTC Tamper using the RTC_TamperCmd() function. + (+) Enable the Time stamp on Tamper detection event using + RTC_TSOnTamperDetecCmd() function. + + *** Backup Data Registers configuration *** + =========================================== + [..] + (+) To write to the RTC Backup Data registers, use the RTC_WriteBackupRegister() + function. + (+) To read the RTC Backup Data registers, use the RTC_ReadBackupRegister() + function. + + ##### RTC and low power modes ##### + =============================================================================== + [..] The MCU can be woken up from a low power mode by an RTC alternate + function. + [..] The RTC alternate functions are the RTC alarms (Alarm A and Alarm B), + RTC wakeup, RTC tamper event detection and RTC time stamp event detection. + These RTC alternate functions can wake up the system from the Stop + and Standby lowpower modes. + The system can also wake up from low power modes without depending + on an external interrupt (Auto-wakeup mode), by using the RTC alarm + or the RTC wakeup events. + [..] The RTC provides a programmable time base for waking up from the + Stop or Standby mode at regular intervals. + Wakeup from STOP and Standby modes is possible only when the RTC + clock source is LSE or LSI. + + ##### Selection of RTC_AF alternate functions ##### + =============================================================================== + [..] The RTC_AF pin (PC13) can be used for the following purposes: + (+) Wakeup pin 2 (WKUP2) using the PWR_WakeUpPinCmd() function. + (+) AFO_ALARM output + (+) AFO_CALIB output + (+) AFI_TAMPER + (+) AFI_TIMESTAMP + + +------------------------------------------------------------------------------------------+ + | Pin |RTC ALARM |RTC CALIB |RTC TAMPER |RTC TIMESTAMP |PC13MODE| PC13VALUE | + | configuration | OUTPUT | OUTPUT | INPUT | INPUT | bit | bit | + | and function | ENABLED | ENABLED | ENABLED | ENABLED | | | + |-----------------|----------|----------|-----------|--------------|--------|--------------| + | Alarm out | | | | | Don't | | + | output OD | 1 |Don't care|Don't care | Don't care | care | 0 | + |-----------------|----------|----------|-----------|--------------|--------|--------------| + | Alarm out | | | | | Don't | | + | output PP | 1 |Don't care|Don't care | Don't care | care | 1 | + |-----------------|----------|----------|-----------|--------------|--------|--------------| + | Calibration out | | | | | Don't | | + | output PP | 0 | 1 |Don't care | Don't care | care | Don't care | + |-----------------|----------|----------|-----------|--------------|--------|--------------| + | TAMPER input | | | | | Don't | | + | floating | 0 | 0 | 1 | 0 | care | Don't care | + |-----------------|----------|----------|-----------|--------------|--------|--------------| + | TIMESTAMP and | | | | | Don't | | + | TAMPER input | 0 | 0 | 1 | 1 | care | Don't care | + | floating | | | | | | | + |-----------------|----------|----------|-----------|--------------|--------|--------------| + | TIMESTAMP input | | | | | Don't | | + | floating | 0 | 0 | 0 | 1 | care | Don't care | + |-----------------|----------|----------|-----------|--------------|--------|--------------| + | Output PP | 0 | 0 | 0 | 0 | 1 | PC13 output | + | Forced | | | | | | | + |-----------------|----------|----------|-----------|--------------|--------|--------------| + | Wakeup Pin or | 0 | 0 | 0 | 0 | 0 | Don't care | + | Standard GPIO | | | | | | | + +------------------------------------------------------------------------------------------+ + + @endverbatim + + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_rtc.h" +#include "stm32f30x_rcc.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup RTC + * @brief RTC driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* Masks Definition */ +#define RTC_TR_RESERVED_MASK ((uint32_t)0x007F7F7F) +#define RTC_DR_RESERVED_MASK ((uint32_t)0x00FFFF3F) +#define RTC_INIT_MASK ((uint32_t)0xFFFFFFFF) +#define RTC_RSF_MASK ((uint32_t)0xFFFFFF5F) +#define RTC_FLAGS_MASK ((uint32_t)(RTC_FLAG_TSOVF | RTC_FLAG_TSF | RTC_FLAG_WUTF | \ + RTC_FLAG_ALRBF | RTC_FLAG_ALRAF | RTC_FLAG_INITF | \ + RTC_FLAG_RSF | RTC_FLAG_INITS | RTC_FLAG_WUTWF | \ + RTC_FLAG_ALRBWF | RTC_FLAG_ALRAWF | RTC_FLAG_TAMP1F | \ + RTC_FLAG_TAMP2F | RTC_FLAG_TAMP3F | RTC_FLAG_RECALPF | \ + RTC_FLAG_SHPF)) + +#define INITMODE_TIMEOUT ((uint32_t) 0x00002000) +#define SYNCHRO_TIMEOUT ((uint32_t) 0x00008000) +#define RECALPF_TIMEOUT ((uint32_t) 0x00001000) +#define SHPF_TIMEOUT ((uint32_t) 0x00002000) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +static uint8_t RTC_ByteToBcd2(uint8_t Value); +static uint8_t RTC_Bcd2ToByte(uint8_t Value); + +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup RTC_Private_Functions + * @{ + */ + +/** @defgroup RTC_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] This section provide functions allowing to initialize and configure the RTC + Prescaler (Synchronous and Asynchronous), RTC Hour format, disable RTC registers + Write protection, enter and exit the RTC initialization mode, RTC registers + synchronization check and reference clock detection enable. + (#) The RTC Prescaler is programmed to generate the RTC 1Hz time base. It is + split into 2 programmable prescalers to minimize power consumption. + (++) A 7-bit asynchronous prescaler and A 13-bit synchronous prescaler. + (++) When both prescalers are used, it is recommended to configure the + asynchronous prescaler to a high value to minimize consumption. + (#) All RTC registers are Write protected. Writing to the RTC registers + is enabled by writing a key into the Write Protection register, RTC_WPR. + (#) To Configure the RTC Calendar, user application should enter initialization + mode. In this mode, the calendar counter is stopped and its value + can be updated. When the initialization sequence is complete, the + calendar restarts counting after 4 RTCCLK cycles. + (#) To read the calendar through the shadow registers after Calendar + initialization, calendar update or after wakeup from low power modes + the software must first clear the RSF flag. The software must then + wait until it is set again before reading the calendar, which means + that the calendar registers have been correctly copied into the RTC_TR + and RTC_DR shadow registers. The RTC_WaitForSynchro() function + implements the above software sequence (RSF clear and RSF check). + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the RTC registers to their default reset values. + * @note This function doesn't reset the RTC Clock source and RTC Backup Data + * registers. + * @param None + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC registers are deinitialized + * - ERROR: RTC registers are not deinitialized + */ +ErrorStatus RTC_DeInit(void) +{ + __IO uint32_t wutcounter = 0x00; + uint32_t wutwfstatus = 0x00; + ErrorStatus status = ERROR; + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Set Initialization mode */ + if (RTC_EnterInitMode() == ERROR) + { + status = ERROR; + } + else + { + /* Reset TR, DR and CR registers */ + RTC->TR = (uint32_t)0x00000000; + RTC->DR = (uint32_t)0x00002101; + + /* Reset All CR bits except CR[2:0] */ + RTC->CR &= (uint32_t)0x00000007; + + /* Wait till RTC WUTWF flag is set and if Time out is reached exit */ + do + { + wutwfstatus = RTC->ISR & RTC_ISR_WUTWF; + wutcounter++; + } while((wutcounter != INITMODE_TIMEOUT) && (wutwfstatus == 0x00)); + + if ((RTC->ISR & RTC_ISR_WUTWF) == RESET) + { + status = ERROR; + } + else + { + /* Reset all RTC CR register bits */ + RTC->CR &= (uint32_t)0x00000000; + RTC->WUTR = (uint32_t)0x0000FFFF; + RTC->PRER = (uint32_t)0x007F00FF; + RTC->ALRMAR = (uint32_t)0x00000000; + RTC->ALRMBR = (uint32_t)0x00000000; + RTC->SHIFTR = (uint32_t)0x00000000; + RTC->CALR = (uint32_t)0x00000000; + RTC->ALRMASSR = (uint32_t)0x00000000; + RTC->ALRMBSSR = (uint32_t)0x00000000; + + /* Reset ISR register and exit initialization mode */ + RTC->ISR = (uint32_t)0x00000000; + + /* Reset Tamper and alternate functions configuration register */ + RTC->TAFCR = 0x00000000; + + /* Wait till the RTC RSF flag is set */ + if (RTC_WaitForSynchro() == ERROR) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @brief Initializes the RTC registers according to the specified parameters + * in RTC_InitStruct. + * @param RTC_InitStruct: pointer to a RTC_InitTypeDef structure that contains + * the configuration information for the RTC peripheral. + * @note The RTC Prescaler register is write protected and can be written in + * initialization mode only. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC registers are initialized + * - ERROR: RTC registers are not initialized + */ +ErrorStatus RTC_Init(RTC_InitTypeDef* RTC_InitStruct) +{ + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_RTC_HOUR_FORMAT(RTC_InitStruct->RTC_HourFormat)); + assert_param(IS_RTC_ASYNCH_PREDIV(RTC_InitStruct->RTC_AsynchPrediv)); + assert_param(IS_RTC_SYNCH_PREDIV(RTC_InitStruct->RTC_SynchPrediv)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Set Initialization mode */ + if (RTC_EnterInitMode() == ERROR) + { + status = ERROR; + } + else + { + /* Clear RTC CR FMT Bit */ + RTC->CR &= ((uint32_t)~(RTC_CR_FMT)); + /* Set RTC_CR register */ + RTC->CR |= ((uint32_t)(RTC_InitStruct->RTC_HourFormat)); + + /* Configure the RTC PRER */ + RTC->PRER = (uint32_t)(RTC_InitStruct->RTC_SynchPrediv); + RTC->PRER |= (uint32_t)(RTC_InitStruct->RTC_AsynchPrediv << 16); + + /* Exit Initialization mode */ + RTC_ExitInitMode(); + + status = SUCCESS; + } + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @brief Fills each RTC_InitStruct member with its default value. + * @param RTC_InitStruct: pointer to a RTC_InitTypeDef structure which will be + * initialized. + * @retval None + */ +void RTC_StructInit(RTC_InitTypeDef* RTC_InitStruct) +{ + /* Initialize the RTC_HourFormat member */ + RTC_InitStruct->RTC_HourFormat = RTC_HourFormat_24; + + /* Initialize the RTC_AsynchPrediv member */ + RTC_InitStruct->RTC_AsynchPrediv = (uint32_t)0x7F; + + /* Initialize the RTC_SynchPrediv member */ + RTC_InitStruct->RTC_SynchPrediv = (uint32_t)0xFF; +} + +/** + * @brief Enables or disables the RTC registers write protection. + * @note All the RTC registers are write protected except for RTC_ISR[13:8], + * RTC_TAFCR and RTC_BKPxR. + * @note Writing a wrong key reactivates the write protection. + * @note The protection mechanism is not affected by system reset. + * @param NewState: new state of the write protection. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_WriteProtectionCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + } + else + { + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + } +} + +/** + * @brief Enters the RTC Initialization mode. + * @note The RTC Initialization mode is write protected, use the + * RTC_WriteProtectionCmd(DISABLE) before calling this function. + * @param None + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC is in Init mode + * - ERROR: RTC is not in Init mode + */ +ErrorStatus RTC_EnterInitMode(void) +{ + __IO uint32_t initcounter = 0x00; + ErrorStatus status = ERROR; + uint32_t initstatus = 0x00; + + /* Check if the Initialization mode is set */ + if ((RTC->ISR & RTC_ISR_INITF) == (uint32_t)RESET) + { + /* Set the Initialization mode */ + RTC->ISR = (uint32_t)RTC_INIT_MASK; + + /* Wait till RTC is in INIT state and if Time out is reached exit */ + do + { + initstatus = RTC->ISR & RTC_ISR_INITF; + initcounter++; + } while((initcounter != INITMODE_TIMEOUT) && (initstatus == 0x00)); + + if ((RTC->ISR & RTC_ISR_INITF) != RESET) + { + status = SUCCESS; + } + else + { + status = ERROR; + } + } + else + { + status = SUCCESS; + } + + return (status); +} + +/** + * @brief Exits the RTC Initialization mode. + * @note When the initialization sequence is complete, the calendar restarts + * counting after 4 RTCCLK cycles. + * @note The RTC Initialization mode is write protected, use the + * RTC_WriteProtectionCmd(DISABLE) before calling this function. + * @param None + * @retval None + */ +void RTC_ExitInitMode(void) +{ + /* Exit Initialization mode */ + RTC->ISR &= (uint32_t)~RTC_ISR_INIT; +} + +/** + * @brief Waits until the RTC Time and Date registers (RTC_TR and RTC_DR) are + * synchronized with RTC APB clock. + * @note The RTC Resynchronization mode is write protected, use the + * RTC_WriteProtectionCmd(DISABLE) before calling this function. + * @note To read the calendar through the shadow registers after Calendar + * initialization, calendar update or after wakeup from low power modes + * the software must first clear the RSF flag. + * The software must then wait until it is set again before reading + * the calendar, which means that the calendar registers have been + * correctly copied into the RTC_TR and RTC_DR shadow registers. + * @param None + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC registers are synchronised + * - ERROR: RTC registers are not synchronised + */ +ErrorStatus RTC_WaitForSynchro(void) +{ + __IO uint32_t synchrocounter = 0; + ErrorStatus status = ERROR; + uint32_t synchrostatus = 0x00; + + if ((RTC->CR & RTC_CR_BYPSHAD) != RESET) + { + /* Bypass shadow mode */ + status = SUCCESS; + } + else + { + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Clear RSF flag */ + RTC->ISR &= (uint32_t)RTC_RSF_MASK; + + /* Wait the registers to be synchronised */ + do + { + synchrostatus = RTC->ISR & RTC_ISR_RSF; + synchrocounter++; + } while((synchrocounter != SYNCHRO_TIMEOUT) && (synchrostatus == 0x00)); + + if ((RTC->ISR & RTC_ISR_RSF) != RESET) + { + status = SUCCESS; + } + else + { + status = ERROR; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + } + + return (status); +} + +/** + * @brief Enables or disables the RTC reference clock detection. + * @param NewState: new state of the RTC reference clock. + * This parameter can be: ENABLE or DISABLE. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC reference clock detection is enabled + * - ERROR: RTC reference clock detection is disabled + */ +ErrorStatus RTC_RefClockCmd(FunctionalState NewState) +{ + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Set Initialization mode */ + if (RTC_EnterInitMode() == ERROR) + { + status = ERROR; + } + else + { + if (NewState != DISABLE) + { + /* Enable the RTC reference clock detection */ + RTC->CR |= RTC_CR_REFCKON; + } + else + { + /* Disable the RTC reference clock detection */ + RTC->CR &= ~RTC_CR_REFCKON; + } + /* Exit Initialization mode */ + RTC_ExitInitMode(); + + status = SUCCESS; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @brief Enables or Disables the Bypass Shadow feature. + * @note When the Bypass Shadow is enabled the calendar value are taken + * directly from the Calendar counter. + * @param NewState: new state of the Bypass Shadow feature. + * This parameter can be: ENABLE or DISABLE. + * @retval None +*/ +void RTC_BypassShadowCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + if (NewState != DISABLE) + { + /* Set the BYPSHAD bit */ + RTC->CR |= (uint8_t)RTC_CR_BYPSHAD; + } + else + { + /* Reset the BYPSHAD bit */ + RTC->CR &= (uint8_t)~RTC_CR_BYPSHAD; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @} + */ + +/** @defgroup RTC_Group2 Time and Date configuration functions + * @brief Time and Date configuration functions + * +@verbatim + =============================================================================== + ##### Time and Date configuration functions ##### + =============================================================================== + [..] This section provide functions allowing to program and read the RTC Calendar + (Time and Date). + +@endverbatim + * @{ + */ + +/** + * @brief Set the RTC current time. + * @param RTC_Format: specifies the format of the entered parameters. + * This parameter can be one of the following values: + * @arg RTC_Format_BIN: Binary data format + * @arg RTC_Format_BCD: BCD data format + * @param RTC_TimeStruct: pointer to a RTC_TimeTypeDef structure that contains + * the time configuration information for the RTC. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC Time register is configured + * - ERROR: RTC Time register is not configured + */ +ErrorStatus RTC_SetTime(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_TimeStruct) +{ + uint32_t tmpreg = 0; + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(RTC_Format)); + + if (RTC_Format == RTC_Format_BIN) + { + if ((RTC->CR & RTC_CR_FMT) != (uint32_t)RESET) + { + assert_param(IS_RTC_HOUR12(RTC_TimeStruct->RTC_Hours)); + assert_param(IS_RTC_H12(RTC_TimeStruct->RTC_H12)); + } + else + { + RTC_TimeStruct->RTC_H12 = 0x00; + assert_param(IS_RTC_HOUR24(RTC_TimeStruct->RTC_Hours)); + } + assert_param(IS_RTC_MINUTES(RTC_TimeStruct->RTC_Minutes)); + assert_param(IS_RTC_SECONDS(RTC_TimeStruct->RTC_Seconds)); + } + else + { + if ((RTC->CR & RTC_CR_FMT) != (uint32_t)RESET) + { + tmpreg = RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Hours); + assert_param(IS_RTC_HOUR12(tmpreg)); + assert_param(IS_RTC_H12(RTC_TimeStruct->RTC_H12)); + } + else + { + RTC_TimeStruct->RTC_H12 = 0x00; + assert_param(IS_RTC_HOUR24(RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Hours))); + } + assert_param(IS_RTC_MINUTES(RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Minutes))); + assert_param(IS_RTC_SECONDS(RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Seconds))); + } + + /* Check the input parameters format */ + if (RTC_Format != RTC_Format_BIN) + { + tmpreg = (((uint32_t)(RTC_TimeStruct->RTC_Hours) << 16) | \ + ((uint32_t)(RTC_TimeStruct->RTC_Minutes) << 8) | \ + ((uint32_t)RTC_TimeStruct->RTC_Seconds) | \ + ((uint32_t)(RTC_TimeStruct->RTC_H12) << 16)); + } + else + { + tmpreg = (uint32_t)(((uint32_t)RTC_ByteToBcd2(RTC_TimeStruct->RTC_Hours) << 16) | \ + ((uint32_t)RTC_ByteToBcd2(RTC_TimeStruct->RTC_Minutes) << 8) | \ + ((uint32_t)RTC_ByteToBcd2(RTC_TimeStruct->RTC_Seconds)) | \ + (((uint32_t)RTC_TimeStruct->RTC_H12) << 16)); + } + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Set Initialization mode */ + if (RTC_EnterInitMode() == ERROR) + { + status = ERROR; + } + else + { + /* Set the RTC_TR register */ + RTC->TR = (uint32_t)(tmpreg & RTC_TR_RESERVED_MASK); + + /* Exit Initialization mode */ + RTC_ExitInitMode(); + + /* If RTC_CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ + if ((RTC->CR & RTC_CR_BYPSHAD) == RESET) + { + if (RTC_WaitForSynchro() == ERROR) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + else + { + status = SUCCESS; + } + + } + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @brief Fills each RTC_TimeStruct member with its default value + * (Time = 00h:00min:00sec). + * @param RTC_TimeStruct: pointer to a RTC_TimeTypeDef structure which will be + * initialized. + * @retval None + */ +void RTC_TimeStructInit(RTC_TimeTypeDef* RTC_TimeStruct) +{ + /* Time = 00h:00min:00sec */ + RTC_TimeStruct->RTC_H12 = RTC_H12_AM; + RTC_TimeStruct->RTC_Hours = 0; + RTC_TimeStruct->RTC_Minutes = 0; + RTC_TimeStruct->RTC_Seconds = 0; +} + +/** + * @brief Get the RTC current Time. + * @param RTC_Format: specifies the format of the returned parameters. + * This parameter can be one of the following values: + * @arg RTC_Format_BIN: Binary data format + * @arg RTC_Format_BCD: BCD data format + * @param RTC_TimeStruct: pointer to a RTC_TimeTypeDef structure that will + * contain the returned current time configuration. + * @retval None + */ +void RTC_GetTime(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_TimeStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(RTC_Format)); + + /* Get the RTC_TR register */ + tmpreg = (uint32_t)(RTC->TR & RTC_TR_RESERVED_MASK); + + /* Fill the structure fields with the read parameters */ + RTC_TimeStruct->RTC_Hours = (uint8_t)((tmpreg & (RTC_TR_HT | RTC_TR_HU)) >> 16); + RTC_TimeStruct->RTC_Minutes = (uint8_t)((tmpreg & (RTC_TR_MNT | RTC_TR_MNU)) >>8); + RTC_TimeStruct->RTC_Seconds = (uint8_t)(tmpreg & (RTC_TR_ST | RTC_TR_SU)); + RTC_TimeStruct->RTC_H12 = (uint8_t)((tmpreg & (RTC_TR_PM)) >> 16); + + /* Check the input parameters format */ + if (RTC_Format == RTC_Format_BIN) + { + /* Convert the structure parameters to Binary format */ + RTC_TimeStruct->RTC_Hours = (uint8_t)RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Hours); + RTC_TimeStruct->RTC_Minutes = (uint8_t)RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Minutes); + RTC_TimeStruct->RTC_Seconds = (uint8_t)RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Seconds); + } +} + +/** + * @brief Gets the RTC current Calendar Subseconds value. + * @note This function freeze the Time and Date registers after reading the + * SSR register. + * @param None + * @retval RTC current Calendar Subseconds value. + */ +uint32_t RTC_GetSubSecond(void) +{ + uint32_t tmpreg = 0; + + /* Get subseconds values from the correspondent registers*/ + tmpreg = (uint32_t)(RTC->SSR); + + /* Read DR register to unfroze calendar registers */ + (void) (RTC->DR); + + return (tmpreg); +} + +/** + * @brief Set the RTC current date. + * @param RTC_Format: specifies the format of the entered parameters. + * This parameter can be one of the following values: + * @arg RTC_Format_BIN: Binary data format + * @arg RTC_Format_BCD: BCD data format + * @param RTC_DateStruct: pointer to a RTC_DateTypeDef structure that contains + * the date configuration information for the RTC. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC Date register is configured + * - ERROR: RTC Date register is not configured + */ +ErrorStatus RTC_SetDate(uint32_t RTC_Format, RTC_DateTypeDef* RTC_DateStruct) +{ + uint32_t tmpreg = 0; + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(RTC_Format)); + + if ((RTC_Format == RTC_Format_BIN) && ((RTC_DateStruct->RTC_Month & 0x10) == 0x10)) + { + RTC_DateStruct->RTC_Month = (RTC_DateStruct->RTC_Month & (uint32_t)~(0x10)) + 0x0A; + } + if (RTC_Format == RTC_Format_BIN) + { + assert_param(IS_RTC_YEAR(RTC_DateStruct->RTC_Year)); + assert_param(IS_RTC_MONTH(RTC_DateStruct->RTC_Month)); + assert_param(IS_RTC_DATE(RTC_DateStruct->RTC_Date)); + } + else + { + assert_param(IS_RTC_YEAR(RTC_Bcd2ToByte(RTC_DateStruct->RTC_Year))); + tmpreg = RTC_Bcd2ToByte(RTC_DateStruct->RTC_Month); + assert_param(IS_RTC_MONTH(tmpreg)); + tmpreg = RTC_Bcd2ToByte(RTC_DateStruct->RTC_Date); + assert_param(IS_RTC_DATE(tmpreg)); + } + assert_param(IS_RTC_WEEKDAY(RTC_DateStruct->RTC_WeekDay)); + + /* Check the input parameters format */ + if (RTC_Format != RTC_Format_BIN) + { + tmpreg = ((((uint32_t)RTC_DateStruct->RTC_Year) << 16) | \ + (((uint32_t)RTC_DateStruct->RTC_Month) << 8) | \ + ((uint32_t)RTC_DateStruct->RTC_Date) | \ + (((uint32_t)RTC_DateStruct->RTC_WeekDay) << 13)); + } + else + { + tmpreg = (((uint32_t)RTC_ByteToBcd2(RTC_DateStruct->RTC_Year) << 16) | \ + ((uint32_t)RTC_ByteToBcd2(RTC_DateStruct->RTC_Month) << 8) | \ + ((uint32_t)RTC_ByteToBcd2(RTC_DateStruct->RTC_Date)) | \ + ((uint32_t)RTC_DateStruct->RTC_WeekDay << 13)); + } + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Set Initialization mode */ + if (RTC_EnterInitMode() == ERROR) + { + status = ERROR; + } + else + { + /* Set the RTC_DR register */ + RTC->DR = (uint32_t)(tmpreg & RTC_DR_RESERVED_MASK); + + /* Exit Initialization mode */ + RTC_ExitInitMode(); + + /* If RTC_CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ + if ((RTC->CR & RTC_CR_BYPSHAD) == RESET) + { + if (RTC_WaitForSynchro() == ERROR) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + else + { + status = SUCCESS; + } + } + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @brief Fills each RTC_DateStruct member with its default value + * (Monday, January 01 xx00). + * @param RTC_DateStruct: pointer to a RTC_DateTypeDef structure which will be + * initialized. + * @retval None + */ +void RTC_DateStructInit(RTC_DateTypeDef* RTC_DateStruct) +{ + /* Monday, January 01 xx00 */ + RTC_DateStruct->RTC_WeekDay = RTC_Weekday_Monday; + RTC_DateStruct->RTC_Date = 1; + RTC_DateStruct->RTC_Month = RTC_Month_January; + RTC_DateStruct->RTC_Year = 0; +} + +/** + * @brief Get the RTC current date. + * @param RTC_Format: specifies the format of the returned parameters. + * This parameter can be one of the following values: + * @arg RTC_Format_BIN: Binary data format + * @arg RTC_Format_BCD: BCD data format + * @param RTC_DateStruct: pointer to a RTC_DateTypeDef structure that will + * contain the returned current date configuration. + * @retval None + */ +void RTC_GetDate(uint32_t RTC_Format, RTC_DateTypeDef* RTC_DateStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(RTC_Format)); + + /* Get the RTC_TR register */ + tmpreg = (uint32_t)(RTC->DR & RTC_DR_RESERVED_MASK); + + /* Fill the structure fields with the read parameters */ + RTC_DateStruct->RTC_Year = (uint8_t)((tmpreg & (RTC_DR_YT | RTC_DR_YU)) >> 16); + RTC_DateStruct->RTC_Month = (uint8_t)((tmpreg & (RTC_DR_MT | RTC_DR_MU)) >> 8); + RTC_DateStruct->RTC_Date = (uint8_t)(tmpreg & (RTC_DR_DT | RTC_DR_DU)); + RTC_DateStruct->RTC_WeekDay = (uint8_t)((tmpreg & (RTC_DR_WDU)) >> 13); + + /* Check the input parameters format */ + if (RTC_Format == RTC_Format_BIN) + { + /* Convert the structure parameters to Binary format */ + RTC_DateStruct->RTC_Year = (uint8_t)RTC_Bcd2ToByte(RTC_DateStruct->RTC_Year); + RTC_DateStruct->RTC_Month = (uint8_t)RTC_Bcd2ToByte(RTC_DateStruct->RTC_Month); + RTC_DateStruct->RTC_Date = (uint8_t)RTC_Bcd2ToByte(RTC_DateStruct->RTC_Date); + RTC_DateStruct->RTC_WeekDay = (uint8_t)(RTC_DateStruct->RTC_WeekDay); + } +} + +/** + * @} + */ + +/** @defgroup RTC_Group3 Alarms configuration functions + * @brief Alarms (Alarm A and Alarm B) configuration functions + * +@verbatim + =============================================================================== + ##### Alarms (Alarm A and Alarm B) configuration functions ##### + =============================================================================== + [..] This section provides functions allowing to program and read the RTC Alarms. + +@endverbatim + * @{ + */ + +/** + * @brief Set the specified RTC Alarm. + * @note The Alarm register can only be written when the corresponding Alarm + * is disabled (Use the RTC_AlarmCmd(DISABLE)). + * @param RTC_Format: specifies the format of the returned parameters. + * This parameter can be one of the following values: + * @arg RTC_Format_BIN: Binary data format + * @arg RTC_Format_BCD: BCD data format + * @param RTC_Alarm: specifies the alarm to be configured. + * This parameter can be one of the following values: + * @arg RTC_Alarm_A: to select Alarm A + * @arg RTC_Alarm_B: to select Alarm B + * @param RTC_AlarmStruct: pointer to a RTC_AlarmTypeDef structure that + * contains the alarm configuration parameters. + * @retval None + */ +void RTC_SetAlarm(uint32_t RTC_Format, uint32_t RTC_Alarm, RTC_AlarmTypeDef* RTC_AlarmStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(RTC_Format)); + assert_param(IS_RTC_ALARM(RTC_Alarm)); + assert_param(IS_ALARM_MASK(RTC_AlarmStruct->RTC_AlarmMask)); + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_SEL(RTC_AlarmStruct->RTC_AlarmDateWeekDaySel)); + + if (RTC_Format == RTC_Format_BIN) + { + if ((RTC->CR & RTC_CR_FMT) != (uint32_t)RESET) + { + assert_param(IS_RTC_HOUR12(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours)); + assert_param(IS_RTC_H12(RTC_AlarmStruct->RTC_AlarmTime.RTC_H12)); + } + else + { + RTC_AlarmStruct->RTC_AlarmTime.RTC_H12 = 0x00; + assert_param(IS_RTC_HOUR24(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours)); + } + assert_param(IS_RTC_MINUTES(RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes)); + assert_param(IS_RTC_SECONDS(RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds)); + + if(RTC_AlarmStruct->RTC_AlarmDateWeekDaySel == RTC_AlarmDateWeekDaySel_Date) + { + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_DATE(RTC_AlarmStruct->RTC_AlarmDateWeekDay)); + } + else + { + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(RTC_AlarmStruct->RTC_AlarmDateWeekDay)); + } + } + else + { + if ((RTC->CR & RTC_CR_FMT) != (uint32_t)RESET) + { + tmpreg = RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours); + assert_param(IS_RTC_HOUR12(tmpreg)); + assert_param(IS_RTC_H12(RTC_AlarmStruct->RTC_AlarmTime.RTC_H12)); + } + else + { + RTC_AlarmStruct->RTC_AlarmTime.RTC_H12 = 0x00; + assert_param(IS_RTC_HOUR24(RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours))); + } + + assert_param(IS_RTC_MINUTES(RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes))); + assert_param(IS_RTC_SECONDS(RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds))); + + if(RTC_AlarmStruct->RTC_AlarmDateWeekDaySel == RTC_AlarmDateWeekDaySel_Date) + { + tmpreg = RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmDateWeekDay); + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_DATE(tmpreg)); + } + else + { + tmpreg = RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmDateWeekDay); + assert_param(IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(tmpreg)); + } + } + + /* Check the input parameters format */ + if (RTC_Format != RTC_Format_BIN) + { + tmpreg = (((uint32_t)(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours) << 16) | \ + ((uint32_t)(RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes) << 8) | \ + ((uint32_t)RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds) | \ + ((uint32_t)(RTC_AlarmStruct->RTC_AlarmTime.RTC_H12) << 16) | \ + ((uint32_t)(RTC_AlarmStruct->RTC_AlarmDateWeekDay) << 24) | \ + ((uint32_t)RTC_AlarmStruct->RTC_AlarmDateWeekDaySel) | \ + ((uint32_t)RTC_AlarmStruct->RTC_AlarmMask)); + } + else + { + tmpreg = (((uint32_t)RTC_ByteToBcd2(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours) << 16) | \ + ((uint32_t)RTC_ByteToBcd2(RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes) << 8) | \ + ((uint32_t)RTC_ByteToBcd2(RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds)) | \ + ((uint32_t)(RTC_AlarmStruct->RTC_AlarmTime.RTC_H12) << 16) | \ + ((uint32_t)RTC_ByteToBcd2(RTC_AlarmStruct->RTC_AlarmDateWeekDay) << 24) | \ + ((uint32_t)RTC_AlarmStruct->RTC_AlarmDateWeekDaySel) | \ + ((uint32_t)RTC_AlarmStruct->RTC_AlarmMask)); + } + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Configure the Alarm register */ + if (RTC_Alarm == RTC_Alarm_A) + { + RTC->ALRMAR = (uint32_t)tmpreg; + } + else + { + RTC->ALRMBR = (uint32_t)tmpreg; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Fills each RTC_AlarmStruct member with its default value + * (Time = 00h:00mn:00sec / Date = 1st day of the month/Mask = + * all fields are masked). + * @param RTC_AlarmStruct: pointer to a @ref RTC_AlarmTypeDef structure which + * will be initialized. + * @retval None + */ +void RTC_AlarmStructInit(RTC_AlarmTypeDef* RTC_AlarmStruct) +{ + /* Alarm Time Settings : Time = 00h:00mn:00sec */ + RTC_AlarmStruct->RTC_AlarmTime.RTC_H12 = RTC_H12_AM; + RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours = 0; + RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes = 0; + RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds = 0; + + /* Alarm Date Settings : Date = 1st day of the month */ + RTC_AlarmStruct->RTC_AlarmDateWeekDaySel = RTC_AlarmDateWeekDaySel_Date; + RTC_AlarmStruct->RTC_AlarmDateWeekDay = 1; + + /* Alarm Masks Settings : Mask = all fields are not masked */ + RTC_AlarmStruct->RTC_AlarmMask = RTC_AlarmMask_None; +} + +/** + * @brief Get the RTC Alarm value and masks. + * @param RTC_Format: specifies the format of the output parameters. + * This parameter can be one of the following values: + * @arg RTC_Format_BIN: Binary data format + * @arg RTC_Format_BCD: BCD data format + * @param RTC_Alarm: specifies the alarm to be read. + * This parameter can be one of the following values: + * @arg RTC_Alarm_A: to select Alarm A + * @arg RTC_Alarm_B: to select Alarm B + * @param RTC_AlarmStruct: pointer to a RTC_AlarmTypeDef structure that will + * contains the output alarm configuration values. + * @retval None + */ +void RTC_GetAlarm(uint32_t RTC_Format, uint32_t RTC_Alarm, RTC_AlarmTypeDef* RTC_AlarmStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(RTC_Format)); + assert_param(IS_RTC_ALARM(RTC_Alarm)); + + /* Get the RTC_ALRMxR register */ + if (RTC_Alarm == RTC_Alarm_A) + { + tmpreg = (uint32_t)(RTC->ALRMAR); + } + else + { + tmpreg = (uint32_t)(RTC->ALRMBR); + } + + /* Fill the structure with the read parameters */ + RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours = (uint32_t)((tmpreg & (RTC_ALRMAR_HT | \ + RTC_ALRMAR_HU)) >> 16); + RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes = (uint32_t)((tmpreg & (RTC_ALRMAR_MNT | \ + RTC_ALRMAR_MNU)) >> 8); + RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds = (uint32_t)(tmpreg & (RTC_ALRMAR_ST | \ + RTC_ALRMAR_SU)); + RTC_AlarmStruct->RTC_AlarmTime.RTC_H12 = (uint32_t)((tmpreg & RTC_ALRMAR_PM) >> 16); + RTC_AlarmStruct->RTC_AlarmDateWeekDay = (uint32_t)((tmpreg & (RTC_ALRMAR_DT | RTC_ALRMAR_DU)) >> 24); + RTC_AlarmStruct->RTC_AlarmDateWeekDaySel = (uint32_t)(tmpreg & RTC_ALRMAR_WDSEL); + RTC_AlarmStruct->RTC_AlarmMask = (uint32_t)(tmpreg & RTC_AlarmMask_All); + + if (RTC_Format == RTC_Format_BIN) + { + RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours = RTC_Bcd2ToByte(RTC_AlarmStruct-> \ + RTC_AlarmTime.RTC_Hours); + RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes = RTC_Bcd2ToByte(RTC_AlarmStruct-> \ + RTC_AlarmTime.RTC_Minutes); + RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds = RTC_Bcd2ToByte(RTC_AlarmStruct-> \ + RTC_AlarmTime.RTC_Seconds); + RTC_AlarmStruct->RTC_AlarmDateWeekDay = RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmDateWeekDay); + } +} + +/** + * @brief Enables or disables the specified RTC Alarm. + * @param RTC_Alarm: specifies the alarm to be configured. + * This parameter can be any combination of the following values: + * @arg RTC_Alarm_A: to select Alarm A + * @arg RTC_Alarm_B: to select Alarm B + * @param NewState: new state of the specified alarm. + * This parameter can be: ENABLE or DISABLE. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC Alarm is enabled/disabled + * - ERROR: RTC Alarm is not enabled/disabled + */ +ErrorStatus RTC_AlarmCmd(uint32_t RTC_Alarm, FunctionalState NewState) +{ + __IO uint32_t alarmcounter = 0x00; + uint32_t alarmstatus = 0x00; + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_RTC_CMD_ALARM(RTC_Alarm)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Configure the Alarm state */ + if (NewState != DISABLE) + { + RTC->CR |= (uint32_t)RTC_Alarm; + + status = SUCCESS; + } + else + { + /* Disable the Alarm in RTC_CR register */ + RTC->CR &= (uint32_t)~RTC_Alarm; + + /* Wait till RTC ALRxWF flag is set and if Time out is reached exit */ + do + { + alarmstatus = RTC->ISR & (RTC_Alarm >> 8); + alarmcounter++; + } while((alarmcounter != INITMODE_TIMEOUT) && (alarmstatus == 0x00)); + + if ((RTC->ISR & (RTC_Alarm >> 8)) == RESET) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @brief Configures the RTC AlarmA/B Subseconds value and mask. + * @note This function is performed only when the Alarm is disabled. + * @param RTC_Alarm: specifies the alarm to be configured. + * This parameter can be one of the following values: + * @arg RTC_Alarm_A: to select Alarm A + * @arg RTC_Alarm_B: to select Alarm B + * @param RTC_AlarmSubSecondValue: specifies the Subseconds value. + * This parameter can be a value from 0 to 0x00007FFF. + * @param RTC_AlarmSubSecondMask: specifies the Subseconds Mask. + * This parameter can be any combination of the following values: + * @arg RTC_AlarmSubSecondMask_All : All Alarm SS fields are masked. + * There is no comparison on sub seconds for Alarm. + * @arg RTC_AlarmSubSecondMask_SS14_1 : SS[14:1] are don't care in Alarm comparison. + * Only SS[0] is compared + * @arg RTC_AlarmSubSecondMask_SS14_2 : SS[14:2] are don't care in Alarm comparison. + * Only SS[1:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_3 : SS[14:3] are don't care in Alarm comparison. + * Only SS[2:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_4 : SS[14:4] are don't care in Alarm comparison. + * Only SS[3:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_5 : SS[14:5] are don't care in Alarm comparison. + * Only SS[4:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_6 : SS[14:6] are don't care in Alarm comparison. + * Only SS[5:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_7 : SS[14:7] are don't care in Alarm comparison. + * Only SS[6:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_8 : SS[14:8] are don't care in Alarm comparison. + * Only SS[7:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_9 : SS[14:9] are don't care in Alarm comparison. + * Only SS[8:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_10: SS[14:10] are don't care in Alarm comparison. + * Only SS[9:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_11: SS[14:11] are don't care in Alarm comparison. + * Only SS[10:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_12: SS[14:12] are don't care in Alarm comparison. + * Only SS[11:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14_13: SS[14:13] are don't care in Alarm comparison. + * Only SS[12:0] are compared + * @arg RTC_AlarmSubSecondMask_SS14 : SS[14] is don't care in Alarm comparison. + * Only SS[13:0] are compared + * @arg RTC_AlarmSubSecondMask_None : SS[14:0] are compared and must match + * to activate alarm + * @retval None + */ +void RTC_AlarmSubSecondConfig(uint32_t RTC_Alarm, uint32_t RTC_AlarmSubSecondValue, uint32_t RTC_AlarmSubSecondMask) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_ALARM(RTC_Alarm)); + assert_param(IS_RTC_ALARM_SUB_SECOND_VALUE(RTC_AlarmSubSecondValue)); + assert_param(IS_RTC_ALARM_SUB_SECOND_MASK(RTC_AlarmSubSecondMask)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Configure the Alarm A or Alarm B SubSecond registers */ + tmpreg = (uint32_t) (uint32_t)(RTC_AlarmSubSecondValue) | (uint32_t)(RTC_AlarmSubSecondMask); + + if (RTC_Alarm == RTC_Alarm_A) + { + /* Configure the AlarmA SubSecond register */ + RTC->ALRMASSR = tmpreg; + } + else + { + /* Configure the Alarm B SubSecond register */ + RTC->ALRMBSSR = tmpreg; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + +} + +/** + * @brief Gets the RTC Alarm Subseconds value. + * @param RTC_Alarm: specifies the alarm to be read. + * This parameter can be one of the following values: + * @arg RTC_Alarm_A: to select Alarm A + * @arg RTC_Alarm_B: to select Alarm B + * @param None + * @retval RTC Alarm Subseconds value. + */ +uint32_t RTC_GetAlarmSubSecond(uint32_t RTC_Alarm) +{ + uint32_t tmpreg = 0; + + /* Get the RTC_ALRMxR register */ + if (RTC_Alarm == RTC_Alarm_A) + { + tmpreg = (uint32_t)((RTC->ALRMASSR) & RTC_ALRMASSR_SS); + } + else + { + tmpreg = (uint32_t)((RTC->ALRMBSSR) & RTC_ALRMBSSR_SS); + } + + return (tmpreg); +} + +/** + * @} + */ + +/** @defgroup RTC_Group4 WakeUp Timer configuration functions + * @brief WakeUp Timer configuration functions + * +@verbatim + =============================================================================== + ##### WakeUp Timer configuration functions ##### + =============================================================================== + [..] This section provide functions allowing to program and read the RTC WakeUp. + +@endverbatim + * @{ + */ + +/** + * @brief Configures the RTC Wakeup clock source. + * @note The WakeUp Clock source can only be changed when the RTC WakeUp + * is disabled (Use the RTC_WakeUpCmd(DISABLE)). + * @param RTC_WakeUpClock: Wakeup Clock source. + * This parameter can be one of the following values: + * @arg RTC_WakeUpClock_RTCCLK_Div16: RTC Wakeup Counter Clock = RTCCLK/16 + * @arg RTC_WakeUpClock_RTCCLK_Div8: RTC Wakeup Counter Clock = RTCCLK/8 + * @arg RTC_WakeUpClock_RTCCLK_Div4: RTC Wakeup Counter Clock = RTCCLK/4 + * @arg RTC_WakeUpClock_RTCCLK_Div2: RTC Wakeup Counter Clock = RTCCLK/2 + * @arg RTC_WakeUpClock_CK_SPRE_16bits: RTC Wakeup Counter Clock = CK_SPRE + * @arg RTC_WakeUpClock_CK_SPRE_17bits: RTC Wakeup Counter Clock = CK_SPRE + * @retval None + */ +void RTC_WakeUpClockConfig(uint32_t RTC_WakeUpClock) +{ + /* Check the parameters */ + assert_param(IS_RTC_WAKEUP_CLOCK(RTC_WakeUpClock)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Clear the Wakeup Timer clock source bits in CR register */ + RTC->CR &= (uint32_t)~RTC_CR_WUCKSEL; + + /* Configure the clock source */ + RTC->CR |= (uint32_t)RTC_WakeUpClock; + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Configures the RTC Wakeup counter. + * @note The RTC WakeUp counter can only be written when the RTC WakeUp + * is disabled (Use the RTC_WakeUpCmd(DISABLE)). + * @param RTC_WakeUpCounter: specifies the WakeUp counter. + * This parameter can be a value from 0x0000 to 0xFFFF. + * @retval None + */ +void RTC_SetWakeUpCounter(uint32_t RTC_WakeUpCounter) +{ + /* Check the parameters */ + assert_param(IS_RTC_WAKEUP_COUNTER(RTC_WakeUpCounter)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Configure the Wakeup Timer counter */ + RTC->WUTR = (uint32_t)RTC_WakeUpCounter; + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Returns the RTC WakeUp timer counter value. + * @param None + * @retval The RTC WakeUp Counter value. + */ +uint32_t RTC_GetWakeUpCounter(void) +{ + /* Get the counter value */ + return ((uint32_t)(RTC->WUTR & RTC_WUTR_WUT)); +} + +/** + * @brief Enables or Disables the RTC WakeUp timer. + * @param NewState: new state of the WakeUp timer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +ErrorStatus RTC_WakeUpCmd(FunctionalState NewState) +{ + __IO uint32_t wutcounter = 0x00; + uint32_t wutwfstatus = 0x00; + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + if (NewState != DISABLE) + { + /* Enable the Wakeup Timer */ + RTC->CR |= (uint32_t)RTC_CR_WUTE; + status = SUCCESS; + } + else + { + /* Disable the Wakeup Timer */ + RTC->CR &= (uint32_t)~RTC_CR_WUTE; + /* Wait till RTC WUTWF flag is set and if Time out is reached exit */ + do + { + wutwfstatus = RTC->ISR & RTC_ISR_WUTWF; + wutcounter++; + } while((wutcounter != INITMODE_TIMEOUT) && (wutwfstatus == 0x00)); + + if ((RTC->ISR & RTC_ISR_WUTWF) == RESET) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return status; +} + +/** + * @} + */ + +/** @defgroup RTC_Group5 Daylight Saving configuration functions + * @brief Daylight Saving configuration functions + * +@verbatim + =============================================================================== + ##### Daylight Saving configuration functions ##### + =============================================================================== + [..] This section provide functions allowing to configure the RTC DayLight Saving. + +@endverbatim + * @{ + */ + +/** + * @brief Adds or substract one hour from the current time. + * @param RTC_DayLightSaveOperation: the value of hour adjustment. + * This parameter can be one of the following values: + * @arg RTC_DayLightSaving_SUB1H: Substract one hour (winter time) + * @arg RTC_DayLightSaving_ADD1H: Add one hour (summer time) + * @param RTC_StoreOperation: Specifies the value to be written in the BCK bit + * in CR register to store the operation. + * This parameter can be one of the following values: + * @arg RTC_StoreOperation_Reset: BCK Bit Reset + * @arg RTC_StoreOperation_Set: BCK Bit Set + * @retval None + */ +void RTC_DayLightSavingConfig(uint32_t RTC_DayLightSaving, uint32_t RTC_StoreOperation) +{ + /* Check the parameters */ + assert_param(IS_RTC_DAYLIGHT_SAVING(RTC_DayLightSaving)); + assert_param(IS_RTC_STORE_OPERATION(RTC_StoreOperation)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Clear the bits to be configured */ + RTC->CR &= (uint32_t)~(RTC_CR_BCK); + + /* Configure the RTC_CR register */ + RTC->CR |= (uint32_t)(RTC_DayLightSaving | RTC_StoreOperation); + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Returns the RTC Day Light Saving stored operation. + * @param None + * @retval RTC Day Light Saving stored operation. + * - RTC_StoreOperation_Reset + * - RTC_StoreOperation_Set + */ +uint32_t RTC_GetStoreOperation(void) +{ + return (RTC->CR & RTC_CR_BCK); +} + +/** + * @} + */ + +/** @defgroup RTC_Group6 Output pin Configuration function + * @brief Output pin Configuration function + * +@verbatim + =============================================================================== + ##### Output pin Configuration function ##### + =============================================================================== + [..] This section provide functions allowing to configure the RTC Output source. + +@endverbatim + * @{ + */ + +/** + * @brief Configures the RTC output source (AFO_ALARM). + * @param RTC_Output: Specifies which signal will be routed to the RTC output. + * This parameter can be one of the following values: + * @arg RTC_Output_Disable: No output selected + * @arg RTC_Output_AlarmA: signal of AlarmA mapped to output + * @arg RTC_Output_AlarmB: signal of AlarmB mapped to output + * @arg RTC_Output_WakeUp: signal of WakeUp mapped to output + * @param RTC_OutputPolarity: Specifies the polarity of the output signal. + * This parameter can be one of the following: + * @arg RTC_OutputPolarity_High: The output pin is high when the + * ALRAF/ALRBF/WUTF is high (depending on OSEL) + * @arg RTC_OutputPolarity_Low: The output pin is low when the + * ALRAF/ALRBF/WUTF is high (depending on OSEL) + * @retval None + */ +void RTC_OutputConfig(uint32_t RTC_Output, uint32_t RTC_OutputPolarity) +{ + /* Check the parameters */ + assert_param(IS_RTC_OUTPUT(RTC_Output)); + assert_param(IS_RTC_OUTPUT_POL(RTC_OutputPolarity)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Clear the bits to be configured */ + RTC->CR &= (uint32_t)~(RTC_CR_OSEL | RTC_CR_POL); + + /* Configure the output selection and polarity */ + RTC->CR |= (uint32_t)(RTC_Output | RTC_OutputPolarity); + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @} + */ + +/** @defgroup RTC_Group7 Digital Calibration configuration functions + * @brief Digital Calibration configuration functions + * +@verbatim + =============================================================================== + ##### Digital Calibration configuration functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the RTC clock to be output through the relative + * pin. + * @param NewState: new state of the digital calibration Output. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_CalibOutputCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + if (NewState != DISABLE) + { + /* Enable the RTC clock output */ + RTC->CR |= (uint32_t)RTC_CR_COE; + } + else + { + /* Disable the RTC clock output */ + RTC->CR &= (uint32_t)~RTC_CR_COE; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Configures the Calibration Pinout (RTC_CALIB) Selection (1Hz or 512Hz). + * @param RTC_CalibOutput : Select the Calibration output Selection . + * This parameter can be one of the following values: + * @arg RTC_CalibOutput_512Hz: A signal has a regular waveform at 512Hz. + * @arg RTC_CalibOutput_1Hz : A signal has a regular waveform at 1Hz. + * @retval None +*/ +void RTC_CalibOutputConfig(uint32_t RTC_CalibOutput) +{ + /* Check the parameters */ + assert_param(IS_RTC_CALIB_OUTPUT(RTC_CalibOutput)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /*clear flags before config*/ + RTC->CR &= (uint32_t)~(RTC_CR_COSEL); + + /* Configure the RTC_CR register */ + RTC->CR |= (uint32_t)RTC_CalibOutput; + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Configures the Smooth Calibration Settings. + * @param RTC_SmoothCalibPeriod : Select the Smooth Calibration Period. + * This parameter can be can be one of the following values: + * @arg RTC_SmoothCalibPeriod_32sec : The smooth calibration periode is 32s. + * @arg RTC_SmoothCalibPeriod_16sec : The smooth calibration periode is 16s. + * @arg RTC_SmoothCalibPeriod_8sec : The smooth calibartion periode is 8s. + * @param RTC_SmoothCalibPlusPulses : Select to Set or reset the CALP bit. + * This parameter can be one of the following values: + * @arg RTC_SmoothCalibPlusPulses_Set : Add one RTCCLK puls every 2**11 pulses. + * @arg RTC_SmoothCalibPlusPulses_Reset: No RTCCLK pulses are added. + * @param RTC_SmouthCalibMinusPulsesValue: Select the value of CALM[8:0] bits. + * This parameter can be one any value from 0 to 0x000001FF. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC Calib registers are configured + * - ERROR: RTC Calib registers are not configured +*/ +ErrorStatus RTC_SmoothCalibConfig(uint32_t RTC_SmoothCalibPeriod, + uint32_t RTC_SmoothCalibPlusPulses, + uint32_t RTC_SmouthCalibMinusPulsesValue) +{ + ErrorStatus status = ERROR; + uint32_t recalpfcount = 0; + + /* Check the parameters */ + assert_param(IS_RTC_SMOOTH_CALIB_PERIOD(RTC_SmoothCalibPeriod)); + assert_param(IS_RTC_SMOOTH_CALIB_PLUS(RTC_SmoothCalibPlusPulses)); + assert_param(IS_RTC_SMOOTH_CALIB_MINUS(RTC_SmouthCalibMinusPulsesValue)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* check if a calibration is pending*/ + if ((RTC->ISR & RTC_ISR_RECALPF) != RESET) + { + /* wait until the Calibration is completed*/ + while (((RTC->ISR & RTC_ISR_RECALPF) != RESET) && (recalpfcount != RECALPF_TIMEOUT)) + { + recalpfcount++; + } + } + + /* check if the calibration pending is completed or if there is no calibration operation at all*/ + if ((RTC->ISR & RTC_ISR_RECALPF) == RESET) + { + /* Configure the Smooth calibration settings */ + RTC->CALR = (uint32_t)((uint32_t)RTC_SmoothCalibPeriod | (uint32_t)RTC_SmoothCalibPlusPulses | (uint32_t)RTC_SmouthCalibMinusPulsesValue); + + status = SUCCESS; + } + else + { + status = ERROR; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return (ErrorStatus)(status); +} + +/** + * @} + */ + + +/** @defgroup RTC_Group8 TimeStamp configuration functions + * @brief TimeStamp configuration functions + * +@verbatim + =============================================================================== + ##### TimeStamp configuration functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or Disables the RTC TimeStamp functionality with the + * specified time stamp pin stimulating edge. + * @param RTC_TimeStampEdge: Specifies the pin edge on which the TimeStamp is + * activated. + * This parameter can be one of the following: + * @arg RTC_TimeStampEdge_Rising: the Time stamp event occurs on the rising + * edge of the related pin. + * @arg RTC_TimeStampEdge_Falling: the Time stamp event occurs on the + * falling edge of the related pin. + * @param NewState: new state of the TimeStamp. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_TimeStampCmd(uint32_t RTC_TimeStampEdge, FunctionalState NewState) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_TIMESTAMP_EDGE(RTC_TimeStampEdge)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Get the RTC_CR register and clear the bits to be configured */ + tmpreg = (uint32_t)(RTC->CR & (uint32_t)~(RTC_CR_TSEDGE | RTC_CR_TSE)); + + /* Get the new configuration */ + if (NewState != DISABLE) + { + tmpreg |= (uint32_t)(RTC_TimeStampEdge | RTC_CR_TSE); + } + else + { + tmpreg |= (uint32_t)(RTC_TimeStampEdge); + } + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Configure the Time Stamp TSEDGE and Enable bits */ + RTC->CR = (uint32_t)tmpreg; + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Gets the RTC TimeStamp value and masks. + * @param RTC_Format: specifies the format of the output parameters. + * This parameter can be one of the following values: + * @arg RTC_Format_BIN: Binary data format + * @arg RTC_Format_BCD: BCD data format + * @param RTC_StampTimeStruct: pointer to a RTC_TimeTypeDef structure that will + * contains the TimeStamp time values. + * @param RTC_StampDateStruct: pointer to a RTC_DateTypeDef structure that will + * contains the TimeStamp date values. + * @retval None + */ +void RTC_GetTimeStamp(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_StampTimeStruct, + RTC_DateTypeDef* RTC_StampDateStruct) +{ + uint32_t tmptime = 0, tmpdate = 0; + + /* Check the parameters */ + assert_param(IS_RTC_FORMAT(RTC_Format)); + + /* Get the TimeStamp time and date registers values */ + tmptime = (uint32_t)(RTC->TSTR & RTC_TR_RESERVED_MASK); + tmpdate = (uint32_t)(RTC->TSDR & RTC_DR_RESERVED_MASK); + + /* Fill the Time structure fields with the read parameters */ + RTC_StampTimeStruct->RTC_Hours = (uint8_t)((tmptime & (RTC_TR_HT | RTC_TR_HU)) >> 16); + RTC_StampTimeStruct->RTC_Minutes = (uint8_t)((tmptime & (RTC_TR_MNT | RTC_TR_MNU)) >> 8); + RTC_StampTimeStruct->RTC_Seconds = (uint8_t)(tmptime & (RTC_TR_ST | RTC_TR_SU)); + RTC_StampTimeStruct->RTC_H12 = (uint8_t)((tmptime & (RTC_TR_PM)) >> 16); + + /* Fill the Date structure fields with the read parameters */ + RTC_StampDateStruct->RTC_Year = 0; + RTC_StampDateStruct->RTC_Month = (uint8_t)((tmpdate & (RTC_DR_MT | RTC_DR_MU)) >> 8); + RTC_StampDateStruct->RTC_Date = (uint8_t)(tmpdate & (RTC_DR_DT | RTC_DR_DU)); + RTC_StampDateStruct->RTC_WeekDay = (uint8_t)((tmpdate & (RTC_DR_WDU)) >> 13); + + /* Check the input parameters format */ + if (RTC_Format == RTC_Format_BIN) + { + /* Convert the Time structure parameters to Binary format */ + RTC_StampTimeStruct->RTC_Hours = (uint8_t)RTC_Bcd2ToByte(RTC_StampTimeStruct->RTC_Hours); + RTC_StampTimeStruct->RTC_Minutes = (uint8_t)RTC_Bcd2ToByte(RTC_StampTimeStruct->RTC_Minutes); + RTC_StampTimeStruct->RTC_Seconds = (uint8_t)RTC_Bcd2ToByte(RTC_StampTimeStruct->RTC_Seconds); + + /* Convert the Date structure parameters to Binary format */ + RTC_StampDateStruct->RTC_Month = (uint8_t)RTC_Bcd2ToByte(RTC_StampDateStruct->RTC_Month); + RTC_StampDateStruct->RTC_Date = (uint8_t)RTC_Bcd2ToByte(RTC_StampDateStruct->RTC_Date); + RTC_StampDateStruct->RTC_WeekDay = (uint8_t)RTC_Bcd2ToByte(RTC_StampDateStruct->RTC_WeekDay); + } +} + +/** + * @brief Gets the RTC timestamp Subseconds value. + * @param None + * @retval RTC current timestamp Subseconds value. + */ +uint32_t RTC_GetTimeStampSubSecond(void) +{ + /* Get timestamp subseconds values from the correspondent registers */ + return (uint32_t)(RTC->TSSSR); +} + +/** + * @} + */ + +/** @defgroup RTC_Group9 Tampers configuration functions + * @brief Tampers configuration functions + * +@verbatim + =============================================================================== + ##### Tampers configuration functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Configures the select Tamper pin edge. + * @param RTC_Tamper: Selected tamper pin. + * This parameter can be any combination of the following values: + * @arg RTC_Tamper_1: Select Tamper 1. + * @arg RTC_Tamper_2: Select Tamper 2. + * @arg RTC_Tamper_3: Select Tamper 3. + * @param RTC_TamperTrigger: Specifies the trigger on the tamper pin that + * stimulates tamper event. + * This parameter can be one of the following values: + * @arg RTC_TamperTrigger_RisingEdge: Rising Edge of the tamper pin causes tamper event. + * @arg RTC_TamperTrigger_FallingEdge: Falling Edge of the tamper pin causes tamper event. + * @arg RTC_TamperTrigger_LowLevel: Low Level of the tamper pin causes tamper event. + * @arg RTC_TamperTrigger_HighLevel: High Level of the tamper pin causes tamper event. + * @retval None + */ +void RTC_TamperTriggerConfig(uint32_t RTC_Tamper, uint32_t RTC_TamperTrigger) +{ + /* Check the parameters */ + assert_param(IS_RTC_TAMPER(RTC_Tamper)); + assert_param(IS_RTC_TAMPER_TRIGGER(RTC_TamperTrigger)); + + /* Check if the active level for Tamper is rising edge (Low level)*/ + if (RTC_TamperTrigger == RTC_TamperTrigger_RisingEdge) + { + /* Configure the RTC_TAFCR register */ + RTC->TAFCR &= (uint32_t)((uint32_t)~(RTC_Tamper << 1)); + } + else + { + /* Configure the RTC_TAFCR register */ + RTC->TAFCR |= (uint32_t)(RTC_Tamper << 1); + } +} + +/** + * @brief Enables or Disables the Tamper detection. + * @param RTC_Tamper: Selected tamper pin. + * This parameter can be any combination of the following values: + * @arg RTC_Tamper_1: Select Tamper 1. + * @arg RTC_Tamper_2: Select Tamper 2. + * @arg RTC_Tamper_3: Select Tamper 3. + * @param NewState: new state of the tamper pin. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_TamperCmd(uint32_t RTC_Tamper, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RTC_TAMPER(RTC_Tamper)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected Tamper pin */ + RTC->TAFCR |= (uint32_t)RTC_Tamper; + } + else + { + /* Disable the selected Tamper pin */ + RTC->TAFCR &= (uint32_t)~RTC_Tamper; + } +} + +/** + * @brief Configures the Tampers Filter. + * @param RTC_TamperFilter: Specifies the tampers filter. + * This parameter can be one of the following values: + * @arg RTC_TamperFilter_Disable: Tamper filter is disabled. + * @arg RTC_TamperFilter_2Sample: Tamper is activated after 2 consecutive + * samples at the active level + * @arg RTC_TamperFilter_4Sample: Tamper is activated after 4 consecutive + * samples at the active level + * @arg RTC_TamperFilter_8Sample: Tamper is activated after 8 consecutive + * samples at the active level + * @retval None + */ +void RTC_TamperFilterConfig(uint32_t RTC_TamperFilter) +{ + /* Check the parameters */ + assert_param(IS_RTC_TAMPER_FILTER(RTC_TamperFilter)); + + /* Clear TAMPFLT[1:0] bits in the RTC_TAFCR register */ + RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_TAMPFLT); + + /* Configure the RTC_TAFCR register */ + RTC->TAFCR |= (uint32_t)RTC_TamperFilter; +} + +/** + * @brief Configures the Tampers Sampling Frequency. + * @param RTC_TamperSamplingFreq: Specifies the tampers Sampling Frequency. + * This parameter can be one of the following values: + * @arg RTC_TamperSamplingFreq_RTCCLK_Div32768: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 32768 + * @arg RTC_TamperSamplingFreq_RTCCLK_Div16384: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 16384 + * @arg RTC_TamperSamplingFreq_RTCCLK_Div8192: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 8192 + * @arg RTC_TamperSamplingFreq_RTCCLK_Div4096: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 4096 + * @arg RTC_TamperSamplingFreq_RTCCLK_Div2048: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 2048 + * @arg RTC_TamperSamplingFreq_RTCCLK_Div1024: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 1024 + * @arg RTC_TamperSamplingFreq_RTCCLK_Div512: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 512 + * @arg RTC_TamperSamplingFreq_RTCCLK_Div256: Each of the tamper inputs are sampled + * with a frequency = RTCCLK / 256 + * @retval None + */ +void RTC_TamperSamplingFreqConfig(uint32_t RTC_TamperSamplingFreq) +{ + /* Check the parameters */ + assert_param(IS_RTC_TAMPER_SAMPLING_FREQ(RTC_TamperSamplingFreq)); + + /* Clear TAMPFREQ[2:0] bits in the RTC_TAFCR register */ + RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_TAMPFREQ); + + /* Configure the RTC_TAFCR register */ + RTC->TAFCR |= (uint32_t)RTC_TamperSamplingFreq; +} + +/** + * @brief Configures the Tampers Pins input Precharge Duration. + * @param RTC_TamperPrechargeDuration: Specifies the Tampers Pins input + * Precharge Duration. + * This parameter can be one of the following values: + * @arg RTC_TamperPrechargeDuration_1RTCCLK: Tamper pins are pre-charged before sampling during 1 RTCCLK cycle + * @arg RTC_TamperPrechargeDuration_2RTCCLK: Tamper pins are pre-charged before sampling during 2 RTCCLK cycle + * @arg RTC_TamperPrechargeDuration_4RTCCLK: Tamper pins are pre-charged before sampling during 4 RTCCLK cycle + * @arg RTC_TamperPrechargeDuration_8RTCCLK: Tamper pins are pre-charged before sampling during 8 RTCCLK cycle + * @retval None + */ +void RTC_TamperPinsPrechargeDuration(uint32_t RTC_TamperPrechargeDuration) +{ + /* Check the parameters */ + assert_param(IS_RTC_TAMPER_PRECHARGE_DURATION(RTC_TamperPrechargeDuration)); + + /* Clear TAMPPRCH[1:0] bits in the RTC_TAFCR register */ + RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_TAMPPRCH); + + /* Configure the RTC_TAFCR register */ + RTC->TAFCR |= (uint32_t)RTC_TamperPrechargeDuration; +} + +/** + * @brief Enables or Disables the TimeStamp on Tamper Detection Event. + * @note The timestamp is valid even the TSE bit in tamper control register + * is reset. + * @param NewState: new state of the timestamp on tamper event. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_TimeStampOnTamperDetectionCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Save timestamp on tamper detection event */ + RTC->TAFCR |= (uint32_t)RTC_TAFCR_TAMPTS; + } + else + { + /* Tamper detection does not cause a timestamp to be saved */ + RTC->TAFCR &= (uint32_t)~RTC_TAFCR_TAMPTS; + } +} + +/** + * @brief Enables or Disables the Precharge of Tamper pin. + * @param NewState: new state of tamper pull up. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_TamperPullUpCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable precharge of the selected Tamper pin */ + RTC->TAFCR &= (uint32_t)~RTC_TAFCR_TAMPPUDIS; + } + else + { + /* Disable precharge of the selected Tamper pin */ + RTC->TAFCR |= (uint32_t)RTC_TAFCR_TAMPPUDIS; + } +} + +/** + * @} + */ + +/** @defgroup RTC_Group10 Backup Data Registers configuration functions + * @brief Backup Data Registers configuration functions + * +@verbatim + =============================================================================== + ##### Backup Data Registers configuration functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Writes a data in a specified RTC Backup data register. + * @param RTC_BKP_DR: RTC Backup data Register number. + * This parameter can be: RTC_BKP_DRx where x can be from 0 to 15 to + * specify the register. + * @param Data: Data to be written in the specified RTC Backup data register. + * @retval None + */ +void RTC_WriteBackupRegister(uint32_t RTC_BKP_DR, uint32_t Data) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_RTC_BKP(RTC_BKP_DR)); + + tmp = RTC_BASE + 0x50; + tmp += (RTC_BKP_DR * 4); + + /* Write the specified register */ + *(__IO uint32_t *)tmp = (uint32_t)Data; +} + +/** + * @brief Reads data from the specified RTC Backup data Register. + * @param RTC_BKP_DR: RTC Backup data Register number. + * This parameter can be: RTC_BKP_DRx where x can be from 0 to 15 to + * specify the register. + * @retval None + */ +uint32_t RTC_ReadBackupRegister(uint32_t RTC_BKP_DR) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_RTC_BKP(RTC_BKP_DR)); + + tmp = RTC_BASE + 0x50; + tmp += (RTC_BKP_DR * 4); + + /* Read the specified register */ + return (*(__IO uint32_t *)tmp); +} + +/** + * @} + */ + +/** @defgroup RTC_Group11 Output Type Config configuration functions + * @brief Output Type Config configuration functions + * +@verbatim + =============================================================================== + ##### Output Type Config configuration functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Configures the RTC Output Pin mode. + * @param RTC_OutputType: specifies the RTC Output (PC13) pin mode. + * This parameter can be one of the following values: + * @arg RTC_OutputType_OpenDrain: RTC Output (PC13) is configured in + * Open Drain mode. + * @arg RTC_OutputType_PushPull: RTC Output (PC13) is configured in + * Push Pull mode. + * @retval None + */ +void RTC_OutputTypeConfig(uint32_t RTC_OutputType) +{ + /* Check the parameters */ + assert_param(IS_RTC_OUTPUT_TYPE(RTC_OutputType)); + + RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_ALARMOUTTYPE); + RTC->TAFCR |= (uint32_t)(RTC_OutputType); +} + +/** + * @} + */ + +/** @defgroup RTC_Group12 Shift control synchronisation functions + * @brief Shift control synchronisation functions + * +@verbatim + =============================================================================== + ##### Shift control synchronisation functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Configures the Synchronization Shift Control Settings. + * @note When REFCKON is set, firmware must not write to Shift control register + * @param RTC_ShiftAdd1S : Select to add or not 1 second to the time Calendar. + * This parameter can be one of the following values : + * @arg RTC_ShiftAdd1S_Set : Add one second to the clock calendar. + * @arg RTC_ShiftAdd1S_Reset: No effect. + * @param RTC_ShiftSubFS: Select the number of Second Fractions to Substitute. + * This parameter can be one any value from 0 to 0x7FFF. + * @retval An ErrorStatus enumeration value: + * - SUCCESS: RTC Shift registers are configured + * - ERROR: RTC Shift registers are not configured +*/ +ErrorStatus RTC_SynchroShiftConfig(uint32_t RTC_ShiftAdd1S, uint32_t RTC_ShiftSubFS) +{ + ErrorStatus status = ERROR; + uint32_t shpfcount = 0; + + /* Check the parameters */ + assert_param(IS_RTC_SHIFT_ADD1S(RTC_ShiftAdd1S)); + assert_param(IS_RTC_SHIFT_SUBFS(RTC_ShiftSubFS)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + /* Check if a Shift is pending*/ + if ((RTC->ISR & RTC_ISR_SHPF) != RESET) + { + /* Wait until the shift is completed*/ + while (((RTC->ISR & RTC_ISR_SHPF) != RESET) && (shpfcount != SHPF_TIMEOUT)) + { + shpfcount++; + } + } + + /* Check if the Shift pending is completed or if there is no Shift operation at all*/ + if ((RTC->ISR & RTC_ISR_SHPF) == RESET) + { + /* check if the reference clock detection is disabled */ + if((RTC->CR & RTC_CR_REFCKON) == RESET) + { + /* Configure the Shift settings */ + RTC->SHIFTR = (uint32_t)(uint32_t)(RTC_ShiftSubFS) | (uint32_t)(RTC_ShiftAdd1S); + + if(RTC_WaitForSynchro() == ERROR) + { + status = ERROR; + } + else + { + status = SUCCESS; + } + } + else + { + status = ERROR; + } + } + else + { + status = ERROR; + } + + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; + + return (ErrorStatus)(status); +} + +/** + * @} + */ + +/** @defgroup RTC_Group13 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + ##### Interrupts and flags management functions ##### + =============================================================================== + [..] All RTC interrupts are connected to the EXTI controller. + (+) To enable the RTC Alarm interrupt, the following sequence is required: + (++) Configure and enable the EXTI Line 17 in interrupt mode and select + the rising edge sensitivity using the EXTI_Init() function. + (++) Configure and enable the RTC_Alarm IRQ channel in the NVIC using + the NVIC_Init() function. + (++) Configure the RTC to generate RTC alarms (Alarm A and/or Alarm B) + using the RTC_SetAlarm() and RTC_AlarmCmd() functions. + (+) To enable the RTC Wakeup interrupt, the following sequence is required: + (++) Configure and enable the EXTI Line 20 in interrupt mode and select + the rising edge sensitivity using the EXTI_Init() function. + (++) Configure and enable the RTC_WKUP IRQ channel in the NVIC using + the NVIC_Init() function. + (++) Configure the RTC to generate the RTC wakeup timer event using the + RTC_WakeUpClockConfig(), RTC_SetWakeUpCounter() and RTC_WakeUpCmd() + functions. + (+) To enable the RTC Tamper interrupt, the following sequence is required: + (++) Configure and enable the EXTI Line 19 in interrupt mode and select + the rising edge sensitivity using the EXTI_Init() function. + (++) Configure and enable the TAMP_STAMP IRQ channel in the NVIC using + the NVIC_Init() function. + (++) Configure the RTC to detect the RTC tamper event using the + RTC_TamperTriggerConfig() and RTC_TamperCmd() functions. + (+) To enable the RTC TimeStamp interrupt, the following sequence is required: + (++) Configure and enable the EXTI Line 19 in interrupt mode and select + the rising edge sensitivity using the EXTI_Init() function. + (++) Configure and enable the TAMP_STAMP IRQ channel in the NVIC using + the NVIC_Init() function. + (++) Configure the RTC to detect the RTC time-stamp event using the + RTC_TimeStampCmd() functions. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified RTC interrupts. + * @param RTC_IT: specifies the RTC interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg RTC_IT_TS: Time Stamp interrupt mask + * @arg RTC_IT_WUT: WakeUp Timer interrupt mask + * @arg RTC_IT_ALRB: Alarm B interrupt mask + * @arg RTC_IT_ALRA: Alarm A interrupt mask + * @arg RTC_IT_TAMP: Tamper event interrupt mask + * @param NewState: new state of the specified RTC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_ITConfig(uint32_t RTC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RTC_CONFIG_IT(RTC_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Disable the write protection for RTC registers */ + RTC->WPR = 0xCA; + RTC->WPR = 0x53; + + if (NewState != DISABLE) + { + /* Configure the Interrupts in the RTC_CR register */ + RTC->CR |= (uint32_t)(RTC_IT & ~RTC_TAFCR_TAMPIE); + /* Configure the Tamper Interrupt in the RTC_TAFCR */ + RTC->TAFCR |= (uint32_t)(RTC_IT & RTC_TAFCR_TAMPIE); + } + else + { + /* Configure the Interrupts in the RTC_CR register */ + RTC->CR &= (uint32_t)~(RTC_IT & (uint32_t)~RTC_TAFCR_TAMPIE); + /* Configure the Tamper Interrupt in the RTC_TAFCR */ + RTC->TAFCR &= (uint32_t)~(RTC_IT & RTC_TAFCR_TAMPIE); + } + /* Enable the write protection for RTC registers */ + RTC->WPR = 0xFF; +} + +/** + * @brief Checks whether the specified RTC flag is set or not. + * @param RTC_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg RTC_FLAG_RECALPF: RECALPF event flag + * @arg RTC_FLAG_TAMP3F: Tamper 3 event flag + * @arg RTC_FLAG_TAMP2F: Tamper 2 event flag + * @arg RTC_FLAG_TAMP1F: Tamper 1 event flag + * @arg RTC_FLAG_TSOVF: Time Stamp OverFlow flag + * @arg RTC_FLAG_TSF: Time Stamp event flag + * @arg RTC_FLAG_WUTF: WakeUp Timer flag + * @arg RTC_FLAG_ALRBF: Alarm B flag + * @arg RTC_FLAG_ALRAF: Alarm A flag + * @arg RTC_FLAG_INITF: Initialization mode flag + * @arg RTC_FLAG_RSF: Registers Synchronized flag + * @arg RTC_FLAG_INITS: Registers Configured flag + * @argRTC_FLAG_SHPF : Shift operation pending flag. + * @arg RTC_FLAG_WUTWF: WakeUp Timer Write flag + * @arg RTC_FLAG_ALRBWF: Alarm B Write flag + * @arg RTC_FLAG_ALRAWF: Alarm A write flag + * @retval The new state of RTC_FLAG (SET or RESET). + */ +FlagStatus RTC_GetFlagStatus(uint32_t RTC_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_GET_FLAG(RTC_FLAG)); + + /* Get all the flags */ + tmpreg = (uint32_t)(RTC->ISR & RTC_FLAGS_MASK); + + /* Return the status of the flag */ + if ((tmpreg & RTC_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the RTC's pending flags. + * @param RTC_FLAG: specifies the RTC flag to clear. + * This parameter can be any combination of the following values: + * @arg RTC_FLAG_TAMP3F: Tamper 3 event flag + * @arg RTC_FLAG_TAMP2F: Tamper 2 event flag + * @arg RTC_FLAG_TAMP1F: Tamper 1 event flag + * @arg RTC_FLAG_TSOVF: Time Stamp Overflow flag + * @arg RTC_FLAG_TSF: Time Stamp event flag + * @arg RTC_FLAG_WUTF: WakeUp Timer flag + * @arg RTC_FLAG_ALRBF: Alarm B flag + * @arg RTC_FLAG_ALRAF: Alarm A flag + * @arg RTC_FLAG_RSF: Registers Synchronized flag + * @retval None + */ +void RTC_ClearFlag(uint32_t RTC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_RTC_CLEAR_FLAG(RTC_FLAG)); + + /* Clear the Flags in the RTC_ISR register */ + RTC->ISR = (uint32_t)((uint32_t)(~((RTC_FLAG | RTC_ISR_INIT)& 0x0001FFFF) | (uint32_t)(RTC->ISR & RTC_ISR_INIT))); +} + +/** + * @brief Checks whether the specified RTC interrupt has occurred or not. + * @param RTC_IT: specifies the RTC interrupt source to check. + * This parameter can be one of the following values: + * @arg RTC_IT_TS: Time Stamp interrupt + * @arg RTC_IT_WUT: WakeUp Timer interrupt + * @arg RTC_IT_ALRB: Alarm B interrupt + * @arg RTC_IT_ALRA: Alarm A interrupt + * @arg RTC_IT_TAMP1: Tamper1 event interrupt + * @arg RTC_IT_TAMP2: Tamper2 event interrupt + * @arg RTC_IT_TAMP3: Tamper3 event interrupt + * @retval The new state of RTC_IT (SET or RESET). + */ +ITStatus RTC_GetITStatus(uint32_t RTC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t tmpreg = 0, enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_RTC_GET_IT(RTC_IT)); + + /* Get the TAMPER Interrupt enable bit and pending bit */ + tmpreg = (uint32_t)(RTC->TAFCR & (RTC_TAFCR_TAMPIE)); + + /* Get the Interrupt enable Status */ + enablestatus = (uint32_t)((RTC->CR & RTC_IT) | (tmpreg & ((RTC_IT >> (RTC_IT >> 18)) >> 15))); + + /* Get the Interrupt pending bit */ + tmpreg = (uint32_t)((RTC->ISR & (uint32_t)(RTC_IT >> 4))); + + /* Get the status of the Interrupt */ + if ((enablestatus != (uint32_t)RESET) && ((tmpreg & 0x0000FFFF) != (uint32_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the RTC's interrupt pending bits. + * @param RTC_IT: specifies the RTC interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg RTC_IT_TS: Time Stamp interrupt + * @arg RTC_IT_WUT: WakeUp Timer interrupt + * @arg RTC_IT_ALRB: Alarm B interrupt + * @arg RTC_IT_ALRA: Alarm A interrupt + * @arg RTC_IT_TAMP1: Tamper1 event interrupt + * @arg RTC_IT_TAMP2: Tamper2 event interrupt + * @arg RTC_IT_TAMP3: Tamper3 event interrupt + * @retval None + */ +void RTC_ClearITPendingBit(uint32_t RTC_IT) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RTC_CLEAR_IT(RTC_IT)); + + /* Get the RTC_ISR Interrupt pending bits mask */ + tmpreg = (uint32_t)(RTC_IT >> 4); + + /* Clear the interrupt pending bits in the RTC_ISR register */ + RTC->ISR = (uint32_t)((uint32_t)(~((tmpreg | RTC_ISR_INIT)& 0x0000FFFF) | (uint32_t)(RTC->ISR & RTC_ISR_INIT))); +} + +/** + * @} + */ + +/** + * @brief Converts a 2 digit decimal to BCD format. + * @param Value: Byte to be converted. + * @retval Converted byte + */ +static uint8_t RTC_ByteToBcd2(uint8_t Value) +{ + uint8_t bcdhigh = 0; + + while (Value >= 10) + { + bcdhigh++; + Value -= 10; + } + + return ((uint8_t)(bcdhigh << 4) | Value); +} + +/** + * @brief Convert from 2 digit BCD to Binary. + * @param Value: BCD value to be converted. + * @retval Converted word + */ +static uint8_t RTC_Bcd2ToByte(uint8_t Value) +{ + uint8_t tmp = 0; + tmp = ((uint8_t)(Value & (uint8_t)0xF0) >> (uint8_t)0x4) * 10; + return (tmp + (Value & (uint8_t)0x0F)); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_spi.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_spi.c new file mode 100644 index 0000000..f6a5ca5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_spi.c @@ -0,0 +1,1410 @@ +/** + ****************************************************************************** + * @file stm32f30x_spi.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the Serial peripheral interface (SPI): + * + Initialization and Configuration + * + Data transfers functions + * + Hardware CRC Calculation + * + DMA transfers management + * + Interrupts and flags management + * + * @verbatim + + + =============================================================================== + ##### How to use this driver ##### + =============================================================================== + [..] + (#) Enable peripheral clock using RCC_APBPeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE) + function for SPI1 or using RCC_APBPeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE) + function for SPI2. + (#) Enable SCK, MOSI, MISO and NSS GPIO clocks using RCC_AHBPeriphClockCmd() + function. + (#) Peripherals alternate function: + (++) Connect the pin to the desired peripherals' Alternate + Function (AF) using GPIO_PinAFConfig() function. + (++) Configure the desired pin in alternate function by: + GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF. + (++) Select the type, pull-up/pull-down and output speed via + GPIO_PuPd, GPIO_OType and GPIO_Speed members. + (++) Call GPIO_Init() function. + (#) Program the Polarity, Phase, First Data, Baud Rate Prescaler, Slave + Management, Peripheral Mode and CRC Polynomial values using the SPI_Init() + function in SPI mode. In I2S mode, program the Mode, Standard, Data Format, + MCLK Output, Audio frequency and Polarity using I2S_Init() function. + (#) Configure the FIFO threshold using SPI_RxFIFOThresholdConfig() to select + at which threshold the RXNE event is generated. + (#) Enable the NVIC and the corresponding interrupt using the function + SPI_I2S_ITConfig() if you need to use interrupt mode. + (#) When using the DMA mode + (++) Configure the DMA using DMA_Init() function. + (++) Active the needed channel Request using SPI_I2S_DMACmd() function. + (#) Enable the SPI using the SPI_Cmd() function or enable the I2S using + I2S_Cmd(). + (#) Enable the DMA using the DMA_Cmd() function when using DMA mode. + (#) Optionally you can enable/configure the following parameters without + re-initialization (i.e there is no need to call again SPI_Init() function): + (++) When bidirectional mode (SPI_Direction_1Line_Rx or SPI_Direction_1Line_Tx) + is programmed as Data direction parameter using the SPI_Init() function + it can be possible to switch between SPI_Direction_Tx or SPI_Direction_Rx + using the SPI_BiDirectionalLineConfig() function. + (++) When SPI_NSS_Soft is selected as Slave Select Management parameter + using the SPI_Init() function it can be possible to manage the + NSS internal signal using the SPI_NSSInternalSoftwareConfig() function. + (++) Reconfigure the data size using the SPI_DataSizeConfig() function. + (++) Enable or disable the SS output using the SPI_SSOutputCmd() function. + (#) To use the CRC Hardware calculation feature refer to the Peripheral + CRC hardware Calculation subsection. + [..] It is possible to use SPI in I2S full duplex mode, in this case, each SPI + peripheral is able to manage sending and receiving data simultaneously + using two data lines. Each SPI peripheral has an extended block called I2Sxext + (ie. I2S2ext for SPI2 and I2S3ext for SPI3). + The extension block is not a full SPI IP, it is used only as I2S slave to + implement full duplex mode. The extension block uses the same clock sources + as its master. + To configure I2S full duplex you have to: + (#) Configure SPIx in I2S mode (I2S_Init() function) as described above. + (#) Call the I2S_FullDuplexConfig() function using the same strucutre passed to + I2S_Init() function. + (#) Call I2S_Cmd() for SPIx then for its extended block. + (#) Configure interrupts or DMA requests and to get/clear flag status, + use I2Sxext instance for the extension block. + [..] Functions that can be called with I2Sxext instances are: + I2S_Cmd(), I2S_FullDuplexConfig(), SPI_I2S_ReceiveData16(), SPI_I2S_SendData16(), + SPI_I2S_DMACmd(), SPI_I2S_ITConfig(), SPI_I2S_GetFlagStatus(), SPI_I2S_ClearFlag(), + SPI_I2S_GetITStatus() and SPI_I2S_ClearITPendingBit(). + [..] Example: To use SPI3 in Full duplex mode (SPI3 is Master Tx, I2S3ext is Slave Rx): + [..] RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI3, ENABLE); + I2S_StructInit(&I2SInitStruct); + I2SInitStruct.Mode = I2S_Mode_MasterTx; + I2S_Init(SPI3, &I2SInitStruct); + I2S_FullDuplexConfig(SPI3ext, &I2SInitStruct) + I2S_Cmd(SPI3, ENABLE); + I2S_Cmd(SPI3ext, ENABLE); + ... + while (SPI_I2S_GetFlagStatus(SPI2, SPI_FLAG_TXE) == RESET) + {} + SPI_I2S_SendData16(SPI3, txdata[i]); + ... + while (SPI_I2S_GetFlagStatus(I2S3ext, SPI_FLAG_RXNE) == RESET) + {} + rxdata[i] = SPI_I2S_ReceiveData16(I2S3ext); + ... + [..] + (@) In SPI mode: To use the SPI TI mode, call the function SPI_TIModeCmd() + just after calling the function SPI_Init(). + + @endverbatim + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_spi.h" +#include "stm32f30x_rcc.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup SPI + * @brief SPI driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* SPI registers Masks */ +#define CR1_CLEAR_MASK ((uint16_t)0x3040) +#define CR2_LDMA_MASK ((uint16_t)0x9FFF) + +#define I2SCFGR_CLEAR_MASK ((uint16_t)0xF040) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup SPI_Private_Functions + * @{ + */ + +/** @defgroup SPI_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] This section provides a set of functions allowing to initialize the SPI Direction, + SPI Mode, SPI Data Size, SPI Polarity, SPI Phase, SPI NSS Management, SPI Baud + Rate Prescaler, SPI First Bit and SPI CRC Polynomial. + [..] The SPI_Init() function follows the SPI configuration procedures for Master mode + and Slave mode (details for these procedures are available in reference manual). + [..] When the Software NSS management (SPI_InitStruct->SPI_NSS = SPI_NSS_Soft) is selected, + use the following function to manage the NSS bit: + void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft); + [..] In Master mode, when the Hardware NSS management (SPI_InitStruct->SPI_NSS = SPI_NSS_Hard) + is selected, use the follwoing function to enable the NSS output feature. + void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState); + [..] The NSS pulse mode can be managed by the SPI TI mode when enabling it using the + following function: void SPI_TIModeCmd(SPI_TypeDef* SPIx, FunctionalState NewState); + And it can be managed by software in the SPI Motorola mode using this function: + void SPI_NSSPulseModeCmd(SPI_TypeDef* SPIx, FunctionalState NewState); + [..] This section provides also functions to initialize the I2S Mode, Standard, + Data Format, MCLK Output, Audio frequency and Polarity. + [..] The I2S_Init() function follows the I2S configuration procedures for Master mode + and Slave mode. + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the SPIx peripheral registers to their default + * reset values. + * @param SPIx: To select the SPIx peripheral, where x can be: 1, 2 or 3 + * in SPI mode. + * @retval None + */ +void SPI_I2S_DeInit(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + if (SPIx == SPI1) + { + /* Enable SPI1 reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, ENABLE); + /* Release SPI1 from reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, DISABLE); + } + else if (SPIx == SPI2) + { + /* Enable SPI2 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE); + /* Release SPI2 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, DISABLE); + } + else + { + if (SPIx == SPI3) + { + /* Enable SPI3 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE); + /* Release SPI3 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, DISABLE); + } + } +} + +/** + * @brief Fills each SPI_InitStruct member with its default value. + * @param SPI_InitStruct: pointer to a SPI_InitTypeDef structure which will be initialized. + * @retval None + */ +void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct) +{ +/*--------------- Reset SPI init structure parameters values -----------------*/ + /* Initialize the SPI_Direction member */ + SPI_InitStruct->SPI_Direction = SPI_Direction_2Lines_FullDuplex; + /* Initialize the SPI_Mode member */ + SPI_InitStruct->SPI_Mode = SPI_Mode_Slave; + /* Initialize the SPI_DataSize member */ + SPI_InitStruct->SPI_DataSize = SPI_DataSize_8b; + /* Initialize the SPI_CPOL member */ + SPI_InitStruct->SPI_CPOL = SPI_CPOL_Low; + /* Initialize the SPI_CPHA member */ + SPI_InitStruct->SPI_CPHA = SPI_CPHA_1Edge; + /* Initialize the SPI_NSS member */ + SPI_InitStruct->SPI_NSS = SPI_NSS_Hard; + /* Initialize the SPI_BaudRatePrescaler member */ + SPI_InitStruct->SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2; + /* Initialize the SPI_FirstBit member */ + SPI_InitStruct->SPI_FirstBit = SPI_FirstBit_MSB; + /* Initialize the SPI_CRCPolynomial member */ + SPI_InitStruct->SPI_CRCPolynomial = 7; +} + +/** + * @brief Initializes the SPIx peripheral according to the specified + * parameters in the SPI_InitStruct. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_InitStruct: pointer to a SPI_InitTypeDef structure that + * contains the configuration information for the specified SPI peripheral. + * @retval None + */ +void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct) +{ + uint16_t tmpreg = 0; + + /* check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Check the SPI parameters */ + assert_param(IS_SPI_DIRECTION_MODE(SPI_InitStruct->SPI_Direction)); + assert_param(IS_SPI_MODE(SPI_InitStruct->SPI_Mode)); + assert_param(IS_SPI_DATA_SIZE(SPI_InitStruct->SPI_DataSize)); + assert_param(IS_SPI_CPOL(SPI_InitStruct->SPI_CPOL)); + assert_param(IS_SPI_CPHA(SPI_InitStruct->SPI_CPHA)); + assert_param(IS_SPI_NSS(SPI_InitStruct->SPI_NSS)); + assert_param(IS_SPI_BAUDRATE_PRESCALER(SPI_InitStruct->SPI_BaudRatePrescaler)); + assert_param(IS_SPI_FIRST_BIT(SPI_InitStruct->SPI_FirstBit)); + assert_param(IS_SPI_CRC_POLYNOMIAL(SPI_InitStruct->SPI_CRCPolynomial)); + + /* Configuring the SPI in master mode */ + if(SPI_InitStruct->SPI_Mode == SPI_Mode_Master) + { +/*---------------------------- SPIx CR1 Configuration ------------------------*/ + /* Get the SPIx CR1 value */ + tmpreg = SPIx->CR1; + /* Clear BIDIMode, BIDIOE, RxONLY, SSM, SSI, LSBFirst, BR, MSTR, CPOL and CPHA bits */ + tmpreg &= CR1_CLEAR_MASK; + /* Configure SPIx: direction, NSS management, first transmitted bit, BaudRate prescaler + master/slave mode, CPOL and CPHA */ + /* Set BIDImode, BIDIOE and RxONLY bits according to SPI_Direction value */ + /* Set SSM, SSI and MSTR bits according to SPI_Mode and SPI_NSS values */ + /* Set LSBFirst bit according to SPI_FirstBit value */ + /* Set BR bits according to SPI_BaudRatePrescaler value */ + /* Set CPOL bit according to SPI_CPOL value */ + /* Set CPHA bit according to SPI_CPHA value */ + tmpreg |= (uint16_t)((uint16_t)(SPI_InitStruct->SPI_Direction | SPI_InitStruct->SPI_Mode) | + (uint16_t)((uint16_t)(SPI_InitStruct->SPI_CPOL | SPI_InitStruct->SPI_CPHA) | + (uint16_t)((uint16_t)(SPI_InitStruct->SPI_NSS | SPI_InitStruct->SPI_BaudRatePrescaler) | + SPI_InitStruct->SPI_FirstBit))); + /* Write to SPIx CR1 */ + SPIx->CR1 = tmpreg; + /*-------------------------Data Size Configuration -----------------------*/ + /* Get the SPIx CR2 value */ + tmpreg = SPIx->CR2; + /* Clear DS[3:0] bits */ + tmpreg &= (uint16_t)~SPI_CR2_DS; + /* Configure SPIx: Data Size */ + tmpreg |= (uint16_t)(SPI_InitStruct->SPI_DataSize); + /* Write to SPIx CR2 */ + SPIx->CR2 = tmpreg; + } + /* Configuring the SPI in slave mode */ + else + { +/*---------------------------- Data size Configuration -----------------------*/ + /* Get the SPIx CR2 value */ + tmpreg = SPIx->CR2; + /* Clear DS[3:0] bits */ + tmpreg &= (uint16_t)~SPI_CR2_DS; + /* Configure SPIx: Data Size */ + tmpreg |= (uint16_t)(SPI_InitStruct->SPI_DataSize); + /* Write to SPIx CR2 */ + SPIx->CR2 = tmpreg; +/*---------------------------- SPIx CR1 Configuration ------------------------*/ + /* Get the SPIx CR1 value */ + tmpreg = SPIx->CR1; + /* Clear BIDIMode, BIDIOE, RxONLY, SSM, SSI, LSBFirst, BR, MSTR, CPOL and CPHA bits */ + tmpreg &= CR1_CLEAR_MASK; + /* Configure SPIx: direction, NSS management, first transmitted bit, BaudRate prescaler + master/salve mode, CPOL and CPHA */ + /* Set BIDImode, BIDIOE and RxONLY bits according to SPI_Direction value */ + /* Set SSM, SSI and MSTR bits according to SPI_Mode and SPI_NSS values */ + /* Set LSBFirst bit according to SPI_FirstBit value */ + /* Set BR bits according to SPI_BaudRatePrescaler value */ + /* Set CPOL bit according to SPI_CPOL value */ + /* Set CPHA bit according to SPI_CPHA value */ + tmpreg |= (uint16_t)((uint16_t)(SPI_InitStruct->SPI_Direction | SPI_InitStruct->SPI_Mode) | + (uint16_t)((uint16_t)(SPI_InitStruct->SPI_CPOL | SPI_InitStruct->SPI_CPHA) | + (uint16_t)((uint16_t)(SPI_InitStruct->SPI_NSS | SPI_InitStruct->SPI_BaudRatePrescaler) | + SPI_InitStruct->SPI_FirstBit))); + + /* Write to SPIx CR1 */ + SPIx->CR1 = tmpreg; + } + + /* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */ + SPIx->I2SCFGR &= (uint16_t)~((uint16_t)SPI_I2SCFGR_I2SMOD); + +/*---------------------------- SPIx CRCPOLY Configuration --------------------*/ + /* Write to SPIx CRCPOLY */ + SPIx->CRCPR = SPI_InitStruct->SPI_CRCPolynomial; +} + +/** + * @brief Fills each I2S_InitStruct member with its default value. + * @param I2S_InitStruct : pointer to a I2S_InitTypeDef structure which will be initialized. + * @retval None + */ +void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct) +{ +/*--------------- Reset I2S init structure parameters values -----------------*/ + /* Initialize the I2S_Mode member */ + I2S_InitStruct->I2S_Mode = I2S_Mode_SlaveTx; + + /* Initialize the I2S_Standard member */ + I2S_InitStruct->I2S_Standard = I2S_Standard_Phillips; + + /* Initialize the I2S_DataFormat member */ + I2S_InitStruct->I2S_DataFormat = I2S_DataFormat_16b; + + /* Initialize the I2S_MCLKOutput member */ + I2S_InitStruct->I2S_MCLKOutput = I2S_MCLKOutput_Disable; + + /* Initialize the I2S_AudioFreq member */ + I2S_InitStruct->I2S_AudioFreq = I2S_AudioFreq_Default; + + /* Initialize the I2S_CPOL member */ + I2S_InitStruct->I2S_CPOL = I2S_CPOL_Low; +} + +/** + * @brief Initializes the SPIx peripheral according to the specified + * parameters in the I2S_InitStruct. + * @param SPIx:To select the SPIx peripheral, where x can be: 2 or 3 + * in I2S mode. + * @param I2S_InitStruct: pointer to an I2S_InitTypeDef structure that + * contains the configuration information for the specified SPI peripheral + * configured in I2S mode. + * @note + * The function calculates the optimal prescaler needed to obtain the most + * accurate audio frequency (depending on the I2S clock source, the PLL values + * and the product configuration). But in case the prescaler value is greater + * than 511, the default value (0x02) will be configured instead. + * @retval None + */ +void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct) +{ + uint16_t tmpreg = 0, i2sdiv = 2, i2sodd = 0, packetlength = 1; + uint32_t tmp = 0; + RCC_ClocksTypeDef RCC_Clocks; + uint32_t sourceclock = 0; + + /* Check the I2S parameters */ + assert_param(IS_SPI_23_PERIPH(SPIx)); + assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode)); + assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard)); + assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat)); + assert_param(IS_I2S_MCLK_OUTPUT(I2S_InitStruct->I2S_MCLKOutput)); + assert_param(IS_I2S_AUDIO_FREQ(I2S_InitStruct->I2S_AudioFreq)); + assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL)); + +/*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/ + /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */ + SPIx->I2SCFGR &= I2SCFGR_CLEAR_MASK; + SPIx->I2SPR = 0x0002; + + /* Get the I2SCFGR register value */ + tmpreg = SPIx->I2SCFGR; + + /* If the default value has to be written, reinitialize i2sdiv and i2sodd*/ + if(I2S_InitStruct->I2S_AudioFreq == I2S_AudioFreq_Default) + { + i2sodd = (uint16_t)0; + i2sdiv = (uint16_t)2; + } + /* If the requested audio frequency is not the default, compute the prescaler */ + else + { + /* Check the frame length (For the Prescaler computing) */ + if(I2S_InitStruct->I2S_DataFormat == I2S_DataFormat_16b) + { + /* Packet length is 16 bits */ + packetlength = 1; + } + else + { + /* Packet length is 32 bits */ + packetlength = 2; + } + + /* I2S Clock source is System clock: Get System Clock frequency */ + RCC_GetClocksFreq(&RCC_Clocks); + + /* Get the source clock value: based on System Clock value */ + sourceclock = RCC_Clocks.SYSCLK_Frequency; + + /* Compute the Real divider depending on the MCLK output state with a floating point */ + if(I2S_InitStruct->I2S_MCLKOutput == I2S_MCLKOutput_Enable) + { + /* MCLK output is enabled */ + tmp = (uint16_t)(((((sourceclock / 256) * 10) / I2S_InitStruct->I2S_AudioFreq)) + 5); + } + else + { + /* MCLK output is disabled */ + tmp = (uint16_t)(((((sourceclock / (32 * packetlength)) *10 ) / I2S_InitStruct->I2S_AudioFreq)) + 5); + } + + /* Remove the floating point */ + tmp = tmp / 10; + + /* Check the parity of the divider */ + i2sodd = (uint16_t)(tmp & (uint16_t)0x0001); + + /* Compute the i2sdiv prescaler */ + i2sdiv = (uint16_t)((tmp - i2sodd) / 2); + + /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */ + i2sodd = (uint16_t) (i2sodd << 8); + } + + /* Test if the divider is 1 or 0 or greater than 0xFF */ + if ((i2sdiv < 2) || (i2sdiv > 0xFF)) + { + /* Set the default values */ + i2sdiv = 2; + i2sodd = 0; + } + + /* Write to SPIx I2SPR register the computed value */ + SPIx->I2SPR = (uint16_t)(i2sdiv | (uint16_t)(i2sodd | (uint16_t)I2S_InitStruct->I2S_MCLKOutput)); + + /* Configure the I2S with the SPI_InitStruct values */ + tmpreg |= (uint16_t)((uint16_t)(SPI_I2SCFGR_I2SMOD | I2S_InitStruct->I2S_Mode) | \ + (uint16_t)((uint16_t)((uint16_t)(I2S_InitStruct->I2S_Standard |I2S_InitStruct->I2S_DataFormat) |\ + I2S_InitStruct->I2S_CPOL))); + + /* Write to SPIx I2SCFGR */ + SPIx->I2SCFGR = tmpreg; +} + +/** + * @brief Enables or disables the specified SPI peripheral. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected SPI peripheral */ + SPIx->CR1 |= SPI_CR1_SPE; + } + else + { + /* Disable the selected SPI peripheral */ + SPIx->CR1 &= (uint16_t)~((uint16_t)SPI_CR1_SPE); + } +} + +/** + * @brief Enables or disables the TI Mode. + * @note This function can be called only after the SPI_Init() function has + * been called. + * @note When TI mode is selected, the control bits SSM, SSI, CPOL and CPHA + * are not taken into consideration and are configured by hardware + * respectively to the TI mode requirements. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the selected SPI TI communication mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_TIModeCmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the TI mode for the selected SPI peripheral */ + SPIx->CR2 |= SPI_CR2_FRF; + } + else + { + /* Disable the TI mode for the selected SPI peripheral */ + SPIx->CR2 &= (uint16_t)~((uint16_t)SPI_CR2_FRF); + } +} + +/** + * @brief Enables or disables the specified SPI peripheral (in I2S mode). + * @param SPIx:To select the SPIx peripheral, where x can be: 2 or 3 in + * I2S mode or I2Sxext for I2S full duplex mode. + * @param NewState: new state of the SPIx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_23_PERIPH_EXT(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI peripheral in I2S mode */ + SPIx->I2SCFGR |= SPI_I2SCFGR_I2SE; + } + else + { + /* Disable the selected SPI peripheral in I2S mode */ + SPIx->I2SCFGR &= (uint16_t)~((uint16_t)SPI_I2SCFGR_I2SE); + } +} + +/** + * @brief Configures the data size for the selected SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_DataSize: specifies the SPI data size. + * For the SPIx peripheral this parameter can be one of the following values: + * @arg SPI_DataSize_4b: Set data size to 4 bits + * @arg SPI_DataSize_5b: Set data size to 5 bits + * @arg SPI_DataSize_6b: Set data size to 6 bits + * @arg SPI_DataSize_7b: Set data size to 7 bits + * @arg SPI_DataSize_8b: Set data size to 8 bits + * @arg SPI_DataSize_9b: Set data size to 9 bits + * @arg SPI_DataSize_10b: Set data size to 10 bits + * @arg SPI_DataSize_11b: Set data size to 11 bits + * @arg SPI_DataSize_12b: Set data size to 12 bits + * @arg SPI_DataSize_13b: Set data size to 13 bits + * @arg SPI_DataSize_14b: Set data size to 14 bits + * @arg SPI_DataSize_15b: Set data size to 15 bits + * @arg SPI_DataSize_16b: Set data size to 16 bits + * @retval None + */ +void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize) +{ + uint16_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_DATA_SIZE(SPI_DataSize)); + /* Read the CR2 register */ + tmpreg = SPIx->CR2; + /* Clear DS[3:0] bits */ + tmpreg &= (uint16_t)~SPI_CR2_DS; + /* Set new DS[3:0] bits value */ + tmpreg |= SPI_DataSize; + SPIx->CR2 = tmpreg; +} + +/** + * @brief Configures the FIFO reception threshold for the selected SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_RxFIFOThreshold: specifies the FIFO reception threshold. + * This parameter can be one of the following values: + * @arg SPI_RxFIFOThreshold_HF: RXNE event is generated if the FIFO + * level is greater or equal to 1/2. + * @arg SPI_RxFIFOThreshold_QF: RXNE event is generated if the FIFO + * level is greater or equal to 1/4. + * @retval None + */ +void SPI_RxFIFOThresholdConfig(SPI_TypeDef* SPIx, uint16_t SPI_RxFIFOThreshold) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_RX_FIFO_THRESHOLD(SPI_RxFIFOThreshold)); + + /* Clear FRXTH bit */ + SPIx->CR2 &= (uint16_t)~((uint16_t)SPI_CR2_FRXTH); + + /* Set new FRXTH bit value */ + SPIx->CR2 |= SPI_RxFIFOThreshold; +} + +/** + * @brief Selects the data transfer direction in bidirectional mode for the specified SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_Direction: specifies the data transfer direction in bidirectional mode. + * This parameter can be one of the following values: + * @arg SPI_Direction_Tx: Selects Tx transmission direction + * @arg SPI_Direction_Rx: Selects Rx receive direction + * @retval None + */ +void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_DIRECTION(SPI_Direction)); + if (SPI_Direction == SPI_Direction_Tx) + { + /* Set the Tx only mode */ + SPIx->CR1 |= SPI_Direction_Tx; + } + else + { + /* Set the Rx only mode */ + SPIx->CR1 &= SPI_Direction_Rx; + } +} + +/** + * @brief Configures internally by software the NSS pin for the selected SPI. + * @note This function can be called only after the SPI_Init() function has + * been called. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_NSSInternalSoft: specifies the SPI NSS internal state. + * This parameter can be one of the following values: + * @arg SPI_NSSInternalSoft_Set: Set NSS pin internally + * @arg SPI_NSSInternalSoft_Reset: Reset NSS pin internally + * @retval None + */ +void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_NSS_INTERNAL(SPI_NSSInternalSoft)); + + if (SPI_NSSInternalSoft != SPI_NSSInternalSoft_Reset) + { + /* Set NSS pin internally by software */ + SPIx->CR1 |= SPI_NSSInternalSoft_Set; + } + else + { + /* Reset NSS pin internally by software */ + SPIx->CR1 &= SPI_NSSInternalSoft_Reset; + } +} + +/** + * @brief Configures the full duplex mode for the I2Sx peripheral using its + * extension I2Sxext according to the specified parameters in the + * I2S_InitStruct. + * @param I2Sxext: where x can be 2 or 3 to select the I2S peripheral extension block. + * @param I2S_InitStruct: pointer to an I2S_InitTypeDef structure that + * contains the configuration information for the specified I2S peripheral + * extension. + * + * @note The structure pointed by I2S_InitStruct parameter should be the same + * used for the master I2S peripheral. In this case, if the master is + * configured as transmitter, the slave will be receiver and vice versa. + * Or you can force a different mode by modifying the field I2S_Mode to the + * value I2S_SlaveRx or I2S_SlaveTx indepedently of the master configuration. + * + * @note The I2S full duplex extension can be configured in slave mode only. + * + * @retval None + */ +void I2S_FullDuplexConfig(SPI_TypeDef* I2Sxext, I2S_InitTypeDef* I2S_InitStruct) +{ + uint16_t tmpreg = 0, tmp = 0; + + /* Check the I2S parameters */ + assert_param(IS_I2S_EXT_PERIPH(I2Sxext)); + assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode)); + assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard)); + assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat)); + assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL)); + +/*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/ + /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */ + I2Sxext->I2SCFGR &= I2SCFGR_CLEAR_MASK; + I2Sxext->I2SPR = 0x0002; + + /* Get the I2SCFGR register value */ + tmpreg = I2Sxext->I2SCFGR; + + /* Get the mode to be configured for the extended I2S */ + if ((I2S_InitStruct->I2S_Mode == I2S_Mode_MasterTx) || (I2S_InitStruct->I2S_Mode == I2S_Mode_SlaveTx)) + { + tmp = I2S_Mode_SlaveRx; + } + else + { + if ((I2S_InitStruct->I2S_Mode == I2S_Mode_MasterRx) || (I2S_InitStruct->I2S_Mode == I2S_Mode_SlaveRx)) + { + tmp = I2S_Mode_SlaveTx; + } + } + + + /* Configure the I2S with the SPI_InitStruct values */ + tmpreg |= (uint16_t)((uint16_t)SPI_I2SCFGR_I2SMOD | (uint16_t)(tmp | \ + (uint16_t)(I2S_InitStruct->I2S_Standard | (uint16_t)(I2S_InitStruct->I2S_DataFormat | \ + (uint16_t)I2S_InitStruct->I2S_CPOL)))); + + /* Write to SPIx I2SCFGR */ + I2Sxext->I2SCFGR = tmpreg; +} + +/** + * @brief Enables or disables the SS output for the selected SPI. + * @note This function can be called only after the SPI_Init() function has + * been called and the NSS hardware management mode is selected. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx SS output. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI SS output */ + SPIx->CR2 |= (uint16_t)SPI_CR2_SSOE; + } + else + { + /* Disable the selected SPI SS output */ + SPIx->CR2 &= (uint16_t)~((uint16_t)SPI_CR2_SSOE); + } +} + +/** + * @brief Enables or disables the NSS pulse management mode. + * @note This function can be called only after the SPI_Init() function has + * been called. + * @note When TI mode is selected, the control bits NSSP is not taken into + * consideration and are configured by hardware respectively to the + * TI mode requirements. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the NSS pulse management mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_NSSPulseModeCmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the NSS pulse management mode */ + SPIx->CR2 |= SPI_CR2_NSSP; + } + else + { + /* Disable the NSS pulse management mode */ + SPIx->CR2 &= (uint16_t)~((uint16_t)SPI_CR2_NSSP); + } +} + +/** + * @} + */ + +/** @defgroup SPI_Group2 Data transfers functions + * @brief Data transfers functions + * +@verbatim + =============================================================================== + ##### Data transfers functions ##### + =============================================================================== + [..] This section provides a set of functions allowing to manage the SPI or I2S + data transfers. + [..] In reception, data are received and then stored into an internal Rx buffer while + In transmission, data are first stored into an internal Tx buffer before being + transmitted. + [..] The read access of the SPI_DR register can be done using the SPI_I2S_ReceiveData() + function and returns the Rx buffered value. Whereas a write access to the SPI_DR + can be done using SPI_I2S_SendData() function and stores the written data into + Tx buffer. + +@endverbatim + * @{ + */ + +/** + * @brief Transmits a Data through the SPIx peripheral. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param Data: Data to be transmitted. + * @retval None + */ +void SPI_SendData8(SPI_TypeDef* SPIx, uint8_t Data) +{ + uint32_t spixbase = 0x00; + + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + spixbase = (uint32_t)SPIx; + spixbase += 0x0C; + + *(__IO uint8_t *) spixbase = Data; +} + +/** + * @brief Transmits a Data through the SPIx/I2Sx peripheral. + * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. + * @param Data: Data to be transmitted. + * @retval None + */ +void SPI_I2S_SendData16(SPI_TypeDef* SPIx, uint16_t Data) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + + SPIx->DR = (uint16_t)Data; +} + +/** + * @brief Returns the most recent received data by the SPIx peripheral. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval The value of the received data. + */ +uint8_t SPI_ReceiveData8(SPI_TypeDef* SPIx) +{ + uint32_t spixbase = 0x00; + + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + + spixbase = (uint32_t)SPIx; + spixbase += 0x0C; + + return *(__IO uint8_t *) spixbase; +} + +/** + * @brief Returns the most recent received data by the SPIx peripheral. + * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. + * @retval The value of the received data. + */ +uint16_t SPI_I2S_ReceiveData16(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + + return SPIx->DR; +} +/** + * @} + */ + +/** @defgroup SPI_Group3 Hardware CRC Calculation functions + * @brief Hardware CRC Calculation functions + * +@verbatim + =============================================================================== + ##### Hardware CRC Calculation functions ##### + =============================================================================== + [..] This section provides a set of functions allowing to manage the SPI CRC hardware + calculation. + [..] SPI communication using CRC is possible through the following procedure: + (#) Program the Data direction, Polarity, Phase, First Data, Baud Rate Prescaler, + Slave Management, Peripheral Mode and CRC Polynomial values using the SPI_Init() + function. + (#) Enable the CRC calculation using the SPI_CalculateCRC() function. + (#) Enable the SPI using the SPI_Cmd() function + (#) Before writing the last data to the TX buffer, set the CRCNext bit using the + SPI_TransmitCRC() function to indicate that after transmission of the last + data, the CRC should be transmitted. + (#) After transmitting the last data, the SPI transmits the CRC. The SPI_CR1_CRCNEXT + bit is reset. The CRC is also received and compared against the SPI_RXCRCR + value. + If the value does not match, the SPI_FLAG_CRCERR flag is set and an interrupt + can be generated when the SPI_I2S_IT_ERR interrupt is enabled. + [..] + (@) + (+@) It is advised to don't read the calculate CRC values during the communication. + (+@) When the SPI is in slave mode, be careful to enable CRC calculation only + when the clock is stable, that is, when the clock is in the steady state. + If not, a wrong CRC calculation may be done. In fact, the CRC is sensitive + to the SCK slave input clock as soon as CRCEN is set, and this, whatever + the value of the SPE bit. + (+@) With high bitrate frequencies, be careful when transmitting the CRC. + As the number of used CPU cycles has to be as low as possible in the CRC + transfer phase, it is forbidden to call software functions in the CRC + transmission sequence to avoid errors in the last data and CRC reception. + In fact, CRCNEXT bit has to be written before the end of the transmission/reception + of the last data. + (+@) For high bit rate frequencies, it is advised to use the DMA mode to avoid the + degradation of the SPI speed performance due to CPU accesses impacting the + SPI bandwidth. + (+@) When the STM32F30x are configured as slaves and the NSS hardware mode is + used, the NSS pin needs to be kept low between the data phase and the CRC + phase. + (+@) When the SPI is configured in slave mode with the CRC feature enabled, CRC + calculation takes place even if a high level is applied on the NSS pin. + This may happen for example in case of a multislave environment where the + communication master addresses slaves alternately. + (+@) Between a slave deselection (high level on NSS) and a new slave selection + (low level on NSS), the CRC value should be cleared on both master and slave + sides in order to resynchronize the master and slave for their respective + CRC calculation. + [..] + (@) To clear the CRC, follow the procedure below: + (#@) Disable SPI using the SPI_Cmd() function. + (#@) Disable the CRC calculation using the SPI_CalculateCRC() function. + (#@) Enable the CRC calculation using the SPI_CalculateCRC() function. + (#@) Enable SPI using the SPI_Cmd() function. + +@endverbatim + * @{ + */ + +/** + * @brief Configures the CRC calculation length for the selected SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_CRCLength: specifies the SPI CRC calculation length. + * This parameter can be one of the following values: + * @arg SPI_CRCLength_8b: Set CRC Calculation to 8 bits + * @arg SPI_CRCLength_16b: Set CRC Calculation to 16 bits + * @retval None + */ +void SPI_CRCLengthConfig(SPI_TypeDef* SPIx, uint16_t SPI_CRCLength) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_CRC_LENGTH(SPI_CRCLength)); + + /* Clear CRCL bit */ + SPIx->CR1 &= (uint16_t)~((uint16_t)SPI_CR1_CRCL); + + /* Set new CRCL bit value */ + SPIx->CR1 |= SPI_CRCLength; +} + +/** + * @brief Enables or disables the CRC value calculation of the transferred bytes. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx CRC value calculation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected SPI CRC calculation */ + SPIx->CR1 |= SPI_CR1_CRCEN; + } + else + { + /* Disable the selected SPI CRC calculation */ + SPIx->CR1 &= (uint16_t)~((uint16_t)SPI_CR1_CRCEN); + } +} + +/** + * @brief Transmits the SPIx CRC value. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval None + */ +void SPI_TransmitCRC(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Enable the selected SPI CRC transmission */ + SPIx->CR1 |= SPI_CR1_CRCNEXT; +} + +/** + * @brief Returns the transmit or the receive CRC register value for the specified SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_CRC: specifies the CRC register to be read. + * This parameter can be one of the following values: + * @arg SPI_CRC_Tx: Selects Tx CRC register + * @arg SPI_CRC_Rx: Selects Rx CRC register + * @retval The selected CRC register value.. + */ +uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC) +{ + uint16_t crcreg = 0; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_CRC(SPI_CRC)); + + if (SPI_CRC != SPI_CRC_Rx) + { + /* Get the Tx CRC register */ + crcreg = SPIx->TXCRCR; + } + else + { + /* Get the Rx CRC register */ + crcreg = SPIx->RXCRCR; + } + /* Return the selected CRC register */ + return crcreg; +} + +/** + * @brief Returns the CRC Polynomial register value for the specified SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval The CRC Polynomial register value. + */ +uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Return the CRC polynomial register */ + return SPIx->CRCPR; +} + +/** + * @} + */ + +/** @defgroup SPI_Group4 DMA transfers management functions + * @brief DMA transfers management functions + * +@verbatim + =============================================================================== + ##### DMA transfers management functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the SPIx/I2Sx DMA interface. + * @param SPIx:To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. + * @param SPI_I2S_DMAReq: specifies the SPI DMA transfer request to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg SPI_I2S_DMAReq_Tx: Tx buffer DMA transfer request + * @arg SPI_I2S_DMAReq_Rx: Rx buffer DMA transfer request + * @param NewState: new state of the selected SPI DMA transfer request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_SPI_I2S_DMA_REQ(SPI_I2S_DMAReq)); + + if (NewState != DISABLE) + { + /* Enable the selected SPI DMA requests */ + SPIx->CR2 |= SPI_I2S_DMAReq; + } + else + { + /* Disable the selected SPI DMA requests */ + SPIx->CR2 &= (uint16_t)~SPI_I2S_DMAReq; + } +} + +/** + * @brief Configures the number of data to transfer type(Even/Odd) for the DMA + * last transfers and for the selected SPI. + * @note This function have a meaning only if DMA mode is selected and if + * the packing mode is used (data length <= 8 and DMA transfer size halfword) + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_LastDMATransfer: specifies the SPI last DMA transfers state. + * This parameter can be one of the following values: + * @arg SPI_LastDMATransfer_TxEvenRxEven: Number of data for transmission Even + * and number of data for reception Even. + * @arg SPI_LastDMATransfer_TxOddRxEven: Number of data for transmission Odd + * and number of data for reception Even. + * @arg SPI_LastDMATransfer_TxEvenRxOdd: Number of data for transmission Even + * and number of data for reception Odd. + * @arg SPI_LastDMATransfer_TxOddRxOdd: RNumber of data for transmission Odd + * and number of data for reception Odd. + * @retval None + */ +void SPI_LastDMATransferCmd(SPI_TypeDef* SPIx, uint16_t SPI_LastDMATransfer) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_LAST_DMA_TRANSFER(SPI_LastDMATransfer)); + + /* Clear LDMA_TX and LDMA_RX bits */ + SPIx->CR2 &= CR2_LDMA_MASK; + + /* Set new LDMA_TX and LDMA_RX bits value */ + SPIx->CR2 |= SPI_LastDMATransfer; +} + +/** + * @} + */ + +/** @defgroup SPI_Group5 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + ##### Interrupts and flags management functions ##### + =============================================================================== + [..] This section provides a set of functions allowing to configure the SPI/I2S + Interrupts sources and check or clear the flags or pending bits status. + The user should identify which mode will be used in his application to manage + the communication: Polling mode, Interrupt mode or DMA mode. + + *** Polling Mode *** + ==================== + [..] In Polling Mode, the SPI/I2S communication can be managed by 9 flags: + (#) SPI_I2S_FLAG_TXE : to indicate the status of the transmit buffer register. + (#) SPI_I2S_FLAG_RXNE : to indicate the status of the receive buffer register. + (#) SPI_I2S_FLAG_BSY : to indicate the state of the communication layer of the SPI. + (#) SPI_FLAG_CRCERR : to indicate if a CRC Calculation error occur. + (#) SPI_FLAG_MODF : to indicate if a Mode Fault error occur. + (#) SPI_I2S_FLAG_OVR : to indicate if an Overrun error occur. + (#) SPI_I2S_FLAG_FRE: to indicate a Frame Format error occurs. + (#) I2S_FLAG_UDR: to indicate an Underrun error occurs. + (#) I2S_FLAG_CHSIDE: to indicate Channel Side. + [..] + (@) Do not use the BSY flag to handle each data transmission or reception. + It is better to use the TXE and RXNE flags instead. + [..] In this Mode it is advised to use the following functions: + (+) FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); + (+) void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); + + *** Interrupt Mode *** + ====================== + [..] In Interrupt Mode, the SPI/I2S communication can be managed by 3 interrupt sources + and 5 pending bits: + [..] Pending Bits: + (#) SPI_I2S_IT_TXE : to indicate the status of the transmit buffer register. + (#) SPI_I2S_IT_RXNE : to indicate the status of the receive buffer register. + (#) SPI_I2S_IT_OVR : to indicate if an Overrun error occur. + (#) I2S_IT_UDR : to indicate an Underrun Error occurs. + (#) SPI_I2S_FLAG_FRE : to indicate a Frame Format error occurs. + [..] Interrupt Source: + (#) SPI_I2S_IT_TXE: specifies the interrupt source for the Tx buffer empty + interrupt. + (#) SPI_I2S_IT_RXNE : specifies the interrupt source for the Rx buffer not + empty interrupt. + (#) SPI_I2S_IT_ERR : specifies the interrupt source for the errors interrupt. + [..] In this Mode it is advised to use the following functions: + (+) void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState); + (+) ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT); + + *** FIFO Status *** + =================== + [..] It is possible to monitor the FIFO status when a transfer is ongoing using the + following function: + (+) uint32_t SPI_GetFIFOStatus(uint8_t SPI_FIFO_Direction); + + *** DMA Mode *** + ================ + [..] In DMA Mode, the SPI communication can be managed by 2 DMA Channel requests: + (#) SPI_I2S_DMAReq_Tx: specifies the Tx buffer DMA transfer request. + (#) SPI_I2S_DMAReq_Rx: specifies the Rx buffer DMA transfer request. + [..] In this Mode it is advised to use the following function: + (+) void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState); + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified SPI/I2S interrupts. + * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. + * @param SPI_I2S_IT: specifies the SPI interrupt source to be enabled or disabled. + * This parameter can be one of the following values: + * @arg SPI_I2S_IT_TXE: Tx buffer empty interrupt mask + * @arg SPI_I2S_IT_RXNE: Rx buffer not empty interrupt mask + * @arg SPI_I2S_IT_ERR: Error interrupt mask + * @param NewState: new state of the specified SPI interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState) +{ + uint16_t itpos = 0, itmask = 0 ; + + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_SPI_I2S_CONFIG_IT(SPI_I2S_IT)); + + /* Get the SPI IT index */ + itpos = SPI_I2S_IT >> 4; + + /* Set the IT mask */ + itmask = (uint16_t)1 << (uint16_t)itpos; + + if (NewState != DISABLE) + { + /* Enable the selected SPI interrupt */ + SPIx->CR2 |= itmask; + } + else + { + /* Disable the selected SPI interrupt */ + SPIx->CR2 &= (uint16_t)~itmask; + } +} + +/** + * @brief Returns the current SPIx Transmission FIFO filled level. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval The Transmission FIFO filling state. + * - SPI_TransmissionFIFOStatus_Empty: when FIFO is empty + * - SPI_TransmissionFIFOStatus_1QuarterFull: if more than 1 quarter-full. + * - SPI_TransmissionFIFOStatus_HalfFull: if more than 1 half-full. + * - SPI_TransmissionFIFOStatus_Full: when FIFO is full. + */ +uint16_t SPI_GetTransmissionFIFOStatus(SPI_TypeDef* SPIx) +{ + /* Get the SPIx Transmission FIFO level bits */ + return (uint16_t)((SPIx->SR & SPI_SR_FTLVL)); +} + +/** + * @brief Returns the current SPIx Reception FIFO filled level. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval The Reception FIFO filling state. + * - SPI_ReceptionFIFOStatus_Empty: when FIFO is empty + * - SPI_ReceptionFIFOStatus_1QuarterFull: if more than 1 quarter-full. + * - SPI_ReceptionFIFOStatus_HalfFull: if more than 1 half-full. + * - SPI_ReceptionFIFOStatus_Full: when FIFO is full. + */ +uint16_t SPI_GetReceptionFIFOStatus(SPI_TypeDef* SPIx) +{ + /* Get the SPIx Reception FIFO level bits */ + return (uint16_t)((SPIx->SR & SPI_SR_FRLVL)); +} + +/** + * @brief Checks whether the specified SPI flag is set or not. + * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. + * @param SPI_I2S_FLAG: specifies the SPI flag to check. + * This parameter can be one of the following values: + * @arg SPI_I2S_FLAG_TXE: Transmit buffer empty flag. + * @arg SPI_I2S_FLAG_RXNE: Receive buffer not empty flag. + * @arg SPI_I2S_FLAG_BSY: Busy flag. + * @arg SPI_I2S_FLAG_OVR: Overrun flag. + * @arg SPI_I2S_FLAG_MODF: Mode Fault flag. + * @arg SPI_I2S_FLAG_CRCERR: CRC Error flag. + * @arg SPI_I2S_FLAG_FRE: TI frame format error flag. + * @arg I2S_FLAG_UDR: Underrun Error flag. + * @arg I2S_FLAG_CHSIDE: Channel Side flag. + * @retval The new state of SPI_I2S_FLAG (SET or RESET). + */ +FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + assert_param(IS_SPI_I2S_GET_FLAG(SPI_I2S_FLAG)); + + /* Check the status of the specified SPI flag */ + if ((SPIx->SR & SPI_I2S_FLAG) != (uint16_t)RESET) + { + /* SPI_I2S_FLAG is set */ + bitstatus = SET; + } + else + { + /* SPI_I2S_FLAG is reset */ + bitstatus = RESET; + } + /* Return the SPI_I2S_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the SPIx CRC Error (CRCERR) flag. + * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. + * @param SPI_I2S_FLAG: specifies the SPI flag to clear. + * This function clears only CRCERR flag. + * @note OVR (OverRun error) flag is cleared by software sequence: a read + * operation to SPI_DR register (SPI_I2S_ReceiveData()) followed by a read + * operation to SPI_SR register (SPI_I2S_GetFlagStatus()). + * @note MODF (Mode Fault) flag is cleared by software sequence: a read/write + * operation to SPI_SR register (SPI_I2S_GetFlagStatus()) followed by a + * write operation to SPI_CR1 register (SPI_Cmd() to enable the SPI). + * @retval None + */ +void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + assert_param(IS_SPI_CLEAR_FLAG(SPI_I2S_FLAG)); + + /* Clear the selected SPI CRC Error (CRCERR) flag */ + SPIx->SR = (uint16_t)~SPI_I2S_FLAG; +} + +/** + * @brief Checks whether the specified SPI/I2S interrupt has occurred or not. + * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3 + * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. + * @param SPI_I2S_IT: specifies the SPI interrupt source to check. + * This parameter can be one of the following values: + * @arg SPI_I2S_IT_TXE: Transmit buffer empty interrupt. + * @arg SPI_I2S_IT_RXNE: Receive buffer not empty interrupt. + * @arg SPI_IT_MODF: Mode Fault interrupt. + * @arg SPI_I2S_IT_OVR: Overrun interrupt. + * @arg I2S_IT_UDR: Underrun interrupt. + * @arg SPI_I2S_IT_FRE: Format Error interrupt. + * @retval The new state of SPI_I2S_IT (SET or RESET). + */ +ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT) +{ + ITStatus bitstatus = RESET; + uint16_t itpos = 0, itmask = 0, enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx)); + assert_param(IS_SPI_I2S_GET_IT(SPI_I2S_IT)); + + /* Get the SPI_I2S_IT index */ + itpos = 0x01 << (SPI_I2S_IT & 0x0F); + + /* Get the SPI_I2S_IT IT mask */ + itmask = SPI_I2S_IT >> 4; + + /* Set the IT mask */ + itmask = 0x01 << itmask; + + /* Get the SPI_I2S_IT enable bit status */ + enablestatus = (SPIx->CR2 & itmask) ; + + /* Check the status of the specified SPI interrupt */ + if (((SPIx->SR & itpos) != (uint16_t)RESET) && enablestatus) + { + /* SPI_I2S_IT is set */ + bitstatus = SET; + } + else + { + /* SPI_I2S_IT is reset */ + bitstatus = RESET; + } + /* Return the SPI_I2S_IT status */ + return bitstatus; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_syscfg.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_syscfg.c new file mode 100644 index 0000000..b628ec6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_syscfg.c @@ -0,0 +1,530 @@ +/** + ****************************************************************************** + * @file stm32f30x_syscfg.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the SYSCFG peripheral: + * + Remapping the memory mapped at 0x00000000 + * + Remapping the DMA channels + * + Enabling I2C fast mode plus driving capability for I2C plus + * + Remapping USB interrupt line + * + Configuring the EXTI lines connection to the GPIO port + * + Configuring the CLASSB requirements + * + @verbatim + + =============================================================================== + ##### How to use this driver ##### + =============================================================================== + [..] The SYSCFG registers can be accessed only when the SYSCFG + interface APB clock is enabled. + [..] To enable SYSCFG APB clock use: + RCC_APBPeriphClockCmd(RCC_APBPeriph_SYSCFG, ENABLE); + + @endverbatim + + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_syscfg.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup SYSCFG + * @brief SYSCFG driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Reset value od SYSCFG_CFGR1 register */ +#define CFGR1_CLEAR_MASK ((uint32_t)0x7C000000) + +/* ------------ SYSCFG registers bit address in the alias region -------------*/ +#define SYSCFG_OFFSET (SYSCFG_BASE - PERIPH_BASE) + +/* --- CFGR1 Register ---*/ +/* Alias word address of USB_IT_RMP bit */ +#define CFGR1_OFFSET (SYSCFG_OFFSET + 0x00) +#define USBITRMP_BitNumber 0x05 +#define CFGR1_USBITRMP_BB (PERIPH_BB_BASE + (CFGR1_OFFSET * 32) + (USBITRMP_BitNumber * 4)) + +/* --- CFGR2 Register ---*/ +/* Alias word address of BYP_ADDR_PAR bit */ +#define CFGR2_OFFSET (SYSCFG_OFFSET + 0x18) +#define BYPADDRPAR_BitNumber 0x04 +#define CFGR1_BYPADDRPAR_BB (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (BYPADDRPAR_BitNumber * 4)) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup SYSCFG_Private_Functions + * @{ + */ + +/** @defgroup SYSCFG_Group1 SYSCFG Initialization and Configuration functions + * @brief SYSCFG Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### SYSCFG Initialization and Configuration functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the SYSCFG registers to their default reset values. + * @param None + * @retval None + * @note MEM_MODE bits are not affected by APB reset. + * MEM_MODE bits took the value from the user option bytes. + */ +void SYSCFG_DeInit(void) +{ + /* Reset SYSCFG_CFGR1 register to reset value without affecting MEM_MODE bits */ + SYSCFG->CFGR1 &= SYSCFG_CFGR1_MEM_MODE; + /* Set FPU Interrupt Enable bits to default value */ + SYSCFG->CFGR1 |= 0x7C000000; + /* Reset RAM Write protection bits to default value */ + SYSCFG->RCR = 0x00000000; + /* Set EXTICRx registers to reset value */ + SYSCFG->EXTICR[0] = 0; + SYSCFG->EXTICR[1] = 0; + SYSCFG->EXTICR[2] = 0; + SYSCFG->EXTICR[3] = 0; + /* Set CFGR2 register to reset value */ + SYSCFG->CFGR2 = 0; + /* Set CFGR3 register to reset value */ + SYSCFG->CFGR3 = 0; +} + +/** + * @brief Configures the memory mapping at address 0x00000000. + * @param SYSCFG_MemoryRemap: selects the memory remapping. + * This parameter can be one of the following values: + * @arg SYSCFG_MemoryRemap_Flash: Main Flash memory mapped at 0x00000000 + * @arg SYSCFG_MemoryRemap_SystemMemory: System Flash memory mapped at 0x00000000 + * @arg SYSCFG_MemoryRemap_SRAM: Embedded SRAM mapped at 0x00000000 + * @retval None + */ +void SYSCFG_MemoryRemapConfig(uint32_t SYSCFG_MemoryRemap) +{ + uint32_t tmpcfgr1 = 0; + + /* Check the parameter */ + assert_param(IS_SYSCFG_MEMORY_REMAP(SYSCFG_MemoryRemap)); + + /* Get CFGR1 register value */ + tmpcfgr1 = SYSCFG->CFGR1; + + /* Clear MEM_MODE bits */ + tmpcfgr1 &= (uint32_t) (~SYSCFG_CFGR1_MEM_MODE); + + /* Set the new MEM_MODE bits value */ + tmpcfgr1 |= (uint32_t) SYSCFG_MemoryRemap; + + /* Set CFGR1 register with the new memory remap configuration */ + SYSCFG->CFGR1 = tmpcfgr1; +} + +/** + * @brief Configures the DMA channels remapping. + * @param SYSCFG_DMARemap: selects the DMA channels remap. + * This parameter can be one of the following values: + * @arg SYSCFG_DMARemap_TIM17: Remap TIM17 DMA requests from DMA1 channel1 to channel2 + * @arg SYSCFG_DMARemap_TIM16: Remap TIM16 DMA requests from DMA1 channel3 to channel4 + * @arg SYSCFG_DMARemap_TIM6DAC1Ch1: Remap TIM6/DAC1 DMA requests from DMA2 channel 3 to DMA1 channel 3 + * @arg SYSCFG_DMARemap_TIM7DAC1Ch2: Remap TIM7/DAC2 DMA requests from DMA2 channel 4 to DMA1 channel 4 + * @arg SYSCFG_DMARemap_ADC2ADC4: Remap ADC2 and ADC4 DMA requests from DMA2 channel1/channel3 to channel3/channel4 + * @arg SYSCFG_DMARemap_DAC2Ch1: Remap DAC2 DMA requests to DMA1 channel5 + * @arg SYSCFG_DMARemapCh2_SPI1_RX: Remap SPI1 RX DMA1 CH2 requests + * @arg SYSCFG_DMARemapCh4_SPI1_RX: Remap SPI1 RX DMA CH4 requests + * @arg SYSCFG_DMARemapCh6_SPI1_RX: Remap SPI1 RX DMA CH6 requests + * @arg SYSCFG_DMARemapCh3_SPI1_TX: Remap SPI1 TX DMA CH2 requests + * @arg SYSCFG_DMARemapCh5_SPI1_TX: Remap SPI1 TX DMA CH5 requests + * @arg SYSCFG_DMARemapCh7_SPI1_TX: Remap SPI1 TX DMA CH7 requests + * @arg SYSCFG_DMARemapCh7_I2C1_RX: Remap I2C1 RX DMA CH7 requests + * @arg SYSCFG_DMARemapCh3_I2C1_RX: Remap I2C1 RX DMA CH3 requests + * @arg SYSCFG_DMARemapCh5_I2C1_RX: Remap I2C1 RX DMA CH5 requests + * @arg SYSCFG_DMARemapCh6_I2C1_TX: Remap I2C1 TX DMA CH6 requests + * @arg SYSCFG_DMARemapCh2_I2C1_TX: Remap I2C1 TX DMA CH2 requests + * @arg SYSCFG_DMARemapCh4_I2C1_TX: Remap I2C1 TX DMA CH4 requests + * @arg SYSCFG_DMARemapCh4_ADC2: Remap ADC2 DMA1 Ch4 requests + * @arg SYSCFG_DMARemapCh2_ADC2: Remap ADC2 DMA1 Ch2 requests + * @param NewState: new state of the DMA channel remapping. + * This parameter can be: Enable or Disable. + * @note When enabled, DMA channel of the selected peripheral is remapped + * @note When disabled, Default DMA channel is mapped to the selected peripheral + * @note + * By default TIM17 DMA requests is mapped to channel 1 + * use SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_TIM17, Enable) + * to remap TIM17 DMA requests to DMA1 channel 2 + * use SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_TIM17, Disable) + * to map TIM17 DMA requests to DMA1 channel 1 (default mapping) + * @retval None + */ +void SYSCFG_DMAChannelRemapConfig(uint32_t SYSCFG_DMARemap, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SYSCFG_DMA_REMAP(SYSCFG_DMARemap)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if ((SYSCFG_DMARemap & 0x80000000)!= 0x80000000) + { + if (NewState != DISABLE) + { + /* Remap the DMA channel */ + SYSCFG->CFGR1 |= (uint32_t)SYSCFG_DMARemap; + } + else + { + /* use the default DMA channel mapping */ + SYSCFG->CFGR1 &= (uint32_t)(~SYSCFG_DMARemap); + } + } + else + { + if (NewState != DISABLE) + { + /* Remap the DMA channel */ + SYSCFG->CFGR3 |= (uint32_t)SYSCFG_DMARemap; + } + else + { + /* use the default DMA channel mapping */ + SYSCFG->CFGR3 &= (uint32_t)(~SYSCFG_DMARemap); + } + } +} + +/** + * @brief Configures the remapping capabilities of DAC/TIM triggers. + * @param SYSCFG_TriggerRemap: selects the trigger to be remapped. + * This parameter can be one of the following values: + * @arg SYSCFG_TriggerRemap_DACTIM3: Remap DAC trigger from TIM8 to TIM3 + * @arg SYSCFG_TriggerRemap_TIM1TIM17: Remap TIM1 ITR3 from TIM4 TRGO to TIM17 OC + * @arg SYSCFG_TriggerRemap_DACHRTIM1_TRIG1: Remap DAC trigger to HRTIM1 TRIG1 + * @arg SYSCFG_TriggerRemap_DACHRTIM1_TRIG2: Remap DAC trigger to HRTIM1 TRIG2 + * @param NewState: new state of the trigger mapping. + * This parameter can be: ENABLE or DISABLE. + * @note ENABLE: Enable fast mode plus driving capability for selected pin + * @note DISABLE: Disable fast mode plus driving capability for selected pin + * @retval None + */ +void SYSCFG_TriggerRemapConfig(uint32_t SYSCFG_TriggerRemap, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SYSCFG_TRIGGER_REMAP(SYSCFG_TriggerRemap)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if ((SYSCFG_TriggerRemap & 0x80000000)!= 0x80000000) + { + if (NewState != DISABLE) + { + /* Remap the trigger */ + SYSCFG->CFGR1 |= (uint32_t)SYSCFG_TriggerRemap; + } + else + { + /* Use the default trigger mapping */ + SYSCFG->CFGR1 &= (uint32_t)(~SYSCFG_TriggerRemap); + } + } + else + { + if (NewState != DISABLE) + { + /* Remap the trigger */ + SYSCFG->CFGR3 |= (uint32_t)SYSCFG_TriggerRemap; + } + else + { + /* Use the default trigger mapping */ + SYSCFG->CFGR3 &= (uint32_t)(~SYSCFG_TriggerRemap); + } + } +} + +/** + * @brief Configures the remapping capabilities of encoder mode. + * @ note This feature implement the so-called M/T method for measuring speed + * and position using quadrature encoders. + * @param SYSCFG_EncoderRemap: selects the remap option for encoder mode. + * This parameter can be one of the following values: + * @arg SYSCFG_EncoderRemap_No: No remap + * @arg SYSCFG_EncoderRemap_TIM2: Timer 2 IC1 and IC2 connected to TIM15 IC1 and IC2 + * @arg SYSCFG_EncoderRemap_TIM3: Timer 3 IC1 and IC2 connected to TIM15 IC1 and IC2 + * @arg SYSCFG_EncoderRemap_TIM4: Timer 4 IC1 and IC2 connected to TIM15 IC1 and IC2 + * @retval None + */ +void SYSCFG_EncoderRemapConfig(uint32_t SYSCFG_EncoderRemap) +{ + /* Check the parameter */ + assert_param(IS_SYSCFG_ENCODER_REMAP(SYSCFG_EncoderRemap)); + + /* Reset the encoder mode remapping bits */ + SYSCFG->CFGR1 &= (uint32_t)(~SYSCFG_CFGR1_ENCODER_MODE); + + /* Set the selected configuration */ + SYSCFG->CFGR1 |= (uint32_t)(SYSCFG_EncoderRemap); +} + +/** + * @brief Remaps the USB interrupt lines. + * @param NewState: new state of the mapping of USB interrupt lines. + * This parameter can be: + * @param ENABLE: Remap the USB interrupt line as following: + * @arg USB Device High Priority (USB_HP) interrupt mapped to line 74. + * @arg USB Device Low Priority (USB_LP) interrupt mapped to line 75. + * @arg USB Wakeup Interrupt (USB_WKUP) interrupt mapped to line 76. + * @param DISABLE: Use the default USB interrupt line: + * @arg USB Device High Priority (USB_HP) interrupt mapped to line 19. + * @arg USB Device Low Priority (USB_LP) interrupt mapped to line 20. + * @arg USB Wakeup Interrupt (USB_WKUP) interrupt mapped to line 42. + * @retval None + */ +void SYSCFG_USBInterruptLineRemapCmd(FunctionalState NewState) +{ + /* Check the parameter */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* Remap the USB interupt lines */ + *(__IO uint32_t *) CFGR1_USBITRMP_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the I2C fast mode plus driving capability. + * @param SYSCFG_I2CFastModePlus: selects the pin. + * This parameter can be one of the following values: + * @arg SYSCFG_I2CFastModePlus_PB6: Configure fast mode plus driving capability for PB6 + * @arg SYSCFG_I2CFastModePlus_PB7: Configure fast mode plus driving capability for PB7 + * @arg SYSCFG_I2CFastModePlus_PB8: Configure fast mode plus driving capability for PB8 + * @arg SYSCFG_I2CFastModePlus_PB9: Configure fast mode plus driving capability for PB9 + * @arg SYSCFG_I2CFastModePlus_I2C1: Configure fast mode plus driving capability for I2C1 pins + * @arg SYSCFG_I2CFastModePlus_I2C2: Configure fast mode plus driving capability for I2C2 pins + * @param NewState: new state of the DMA channel remapping. + * This parameter can be: + * @arg ENABLE: Enable fast mode plus driving capability for selected I2C pin + * @arg DISABLE: Disable fast mode plus driving capability for selected I2C pin + * @note For I2C1, fast mode plus driving capability can be enabled on all selected + * I2C1 pins using SYSCFG_I2CFastModePlus_I2C1 parameter or independently + * on each one of the following pins PB6, PB7, PB8 and PB9. + * @note For remaing I2C1 pins (PA14, PA15...) fast mode plus driving capability + * can be enabled only by using SYSCFG_I2CFastModePlus_I2C1 parameter. + * @note For all I2C2 pins fast mode plus driving capability can be enabled + * only by using SYSCFG_I2CFastModePlus_I2C2 parameter. + * @retval None + */ +void SYSCFG_I2CFastModePlusConfig(uint32_t SYSCFG_I2CFastModePlus, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SYSCFG_I2C_FMP(SYSCFG_I2CFastModePlus)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable fast mode plus driving capability for selected I2C pin */ + SYSCFG->CFGR1 |= (uint32_t)SYSCFG_I2CFastModePlus; + } + else + { + /* Disable fast mode plus driving capability for selected I2C pin */ + SYSCFG->CFGR1 &= (uint32_t)(~SYSCFG_I2CFastModePlus); + } +} + +/** + * @brief Enables or disables the selected SYSCFG interrupts. + * @param SYSCFG_IT: specifies the SYSCFG interrupt sources to be enabled or disabled. + * This parameter can be one of the following values: + * @arg SYSCFG_IT_IXC: Inexact Interrupt + * @arg SYSCFG_IT_IDC: Input denormal Interrupt + * @arg SYSCFG_IT_OFC: Overflow Interrupt + * @arg SYSCFG_IT_UFC: Underflow Interrupt + * @arg SYSCFG_IT_DZC: Divide-by-zero Interrupt + * @arg SYSCFG_IT_IOC: Invalid operation Interrupt + * @param NewState: new state of the specified SYSCFG interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SYSCFG_ITConfig(uint32_t SYSCFG_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_SYSCFG_IT(SYSCFG_IT)); + + if (NewState != DISABLE) + { + /* Enable the selected SYSCFG interrupts */ + SYSCFG->CFGR1 |= SYSCFG_IT; + } + else + { + /* Disable the selected SYSCFG interrupts */ + SYSCFG->CFGR1 &= ((uint32_t)~SYSCFG_IT); + } +} + +/** + * @brief Selects the GPIO pin used as EXTI Line. + * @param EXTI_PortSourceGPIOx : selects the GPIO port to be used as source + * for EXTI lines where x can be (A, B, C, D, E or F). + * @param EXTI_PinSourcex: specifies the EXTI line to be configured. + * This parameter can be EXTI_PinSourcex where x can be (0..15) + * @retval None + */ +void SYSCFG_EXTILineConfig(uint8_t EXTI_PortSourceGPIOx, uint8_t EXTI_PinSourcex) +{ + uint32_t tmp = 0x00; + + /* Check the parameters */ + assert_param(IS_EXTI_PORT_SOURCE(EXTI_PortSourceGPIOx)); + assert_param(IS_EXTI_PIN_SOURCE(EXTI_PinSourcex)); + + tmp = ((uint32_t)0x0F) << (0x04 * (EXTI_PinSourcex & (uint8_t)0x03)); + SYSCFG->EXTICR[EXTI_PinSourcex >> 0x02] &= ~tmp; + SYSCFG->EXTICR[EXTI_PinSourcex >> 0x02] |= (((uint32_t)EXTI_PortSourceGPIOx) << (0x04 * (EXTI_PinSourcex & (uint8_t)0x03))); +} + +/** + * @brief Connects the selected parameter to the break input of TIM1. + * @note The selected configuration is locked and can be unlocked by system reset + * @param SYSCFG_Break: selects the configuration to be connected to break + * input of TIM1 + * This parameter can be any combination of the following values: + * @arg SYSCFG_Break_PVD: PVD interrupt is connected to the break input of TIM1. + * @arg SYSCFG_Break_SRAMParity: SRAM Parity error is connected to the break input of TIM1. + * @arg SYSCFG_Break_HardFault: Lockup output of CortexM4 is connected to the break input of TIM1. + * @retval None + */ +void SYSCFG_BreakConfig(uint32_t SYSCFG_Break) +{ + /* Check the parameter */ + assert_param(IS_SYSCFG_LOCK_CONFIG(SYSCFG_Break)); + + SYSCFG->CFGR2 |= (uint32_t) SYSCFG_Break; +} + +/** + * @brief Disables the parity check on RAM. + * @note Disabling the parity check on RAM locks the configuration bit. + * To re-enable the parity check on RAM perform a system reset. + * @param None + * @retval None + */ +void SYSCFG_BypassParityCheckDisable(void) +{ + /* Disable the adddress parity check on RAM */ + *(__IO uint32_t *) CFGR1_BYPADDRPAR_BB = (uint32_t)0x00000001; +} + +/** + * @brief Enables the ICODE SRAM write protection. + * @note Enabling the ICODE SRAM write protection locks the configuration bit. + * To disable the ICODE SRAM write protection perform a system reset. + * @param None + * @retval None + */ +void SYSCFG_SRAMWRPEnable(uint32_t SYSCFG_SRAMWRP) +{ + /* Check the parameter */ + assert_param(IS_SYSCFG_PAGE(SYSCFG_SRAMWRP)); + + /* Enable the write-protection on the selected ICODE SRAM page */ + SYSCFG->RCR |= (uint32_t)SYSCFG_SRAMWRP; +} + +/** + * @brief Checks whether the specified SYSCFG flag is set or not. + * @param SYSCFG_Flag: specifies the SYSCFG flag to check. + * This parameter can be one of the following values: + * @arg SYSCFG_FLAG_PE: SRAM parity error flag. + * @retval The new state of SYSCFG_Flag (SET or RESET). + */ +#ifdef __GNUC__ +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wunused-parameter" +#endif +FlagStatus SYSCFG_GetFlagStatus(uint32_t SYSCFG_Flag) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameter */ + assert_param(IS_SYSCFG_FLAG(SYSCFG_Flag)); + + /* Check the status of the specified SPI flag */ + if ((SYSCFG->CFGR2 & SYSCFG_CFGR2_SRAM_PE) != (uint32_t)RESET) + { + /* SYSCFG_Flag is set */ + bitstatus = SET; + } + else + { + /* SYSCFG_Flag is reset */ + bitstatus = RESET; + } + /* Return the SYSCFG_Flag status */ + return bitstatus; +} +#ifdef __GNUC__ +# pragma GCC diagnostic pop +#endif + +/** + * @brief Clears the selected SYSCFG flag. + * @param SYSCFG_Flag: selects the flag to be cleared. + * This parameter can be any combination of the following values: + * @arg SYSCFG_FLAG_PE: SRAM parity error flag. + * @retval None + */ +void SYSCFG_ClearFlag(uint32_t SYSCFG_Flag) +{ + /* Check the parameter */ + assert_param(IS_SYSCFG_FLAG(SYSCFG_Flag)); + + SYSCFG->CFGR2 |= (uint32_t) SYSCFG_Flag; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_tim.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_tim.c new file mode 100644 index 0000000..60a5259 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_tim.c @@ -0,0 +1,3995 @@ +/** + ****************************************************************************** + * @file stm32f30x_tim.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the TIM peripheral: + * + TimeBase management + * + Output Compare management + * + Input Capture management + * + Advanced-control timers (TIM1 and TIM8) specific features + * + Interrupts, DMA and flags management + * + Clocks management + * + Synchronization management + * + Specific interface management + * + Specific remapping management + * + @verbatim + + ============================================================================== + ##### How to use this driver ##### + ============================================================================== + [..] This driver provides functions to configure and program the TIM + of all stm32f30x devices. + These functions are split in 9 groups: + + (#) TIM TimeBase management: this group includes all needed functions + to configure the TM Timebase unit: + (++) Set/Get Prescaler + (++) Set/Get Autoreload + (++) Counter modes configuration + (++) Set Clock division + (++) Select the One Pulse mode + (++) Update Request Configuration + (++) Update Disable Configuration + (++) Auto-Preload Configuration + (++) Enable/Disable the counter + + (#) TIM Output Compare management: this group includes all needed + functions to configure the Capture/Compare unit used in Output + compare mode: + (++) Configure each channel, independently, in Output Compare mode + (++) Select the output compare modes + (++) Select the Polarities of each channel + (++) Set/Get the Capture/Compare register values + (++) Select the Output Compare Fast mode + (++) Select the Output Compare Forced mode + (++) Output Compare-Preload Configuration + (++) Clear Output Compare Reference + (++) Select the OCREF Clear signal + (++) Enable/Disable the Capture/Compare Channels + + (#) TIM Input Capture management: this group includes all needed + functions to configure the Capture/Compare unit used in + Input Capture mode: + (++) Configure each channel in input capture mode + (++) Configure Channel1/2 in PWM Input mode + (++) Set the Input Capture Prescaler + (++) Get the Capture/Compare values + + (#) Advanced-control timers (TIM1 and TIM8) specific features + (++) Configures the Break input, dead time, Lock level, the OSSI, + the OSSR State and the AOE(automatic output enable) + (++) Enable/Disable the TIM peripheral Main Outputs + (++) Select the Commutation event + (++) Set/Reset the Capture Compare Preload Control bit + + (#) TIM interrupts, DMA and flags management + (++) Enable/Disable interrupt sources + (++) Get flags status + (++) Clear flags/ Pending bits + (++) Enable/Disable DMA requests + (++) Configure DMA burst mode + (++) Select CaptureCompare DMA request + + (#) TIM clocks management: this group includes all needed functions + to configure the clock controller unit: + (++) Select internal/External clock + (++) Select the external clock mode: ETR(Mode1/Mode2), TIx or ITRx + + (#) TIM synchronization management: this group includes all needed + functions to configure the Synchronization unit: + (++) Select Input Trigger + (++) Select Output Trigger + (++) Select Master Slave Mode + (++) ETR Configuration when used as external trigger + + (#) TIM specific interface management, this group includes all + needed functions to use the specific TIM interface: + (++) Encoder Interface Configuration + (++) Select Hall Sensor + + (#) TIM specific remapping management includes the Remapping + configuration of specific timers + + @endverbatim + + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_tim.h" +#include "stm32f30x_rcc.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup TIM + * @brief TIM driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/* ---------------------- TIM registers bit mask ------------------------ */ +#define SMCR_ETR_MASK ((uint16_t)0x00FF) +#define CCMR_OFFSET ((uint16_t)0x0018) +#define CCER_CCE_SET ((uint16_t)0x0001) +#define CCER_CCNE_SET ((uint16_t)0x0004) +#define CCMR_OC13M_MASK ((uint32_t)0xFFFEFF8F) +#define CCMR_OC24M_MASK ((uint32_t)0xFEFF8FFF) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); + +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup TIM_Private_Functions + * @{ + */ + +/** @defgroup TIM_Group1 TimeBase management functions + * @brief TimeBase management functions + * +@verbatim + =============================================================================== + ##### TimeBase management functions ##### + =============================================================================== + + + *** TIM Driver: how to use it in Timing(Time base) Mode *** + ============================================================ + [..] + To use the Timer in Timing(Time base) mode, the following steps are mandatory: + + (#) Enable TIM clock using + RCC_APBxPeriphClockCmd(RCC_APBxPeriph_TIMx, ENABLE) function + (#) Fill the TIM_TimeBaseInitStruct with the desired parameters. + (#) Call TIM_TimeBaseInit(TIMx, &TIM_TimeBaseInitStruct) to configure + the Time Base unit + with the corresponding configuration + (#) Enable the NVIC if you need to generate the update interrupt. + (#) Enable the corresponding interrupt using the function + TIM_ITConfig(TIMx, TIM_IT_Update) + (#) Call the TIM_Cmd(ENABLE) function to enable the TIM counter. + [..] + (@) All other functions can be used separately to modify, if needed, + a specific feature of the Timer. + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the TIMx peripheral registers to their default reset values. + * @param TIMx: where x can be 1, 2, 3, 4, 6 ,7 ,8, 15, 16 or 17 to select the TIM peripheral. + * @retval None + + */ +void TIM_DeInit(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + if (TIMx == TIM1) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, DISABLE); + } + else if (TIMx == TIM2) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, DISABLE); + } + else if (TIMx == TIM3) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, DISABLE); + } + else if (TIMx == TIM4) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, DISABLE); + } + else if (TIMx == TIM6) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, DISABLE); + } + else if (TIMx == TIM7) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, DISABLE); + } + else if (TIMx == TIM8) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, DISABLE); + } + else if (TIMx == TIM15) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM15, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM15, DISABLE); + } + else if (TIMx == TIM16) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM16, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM16, DISABLE); + } + else + { + if (TIMx == TIM17) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM17, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM17, DISABLE); + } + } +} + +/** + * @brief Initializes the TIMx Time Base Unit peripheral according to + * the specified parameters in the TIM_TimeBaseInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 6 ,7 ,8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_TimeBaseInitStruct: pointer to a TIM_TimeBaseInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) +{ + uint16_t tmpcr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_COUNTER_MODE(TIM_TimeBaseInitStruct->TIM_CounterMode)); + assert_param(IS_TIM_CKD_DIV(TIM_TimeBaseInitStruct->TIM_ClockDivision)); + + tmpcr1 = TIMx->CR1; + + if((TIMx == TIM1) || (TIMx == TIM8)|| (TIMx == TIM2) || + (TIMx == TIM3)|| (TIMx == TIM4)) + { + /* Select the Counter Mode */ + tmpcr1 &= (uint16_t)(~(TIM_CR1_DIR | TIM_CR1_CMS)); + tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_CounterMode; + } + + if((TIMx != TIM6) && (TIMx != TIM7)) + { + /* Set the clock division */ + tmpcr1 &= (uint16_t)(~TIM_CR1_CKD); + tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_ClockDivision; + } + + TIMx->CR1 = tmpcr1; + + /* Set the Autoreload value */ + TIMx->ARR = TIM_TimeBaseInitStruct->TIM_Period ; + + /* Set the Prescaler value */ + TIMx->PSC = TIM_TimeBaseInitStruct->TIM_Prescaler; + + if ((TIMx == TIM1) || (TIMx == TIM8)|| (TIMx == TIM15) || + (TIMx == TIM16) || (TIMx == TIM17)) + { + /* Set the Repetition Counter value */ + TIMx->RCR = TIM_TimeBaseInitStruct->TIM_RepetitionCounter; + } + + /* Generate an update event to reload the Prescaler + and the repetition counter(only for TIM1 and TIM8) value immediatly */ + TIMx->EGR = TIM_PSCReloadMode_Immediate; +} + +/** + * @brief Fills each TIM_TimeBaseInitStruct member with its default value. + * @param TIM_TimeBaseInitStruct : pointer to a TIM_TimeBaseInitTypeDef + * structure which will be initialized. + * @retval None + */ +void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) +{ + /* Set the default configuration */ + TIM_TimeBaseInitStruct->TIM_Period = 0xFFFFFFFF; + TIM_TimeBaseInitStruct->TIM_Prescaler = 0x0000; + TIM_TimeBaseInitStruct->TIM_ClockDivision = TIM_CKD_DIV1; + TIM_TimeBaseInitStruct->TIM_CounterMode = TIM_CounterMode_Up; + TIM_TimeBaseInitStruct->TIM_RepetitionCounter = 0x0000; +} + +/** + * @brief Configures the TIMx Prescaler. + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17 to select the TIM peripheral. + * @param Prescaler: specifies the Prescaler Register value + * @param TIM_PSCReloadMode: specifies the TIM Prescaler Reload mode + * This parameter can be one of the following values: + * @arg TIM_PSCReloadMode_Update: The Prescaler is loaded at the update event. + * @arg TIM_PSCReloadMode_Immediate: The Prescaler is loaded immediatly. + * @retval None + */ +void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_PRESCALER_RELOAD(TIM_PSCReloadMode)); + /* Set the Prescaler value */ + TIMx->PSC = Prescaler; + /* Set or reset the UG Bit */ + TIMx->EGR = TIM_PSCReloadMode; +} + +/** + * @brief Specifies the TIMx Counter Mode to be used. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_CounterMode: specifies the Counter Mode to be used + * This parameter can be one of the following values: + * @arg TIM_CounterMode_Up: TIM Up Counting Mode + * @arg TIM_CounterMode_Down: TIM Down Counting Mode + * @arg TIM_CounterMode_CenterAligned1: TIM Center Aligned Mode1 + * @arg TIM_CounterMode_CenterAligned2: TIM Center Aligned Mode2 + * @arg TIM_CounterMode_CenterAligned3: TIM Center Aligned Mode3 + * @retval None + */ +void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode) +{ + uint16_t tmpcr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_COUNTER_MODE(TIM_CounterMode)); + + tmpcr1 = TIMx->CR1; + + /* Reset the CMS and DIR Bits */ + tmpcr1 &= (uint16_t)~(TIM_CR1_DIR | TIM_CR1_CMS); + + /* Set the Counter Mode */ + tmpcr1 |= TIM_CounterMode; + + /* Write to TIMx CR1 register */ + TIMx->CR1 = tmpcr1; +} + +/** + * @brief Sets the TIMx Counter Register value + * @param TIMx: where x can be 1, 2, 3, 4, 6 ,7 ,8, 15, 16 or 17 to select the TIM peripheral. + * @param Counter: specifies the Counter register new value. + * @retval None + */ +void TIM_SetCounter(TIM_TypeDef* TIMx, uint32_t Counter) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + /* Set the Counter Register value */ + TIMx->CNT = Counter; +} + +/** + * @brief Sets the TIMx Autoreload Register value + * @param TIMx: where x can be 1, 2, 3, 4, 6 ,7 ,8, 15, 16 or 17 to select the TIM peripheral. + * @param Autoreload: specifies the Autoreload register new value. + * @retval None + */ +void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint32_t Autoreload) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + /* Set the Autoreload Register value */ + TIMx->ARR = Autoreload; +} + +/** + * @brief Gets the TIMx Counter value. + * @param TIMx: where x can be 1, 2, 3, 4, 6 ,7 ,8, 15, 16 or 17 to select the TIM peripheral. + * @retval Counter Register value + */ +uint32_t TIM_GetCounter(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + /* Get the Counter Register value */ + return TIMx->CNT; +} + +/** + * @brief Gets the TIMx Prescaler value. + * @param TIMx: where x can be 1, 2, 3, 4, 6 ,7 ,8, 15, 16 or 17 to select the TIM peripheral. + * @retval Prescaler Register value. + */ +uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + /* Get the Prescaler Register value */ + return TIMx->PSC; +} + +/** + * @brief Enables or Disables the TIMx Update event. + * @param TIMx: where x can be 1, 2, 3, 4, 6 ,7 ,8, 15, 16 or 17 to select the TIM peripheral. + * @param NewState: new state of the TIMx UDIS bit + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the Update Disable Bit */ + TIMx->CR1 |= TIM_CR1_UDIS; + } + else + { + /* Reset the Update Disable Bit */ + TIMx->CR1 &= (uint16_t)~TIM_CR1_UDIS; + } +} + +/** + * @brief Configures the TIMx Update Request Interrupt source. + * @param TIMx: where x can be 1, 2, 3, 4, 6 ,7 ,8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_UpdateSource: specifies the Update source. + * This parameter can be one of the following values: + * @arg TIM_UpdateSource_Regular: Source of update is the counter + * overflow/underflow or the setting of UG bit, or an update + * generation through the slave mode controller. + * @arg TIM_UpdateSource_Global: Source of update is counter overflow/underflow. + * @retval None + */ +void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_UPDATE_SOURCE(TIM_UpdateSource)); + + if (TIM_UpdateSource != TIM_UpdateSource_Global) + { + /* Set the URS Bit */ + TIMx->CR1 |= TIM_CR1_URS; + } + else + { + /* Reset the URS Bit */ + TIMx->CR1 &= (uint16_t)~TIM_CR1_URS; + } +} + +/** + * @brief Sets or resets the update interrupt flag (UIF)status bit Remapping. + * when sets, reading TIMx_CNT register returns UIF bit instead of CNT[31] + * @param TIMx: where x can be 1, 2, 3, 4, 6 ,7 ,8, 15, 16 or 17 to select the TIM peripheral. + * @param NewState: new state of the UIFREMAP bit. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_UIFRemap(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the TIM Counter */ + TIMx->CR1 |= TIM_CR1_UIFREMAP; + } + else + { + /* Disable the TIM Counter */ + TIMx->CR1 &= (uint16_t)~TIM_CR1_UIFREMAP; + } +} + +/** + * @brief Enables or disables TIMx peripheral Preload register on ARR. + * @param TIMx: where x can be 1, 2, 3, 4, 6 ,7 ,8, 15, 16 or 17 to select the TIM peripheral. + * @param NewState: new state of the TIMx peripheral Preload register + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the ARR Preload Bit */ + TIMx->CR1 |= TIM_CR1_ARPE; + } + else + { + /* Reset the ARR Preload Bit */ + TIMx->CR1 &= (uint16_t)~TIM_CR1_ARPE; + } +} + +/** + * @brief Selects the TIMx's One Pulse Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 6 ,7 ,8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_OPMode: specifies the OPM Mode to be used. + * This parameter can be one of the following values: + * @arg TIM_OPMode_Single + * @arg TIM_OPMode_Repetitive + * @retval None + */ +void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_OPM_MODE(TIM_OPMode)); + + /* Reset the OPM Bit */ + TIMx->CR1 &= (uint16_t)~TIM_CR1_OPM; + + /* Configure the OPM Mode */ + TIMx->CR1 |= TIM_OPMode; +} + +/** + * @brief Sets the TIMx Clock Division value. + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17, to select the TIM peripheral. + * @param TIM_CKD: specifies the clock division value. + * This parameter can be one of the following value: + * @arg TIM_CKD_DIV1: TDTS = Tck_tim + * @arg TIM_CKD_DIV2: TDTS = 2*Tck_tim + * @arg TIM_CKD_DIV4: TDTS = 4*Tck_tim + * @retval None + */ +void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_CKD_DIV(TIM_CKD)); + + /* Reset the CKD Bits */ + TIMx->CR1 &= (uint16_t)(~TIM_CR1_CKD); + + /* Set the CKD value */ + TIMx->CR1 |= TIM_CKD; +} + +/** + * @brief Enables or disables the specified TIM peripheral. + * @param TIMx: where x can be 1, 2, 3, 4, 6, 7, 8, 15, 16 or 17 to select + * the TIMx peripheral. + * @param NewState: new state of the TIMx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the TIM Counter */ + TIMx->CR1 |= TIM_CR1_CEN; + } + else + { + /* Disable the TIM Counter */ + TIMx->CR1 &= (uint16_t)~TIM_CR1_CEN; + } +} +/** + * @} + */ + +/** @defgroup TIM_Group2 Output Compare management functions + * @brief Output Compare management functions + * +@verbatim + =============================================================================== + ##### Output Compare management functions ##### + =============================================================================== + + *** TIM Driver: how to use it in Output Compare Mode *** + ======================================================== + [..] + To use the Timer in Output Compare mode, the following steps are mandatory: + + (#) Enable TIM clock using RCC_APBxPeriphClockCmd(RCC_APBxPeriph_TIMx, ENABLE) function + + (#) Configure the TIM pins by configuring the corresponding GPIO pins + + (#) Configure the Time base unit as described in the first part of this driver, + if needed, else the Timer will run with the default configuration: + (++) Autoreload value = 0xFFFF + (++) Prescaler value = 0x0000 + (++) Counter mode = Up counting + (++) Clock Division = TIM_CKD_DIV1 + (#) Fill the TIM_OCInitStruct with the desired parameters including: + (++) The TIM Output Compare mode: TIM_OCMode + (++) TIM Output State: TIM_OutputState + (++) TIM Pulse value: TIM_Pulse + (++) TIM Output Compare Polarity : TIM_OCPolarity + + (#) Call TIM_OCxInit(TIMx, &TIM_OCInitStruct) to configure the desired channel with the + corresponding configuration + + (#) Call the TIM_Cmd(ENABLE) function to enable the TIM counter. + [..] + (@) All other functions can be used separately to modify, if needed, + a specific feature of the Timer. + + (@) In case of PWM mode, this function is mandatory: + TIM_OCxPreloadConfig(TIMx, TIM_OCPreload_ENABLE); + + (@) If the corresponding interrupt or DMA request are needed, the user should: + (#@) Enable the NVIC (or the DMA) to use the TIM interrupts (or DMA requests). + (#@) Enable the corresponding interrupt (or DMA request) using the function + TIM_ITConfig(TIMx, TIM_IT_CCx) (or TIM_DMA_Cmd(TIMx, TIM_DMA_CCx)) + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the TIMx Channel1 according to the specified parameters in + * the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17, to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure that contains + * the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint32_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + + /* Disable the Channel 1: Reset the CC1E Bit */ + TIMx->CCER &= (uint32_t)~TIM_CCER_CC1E; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR1; + + /* Reset the Output Compare Mode Bits */ + tmpccmrx &= (uint32_t)~TIM_CCMR1_OC1M; + tmpccmrx &= (uint32_t)~TIM_CCMR1_CC1S; + /* Select the Output Compare Mode */ + tmpccmrx |= TIM_OCInitStruct->TIM_OCMode; + + /* Reset the Output Polarity level */ + tmpccer &= (uint32_t)~TIM_CCER_CC1P; + /* Set the Output Compare Polarity */ + tmpccer |= TIM_OCInitStruct->TIM_OCPolarity; + + /* Set the Output State */ + tmpccer |= TIM_OCInitStruct->TIM_OutputState; + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM15) || (TIMx == TIM16) || (TIMx == TIM17)) + { + assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); + assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + + /* Reset the Output N Polarity level */ + tmpccer &= (uint32_t)~TIM_CCER_CC1NP; + /* Set the Output N Polarity */ + tmpccer |= TIM_OCInitStruct->TIM_OCNPolarity; + /* Reset the Output N State */ + tmpccer &= (uint32_t)~TIM_CCER_CC1NE; + + /* Set the Output N State */ + tmpccer |= TIM_OCInitStruct->TIM_OutputNState; + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= (uint32_t)~TIM_CR2_OIS1; + tmpcr2 &= (uint32_t)~TIM_CR2_OIS1N; + /* Set the Output Idle state */ + tmpcr2 |= TIM_OCInitStruct->TIM_OCIdleState; + /* Set the Output N Idle state */ + tmpcr2 |= TIM_OCInitStruct->TIM_OCNIdleState; + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR1 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel2 according to the specified parameters + * in the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure that contains + * the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint32_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= (uint32_t)~TIM_CCER_CC2E; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR1; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint32_t)~TIM_CCMR1_OC2M; + tmpccmrx &= (uint32_t)~TIM_CCMR1_CC2S; + + /* Select the Output Compare Mode */ + tmpccmrx |= (uint32_t)(TIM_OCInitStruct->TIM_OCMode << 8); + + /* Reset the Output Polarity level */ + tmpccer &= (uint32_t)~TIM_CCER_CC2P; + /* Set the Output Compare Polarity */ + tmpccer |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OCPolarity << 4); + + /* Set the Output State */ + tmpccer |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OutputState << 4); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); + assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + + /* Reset the Output N Polarity level */ + tmpccer &= (uint32_t)~TIM_CCER_CC2NP; + /* Set the Output N Polarity */ + tmpccer |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OCNPolarity << 4); + /* Reset the Output N State */ + tmpccer &= (uint32_t)~TIM_CCER_CC2NE; + + /* Set the Output N State */ + tmpccer |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OutputNState << 4); + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= (uint32_t)~TIM_CR2_OIS2; + tmpcr2 &= (uint32_t)~TIM_CR2_OIS2N; + /* Set the Output Idle state */ + tmpcr2 |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OCIdleState << 2); + /* Set the Output N Idle state */ + tmpcr2 |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OCNIdleState << 2); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR2 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel3 according to the specified parameters + * in the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure that contains + * the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint32_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + + /* Disable the Channel 3: Reset the CC2E Bit */ + TIMx->CCER &= (uint32_t)~TIM_CCER_CC3E; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR2 register value */ + tmpccmrx = TIMx->CCMR2; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint32_t)~TIM_CCMR2_OC3M; + tmpccmrx &= (uint32_t)~TIM_CCMR2_CC3S; + /* Select the Output Compare Mode */ + tmpccmrx |= TIM_OCInitStruct->TIM_OCMode; + + /* Reset the Output Polarity level */ + tmpccer &= (uint32_t)~TIM_CCER_CC3P; + /* Set the Output Compare Polarity */ + tmpccer |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OCPolarity << 8); + + /* Set the Output State */ + tmpccer |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OutputState << 8); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); + assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + + /* Reset the Output N Polarity level */ + tmpccer &= (uint32_t)~TIM_CCER_CC3NP; + /* Set the Output N Polarity */ + tmpccer |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OCNPolarity << 8); + /* Reset the Output N State */ + tmpccer &= (uint32_t)~TIM_CCER_CC3NE; + + /* Set the Output N State */ + tmpccer |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OutputNState << 8); + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= (uint32_t)~TIM_CR2_OIS3; + tmpcr2 &= (uint32_t)~TIM_CR2_OIS3N; + /* Set the Output Idle state */ + tmpcr2 |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OCIdleState << 4); + /* Set the Output N Idle state */ + tmpcr2 |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OCNIdleState << 4); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR3 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel4 according to the specified parameters + * in the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure that contains + * the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint32_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + + /* Disable the Channel 4: Reset the CC4E Bit */ + TIMx->CCER &= (uint32_t)~TIM_CCER_CC4E; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR2 register value */ + tmpccmrx = TIMx->CCMR2; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint32_t)~TIM_CCMR2_OC4M; + tmpccmrx &= (uint32_t)~TIM_CCMR2_CC4S; + + /* Select the Output Compare Mode */ + tmpccmrx |= (uint32_t)(TIM_OCInitStruct->TIM_OCMode << 8); + + /* Reset the Output Polarity level */ + tmpccer &= (uint32_t)~TIM_CCER_CC4P; + /* Set the Output Compare Polarity */ + tmpccer |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OCPolarity << 12); + + /* Set the Output State */ + tmpccer |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OutputState << 12); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + /* Reset the Output Compare IDLE State */ + tmpcr2 &=(uint32_t) ~TIM_CR2_OIS4; + /* Set the Output Idle state */ + tmpcr2 |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OCIdleState << 6); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR4 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel5 according to the specified parameters + * in the TIM_OCInitStruct. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure that contains + * the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC5Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint32_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + + /* Disable the Channel 5: Reset the CC5E Bit */ + TIMx->CCER &= (uint32_t)~TIM_CCER_CC5E; /* to be verified*/ + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR3 register value */ + tmpccmrx = TIMx->CCMR3; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint32_t)~TIM_CCMR3_OC5M; + + /* Select the Output Compare Mode */ + tmpccmrx |= (uint32_t)(TIM_OCInitStruct->TIM_OCMode); + + /* Reset the Output Polarity level */ + tmpccer &= (uint32_t)~TIM_CCER_CC5P; + /* Set the Output Compare Polarity */ + tmpccer |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OCPolarity << 16); + + /* Set the Output State */ + tmpccer |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OutputState << 16); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + /* Reset the Output Compare IDLE State */ + tmpcr2 &=(uint32_t) ~TIM_CR2_OIS5; + /* Set the Output Idle state */ + tmpcr2 |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OCIdleState << 16); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR3 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR5 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel6 according to the specified parameters + * in the TIM_OCInitStruct. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure that contains + * the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC6Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint32_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + + /* Disable the Channel 5: Reset the CC5E Bit */ + TIMx->CCER &= (uint32_t)~TIM_CCER_CC6E; /* to be verified*/ + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR3 register value */ + tmpccmrx = TIMx->CCMR3; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint32_t)~TIM_CCMR3_OC6M; + + /* Select the Output Compare Mode */ + tmpccmrx |= (uint32_t)(TIM_OCInitStruct->TIM_OCMode << 8); + + /* Reset the Output Polarity level */ + tmpccer &= (uint32_t)~TIM_CCER_CC6P; + /* Set the Output Compare Polarity */ + tmpccer |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OCPolarity << 20); + + /* Set the Output State */ + tmpccer |= (uint32_t)((uint32_t)TIM_OCInitStruct->TIM_OutputState << 20); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + /* Reset the Output Compare IDLE State */ + tmpcr2 &=(uint32_t) ~TIM_CR2_OIS6; + /* Set the Output Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 18); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR3 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR6 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Selects the TIM Group Channel 5 and Channel 1, + OC1REFC is the logical AND of OC1REFC and OC5REF. + * @param TIMx: where x can be 1 or 8 to select the TIMx peripheral + * @param NewState: new state of the Commutation event. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectGC5C1(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the GC5C1 Bit */ + TIMx->CCR5 |= TIM_CCR5_GC5C1; + } + else + { + /* Reset the GC5C1 Bit */ + TIMx->CCR5 &= (uint32_t)~TIM_CCR5_GC5C1; + } +} + +/** + * @brief Selects the TIM Group Channel 5 and Channel 2, + OC2REFC is the logical AND of OC2REFC and OC5REF. + * @param TIMx: where x can be 1 or 8 to select the TIMx peripheral + * @param NewState: new state of the Commutation event. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectGC5C2(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the GC5C2 Bit */ + TIMx->CCR5 |= TIM_CCR5_GC5C2; + } + else + { + /* Reset the GC5C2 Bit */ + TIMx->CCR5 &= (uint32_t)~TIM_CCR5_GC5C2; + } +} + + +/** + * @brief Selects the TIM Group Channel 5 and Channel 3, + OC3REFC is the logical AND of OC3REFC and OC5REF. + * @param TIMx: where x can be 1 or 8 to select the TIMx peripheral + * @param NewState: new state of the Commutation event. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectGC5C3(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the GC5C3 Bit */ + TIMx->CCR5 |= TIM_CCR5_GC5C3; + } + else + { + /* Reset the GC5C3 Bit */ + TIMx->CCR5 &= (uint32_t)~TIM_CCR5_GC5C3; + } +} + +/** + * @brief Fills each TIM_OCInitStruct member with its default value. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure which will + * be initialized. + * @retval None + */ +void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + /* Set the default configuration */ + TIM_OCInitStruct->TIM_OCMode = TIM_OCMode_Timing; + TIM_OCInitStruct->TIM_OutputState = TIM_OutputState_Disable; + TIM_OCInitStruct->TIM_OutputNState = TIM_OutputNState_Disable; + TIM_OCInitStruct->TIM_Pulse = 0x00000000; + TIM_OCInitStruct->TIM_OCPolarity = TIM_OCPolarity_High; + TIM_OCInitStruct->TIM_OCNPolarity = TIM_OCPolarity_High; + TIM_OCInitStruct->TIM_OCIdleState = TIM_OCIdleState_Reset; + TIM_OCInitStruct->TIM_OCNIdleState = TIM_OCNIdleState_Reset; +} + +/** + * @brief Selects the TIM Output Compare Mode. + * @note This function disables the selected channel before changing the Output + * Compare Mode. If needed, user has to enable this channel using + * TIM_CCxCmd() and TIM_CCxNCmd() functions. + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_Channel: specifies the TIM Channel + * This parameter can be one of the following values: + * @arg TIM_Channel_1: TIM Channel 1 + * @arg TIM_Channel_2: TIM Channel 2 + * @arg TIM_Channel_3: TIM Channel 3 + * @arg TIM_Channel_4: TIM Channel 4 + * @param TIM_OCMode: specifies the TIM Output Compare Mode. + * This parameter can be one of the following values: + * @arg TIM_OCMode_Timing + * @arg TIM_OCMode_Active + * @arg TIM_OCMode_Toggle + * @arg TIM_OCMode_PWM1 + * @arg TIM_OCMode_PWM2 + * @arg TIM_ForcedAction_Active + * @arg TIM_ForcedAction_InActive + * @arg TIM_OCMode_Retrigerrable_OPM1 + * @arg TIM_OCMode_Retrigerrable_OPM2 + * @arg TIM_OCMode_Combined_PWM1 + * @arg TIM_OCMode_Combined_PWM2 + * @arg TIM_OCMode_Asymmetric_PWM1 + * @arg TIM_OCMode_Asymmetric_PWM2 + * @retval None + */ +void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t TIM_OCMode) +{ + uint32_t tmp = 0; + uint16_t tmp1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_OCM(TIM_OCMode)); + + tmp = (uint32_t) TIMx; + tmp += CCMR_OFFSET; + + tmp1 = CCER_CCE_SET << (uint16_t)TIM_Channel; + + /* Disable the Channel: Reset the CCxE Bit */ + TIMx->CCER &= (uint16_t) ~tmp1; + + if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) + { + tmp += (TIM_Channel>>1); + + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= CCMR_OC13M_MASK; + + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= TIM_OCMode; + } + else + { + tmp += (uint32_t)(TIM_Channel - (uint32_t)4)>> (uint32_t)1; + + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= CCMR_OC24M_MASK; + + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= (uint32_t)(TIM_OCMode << 8); + } +} + +/** + * @brief Sets the TIMx Capture Compare1 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17 to select the TIM peripheral. + * @param Compare1: specifies the Capture Compare1 register new value. + * @retval None + */ +void TIM_SetCompare1(TIM_TypeDef* TIMx, uint32_t Compare1) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + + /* Set the Capture Compare1 Register value */ + TIMx->CCR1 = Compare1; +} + +/** + * @brief Sets the TIMx Capture Compare2 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 to select the TIM + * peripheral. + * @param Compare2: specifies the Capture Compare2 register new value. + * @retval None + */ +void TIM_SetCompare2(TIM_TypeDef* TIMx, uint32_t Compare2) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + + /* Set the Capture Compare2 Register value */ + TIMx->CCR2 = Compare2; +} + +/** + * @brief Sets the TIMx Capture Compare3 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param Compare3: specifies the Capture Compare3 register new value. + * @retval None + */ +void TIM_SetCompare3(TIM_TypeDef* TIMx, uint32_t Compare3) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + + /* Set the Capture Compare3 Register value */ + TIMx->CCR3 = Compare3; +} + +/** + * @brief Sets the TIMx Capture Compare4 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param Compare4: specifies the Capture Compare4 register new value. + * @retval None + */ +void TIM_SetCompare4(TIM_TypeDef* TIMx, uint32_t Compare4) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + + /* Set the Capture Compare4 Register value */ + TIMx->CCR4 = Compare4; +} + +/** + * @brief Sets the TIMx Capture Compare5 Register value + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param Compare5: specifies the Capture Compare5 register new value. + * @retval None + */ +void TIM_SetCompare5(TIM_TypeDef* TIMx, uint32_t Compare5) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + + /* Set the Capture Compare5 Register value */ + TIMx->CCR5 = Compare5; +} + +/** + * @brief Sets the TIMx Capture Compare6 Register value + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param Compare6: specifies the Capture Compare5 register new value. + * @retval None + */ +void TIM_SetCompare6(TIM_TypeDef* TIMx, uint32_t Compare6) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + + /* Set the Capture Compare6 Register value */ + TIMx->CCR6 = Compare6; +} + +/** + * @brief Forces the TIMx output 1 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC1REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC1REF. + * @retval None + */ +void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint32_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC1M Bits */ + tmpccmr1 &= (uint32_t)~TIM_CCMR1_OC1M; + + /* Configure The Forced output Mode */ + tmpccmr1 |= TIM_ForcedAction; + + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Forces the TIMx output 2 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 to select the TIM + * peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC2REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC2REF. + * @retval None + */ +void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint32_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC2M Bits */ + tmpccmr1 &= (uint32_t)~TIM_CCMR1_OC2M; + + /* Configure The Forced output Mode */ + tmpccmr1 |= ((uint32_t)TIM_ForcedAction << 8); + + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Forces the TIMx output 3 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC3REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC3REF. + * @retval None + */ +void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint32_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC1M Bits */ + tmpccmr2 &= (uint32_t)~TIM_CCMR2_OC3M; + + /* Configure The Forced output Mode */ + tmpccmr2 |= TIM_ForcedAction; + + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Forces the TIMx output 4 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC4REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC4REF. + * @retval None + */ +void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint32_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC2M Bits */ + tmpccmr2 &= (uint32_t)~TIM_CCMR2_OC4M; + + /* Configure The Forced output Mode */ + tmpccmr2 |= ((uint32_t)TIM_ForcedAction << 8); + + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Forces the TIMx output 5 waveform to active or inactive level. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC5REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC5REF. + * @retval None + */ +void TIM_ForcedOC5Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint32_t tmpccmr3 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr3 = TIMx->CCMR3; + + /* Reset the OC5M Bits */ + tmpccmr3 &= (uint32_t)~TIM_CCMR3_OC5M; + + /* Configure The Forced output Mode */ + tmpccmr3 |= (uint32_t)(TIM_ForcedAction); + + /* Write to TIMx CCMR3 register */ + TIMx->CCMR3 = tmpccmr3; +} + +/** + * @brief Forces the TIMx output 6 waveform to active or inactive level. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC5REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC5REF. + * @retval None + */ +void TIM_ForcedOC6Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint32_t tmpccmr3 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr3 = TIMx->CCMR3; + + /* Reset the OC6M Bits */ + tmpccmr3 &= (uint32_t)~TIM_CCMR3_OC6M; + + /* Configure The Forced output Mode */ + tmpccmr3 |= ((uint32_t)TIM_ForcedAction << 8); + + /* Write to TIMx CCMR3 register */ + TIMx->CCMR3 = tmpccmr3; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR1. + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint32_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC1PE Bit */ + tmpccmr1 &= (uint32_t)(~TIM_CCMR1_OC1PE); + + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr1 |= TIM_OCPreload; + + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR2. + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 to select the TIM + * peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint32_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC2PE Bit */ + tmpccmr1 &= (uint32_t)(~TIM_CCMR1_OC2PE); + + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr1 |= ((uint32_t)TIM_OCPreload << 8); + + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR3. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint32_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC3PE Bit */ + tmpccmr2 &= (uint32_t)(~TIM_CCMR2_OC3PE); + + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr2 |= TIM_OCPreload; + + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR4. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint32_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC4PE Bit */ + tmpccmr2 &= (uint32_t)(~TIM_CCMR2_OC4PE); + + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr2 |= ((uint32_t)TIM_OCPreload << 8); + + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR5. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC5PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint32_t tmpccmr3 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + + tmpccmr3 = TIMx->CCMR3; + + /* Reset the OC5PE Bit */ + tmpccmr3 &= (uint32_t)(~TIM_CCMR3_OC5PE); + + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr3 |= (uint32_t)(TIM_OCPreload); + + /* Write to TIMx CCMR3 register */ + TIMx->CCMR3 = tmpccmr3; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR6. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC6PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint32_t tmpccmr3 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + + tmpccmr3 = TIMx->CCMR3; + + /* Reset the OC5PE Bit */ + tmpccmr3 &= (uint32_t)(~TIM_CCMR3_OC6PE); + + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr3 |= ((uint32_t)TIM_OCPreload << 8); + + /* Write to TIMx CCMR3 register */ + TIMx->CCMR3 = tmpccmr3; +} + +/** + * @brief Configures the TIMx Output Compare 1 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint32_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC1FE Bit */ + tmpccmr1 &= (uint32_t)~TIM_CCMR1_OC1FE; + + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr1 |= TIM_OCFast; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Configures the TIMx Output Compare 2 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 to select the TIM + * peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint32_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC2FE Bit */ + tmpccmr1 &= (uint32_t)(~TIM_CCMR1_OC2FE); + + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr1 |= ((uint32_t)TIM_OCFast << 8); + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Configures the TIMx Output Compare 3 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint32_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + + /* Get the TIMx CCMR2 register value */ + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC3FE Bit */ + tmpccmr2 &= (uint32_t)~TIM_CCMR2_OC3FE; + + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr2 |= TIM_OCFast; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Configures the TIMx Output Compare 4 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint32_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + + /* Get the TIMx CCMR2 register value */ + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC4FE Bit */ + tmpccmr2 &= (uint32_t)(~TIM_CCMR2_OC4FE); + + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr2 |= ((uint32_t)TIM_OCFast << 8); + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Clears or safeguards the OCREF1 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint32_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC1CE Bit */ + tmpccmr1 &= (uint32_t)~TIM_CCMR1_OC1CE; + + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr1 |= TIM_OCClear; + + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Clears or safeguards the OCREF2 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 to select the TIM + * peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint32_t tmpccmr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC2CE Bit */ + tmpccmr1 &= (uint32_t)~TIM_CCMR1_OC2CE; + + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr1 |= ((uint32_t)TIM_OCClear << 8); + + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Clears or safeguards the OCREF3 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint32_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC3CE Bit */ + tmpccmr2 &= (uint32_t)~TIM_CCMR2_OC3CE; + + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr2 |= TIM_OCClear; + + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Clears or safeguards the OCREF4 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint32_t tmpccmr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + + tmpccmr2 = TIMx->CCMR2; + + /* Reset the OC4CE Bit */ + tmpccmr2 &= (uint32_t)~TIM_CCMR2_OC4CE; + + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr2 |= ((uint32_t)TIM_OCClear << 8); + + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Clears or safeguards the OCREF5 signal on an external event + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC5Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint32_t tmpccmr3 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + + tmpccmr3 = TIMx->CCMR3; + + /* Reset the OC5CE Bit */ + tmpccmr3 &= (uint32_t)~TIM_CCMR3_OC5CE; + + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr3 |= (uint32_t)(TIM_OCClear); + + /* Write to TIMx CCMR3 register */ + TIMx->CCMR3 = tmpccmr3; +} + +/** + * @brief Clears or safeguards the OCREF6 signal on an external event + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC6Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint32_t tmpccmr3 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + + tmpccmr3 = TIMx->CCMR3; + + /* Reset the OC5CE Bit */ + tmpccmr3 &= (uint32_t)~TIM_CCMR3_OC6CE; + + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr3 |= ((uint32_t)TIM_OCClear << 8); + + /* Write to TIMx CCMR3 register */ + TIMx->CCMR3 = tmpccmr3; +} + +/** + * @brief Selects the OCReference Clear source. + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_OCReferenceClear: specifies the OCReference Clear source. + * This parameter can be one of the following values: + * @arg TIM_OCReferenceClear_ETRF: The internal OCreference clear input is connected to ETRF. + * @arg TIM_OCReferenceClear_OCREFCLR: The internal OCreference clear input is connected to OCREF_CLR input. + * @retval None + */ +void TIM_SelectOCREFClear(TIM_TypeDef* TIMx, uint16_t TIM_OCReferenceClear) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(TIM_OCREFERENCECECLEAR_SOURCE(TIM_OCReferenceClear)); + + /* Set the TIM_OCReferenceClear source */ + TIMx->SMCR &= (uint16_t)~((uint16_t)TIM_SMCR_OCCS); + TIMx->SMCR |= TIM_OCReferenceClear; +} + +/** + * @brief Configures the TIMx channel 1 polarity. + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC1 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint32_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC1P Bit */ + tmpccer &= (uint32_t)(~TIM_CCER_CC1P); + tmpccer |= TIM_OCPolarity; + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx Channel 1N polarity. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_OCNPolarity: specifies the OC1N Polarity + * This parameter can be one of the following values: + * @arg TIM_OCNPolarity_High: Output Compare active high + * @arg TIM_OCNPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) +{ + uint32_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC1NP Bit */ + tmpccer &= (uint32_t)~TIM_CCER_CC1NP; + tmpccer |= TIM_OCNPolarity; + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 2 polarity. + * @param TIMx: where x can be 1, 2, 3, 4 8 or 15 to select the TIM + * peripheral. + * @param TIM_OCPolarity: specifies the OC2 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint32_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC2P Bit */ + tmpccer &= (uint32_t)(~TIM_CCER_CC2P); + tmpccer |= ((uint32_t)TIM_OCPolarity << 4); + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx Channel 2N polarity. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCNPolarity: specifies the OC2N Polarity + * This parameter can be one of the following values: + * @arg TIM_OCNPolarity_High: Output Compare active high + * @arg TIM_OCNPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) +{ + uint32_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC2NP Bit */ + tmpccer &= (uint32_t)~TIM_CCER_CC2NP; + tmpccer |= ((uint32_t)TIM_OCNPolarity << 4); + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 3 polarity. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC3 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint32_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC3P Bit */ + tmpccer &= (uint32_t)~TIM_CCER_CC3P; + tmpccer |= ((uint32_t)TIM_OCPolarity << 8); + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx Channel 3N polarity. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCNPolarity: specifies the OC3N Polarity + * This parameter can be one of the following values: + * @arg TIM_OCNPolarity_High: Output Compare active high + * @arg TIM_OCNPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) +{ + uint32_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC3NP Bit */ + tmpccer &= (uint32_t)~TIM_CCER_CC3NP; + tmpccer |= ((uint32_t)TIM_OCNPolarity << 8); + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 4 polarity. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC4 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint32_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC4P Bit */ + tmpccer &= (uint32_t)~TIM_CCER_CC4P; + tmpccer |= ((uint32_t)TIM_OCPolarity << 12); + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 5 polarity. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC5 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC5PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint32_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC5P Bit */ + tmpccer &= (uint32_t)~TIM_CCER_CC5P; + tmpccer |= ((uint32_t)TIM_OCPolarity << 16); + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 6 polarity. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC6 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC6PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint32_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + + tmpccer = TIMx->CCER; + + /* Set or Reset the CC6P Bit */ + tmpccer &= (uint32_t)~TIM_CCER_CC6P; + tmpccer |= ((uint32_t)TIM_OCPolarity << 20); + + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Enables or disables the TIM Capture Compare Channel x. + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_Channel: specifies the TIM Channel + * This parameter can be one of the following values: + * @arg TIM_Channel_1: TIM Channel 1 + * @arg TIM_Channel_2: TIM Channel 2 + * @arg TIM_Channel_3: TIM Channel 3 + * @arg TIM_Channel_4: TIM Channel 4 + * @arg TIM_Channel_5: TIM Channel 5 + * @arg TIM_Channel_6: TIM Channel 6 + * @param TIM_CCx: specifies the TIM Channel CCxE bit new state. + * This parameter can be: TIM_CCx_Enable or TIM_CCx_Disable. + * @retval None + */ +void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx) +{ + uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_CCX(TIM_CCx)); + + tmp = (uint32_t)CCER_CCE_SET << (uint32_t)TIM_Channel; + + /* Reset the CCxE Bit */ + TIMx->CCER &= (uint32_t)(~tmp); + + /* Set or reset the CCxE Bit */ + TIMx->CCER |= ((uint32_t)TIM_CCx << (uint32_t)TIM_Channel); +} + +/** + * @brief Enables or disables the TIM Capture Compare Channel xN. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_Channel: specifies the TIM Channel + * This parameter can be one of the following values: + * @arg TIM_Channel_1: TIM Channel 1 + * @arg TIM_Channel_2: TIM Channel 2 + * @arg TIM_Channel_3: TIM Channel 3 + * @param TIM_CCxN: specifies the TIM Channel CCxNE bit new state. + * This parameter can be: TIM_CCxN_Enable or TIM_CCxN_Disable. + * @retval None + */ +void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN) +{ + uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_COMPLEMENTARY_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_CCXN(TIM_CCxN)); + + tmp = (uint32_t)CCER_CCNE_SET << (uint32_t)TIM_Channel; + + /* Reset the CCxNE Bit */ + TIMx->CCER &= (uint32_t) ~tmp; + + /* Set or reset the CCxNE Bit */ + TIMx->CCER |= ((uint32_t)TIM_CCxN << (uint32_t)TIM_Channel); +} +/** + * @} + */ + +/** @defgroup TIM_Group3 Input Capture management functions + * @brief Input Capture management functions + * +@verbatim + =============================================================================== + ##### Input Capture management functions ##### + =============================================================================== + + *** TIM Driver: how to use it in Input Capture Mode *** + ======================================================= + [..] + To use the Timer in Input Capture mode, the following steps are mandatory: + + (#) Enable TIM clock using RCC_APBxPeriphClockCmd(RCC_APBxPeriph_TIMx, ENABLE) function + + (#) Configure the TIM pins by configuring the corresponding GPIO pins + + (#) Configure the Time base unit as described in the first part of this driver, + if needed, else the Timer will run with the default configuration: + (++) Autoreload value = 0xFFFF + (++) Prescaler value = 0x0000 + (++) Counter mode = Up counting + (++) Clock Division = TIM_CKD_DIV1 + + (#) Fill the TIM_ICInitStruct with the desired parameters including: + (++) TIM Channel: TIM_Channel + (++) TIM Input Capture polarity: TIM_ICPolarity + (++) TIM Input Capture selection: TIM_ICSelection + (++) TIM Input Capture Prescaler: TIM_ICPrescaler + (++) TIM Input CApture filter value: TIM_ICFilter + + (#) Call TIM_ICInit(TIMx, &TIM_ICInitStruct) to configure the desired channel with the + corresponding configuration and to measure only frequency or duty cycle of the input signal, + or, + Call TIM_PWMIConfig(TIMx, &TIM_ICInitStruct) to configure the desired channels with the + corresponding configuration and to measure the frequency and the duty cycle of the input signal + + (#) Enable the NVIC or the DMA to read the measured frequency. + + (#) Enable the corresponding interrupt (or DMA request) to read the Captured value, + using the function TIM_ITConfig(TIMx, TIM_IT_CCx) (or TIM_DMA_Cmd(TIMx, TIM_DMA_CCx)) + + (#) Call the TIM_Cmd(ENABLE) function to enable the TIM counter. + + (#) Use TIM_GetCapturex(TIMx); to read the captured value. + [..] + (@) All other functions can be used separately to modify, if needed, + a specific feature of the Timer. + +@endverbatim + * @{ + */ + +/** + * @brief Initializes the TIM peripheral according to the specified parameters + * in the TIM_ICInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure that contains + * the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_IC_POLARITY(TIM_ICInitStruct->TIM_ICPolarity)); + assert_param(IS_TIM_IC_SELECTION(TIM_ICInitStruct->TIM_ICSelection)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICInitStruct->TIM_ICPrescaler)); + assert_param(IS_TIM_IC_FILTER(TIM_ICInitStruct->TIM_ICFilter)); + + if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1) + { + /* TI1 Configuration */ + TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_2) + { + /* TI2 Configuration */ + TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_3) + { + /* TI3 Configuration */ + TI3_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC3Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else + { + /* TI4 Configuration */ + TI4_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC4Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } +} + +/** + * @brief Fills each TIM_ICInitStruct member with its default value. + * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure which will + * be initialized. + * @retval None + */ +void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct) +{ + /* Set the default configuration */ + TIM_ICInitStruct->TIM_Channel = TIM_Channel_1; + TIM_ICInitStruct->TIM_ICPolarity = TIM_ICPolarity_Rising; + TIM_ICInitStruct->TIM_ICSelection = TIM_ICSelection_DirectTI; + TIM_ICInitStruct->TIM_ICPrescaler = TIM_ICPSC_DIV1; + TIM_ICInitStruct->TIM_ICFilter = 0x00; +} + +/** + * @brief Configures the TIM peripheral according to the specified parameters + * in the TIM_ICInitStruct to measure an external PWM signal. + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 to select the TIM + * peripheral. + * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure that contains + * the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct) +{ + uint16_t icoppositepolarity = TIM_ICPolarity_Rising; + uint16_t icoppositeselection = TIM_ICSelection_DirectTI; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + + /* Select the Opposite Input Polarity */ + if (TIM_ICInitStruct->TIM_ICPolarity == TIM_ICPolarity_Rising) + { + icoppositepolarity = TIM_ICPolarity_Falling; + } + else + { + icoppositepolarity = TIM_ICPolarity_Rising; + } + /* Select the Opposite Input */ + if (TIM_ICInitStruct->TIM_ICSelection == TIM_ICSelection_DirectTI) + { + icoppositeselection = TIM_ICSelection_IndirectTI; + } + else + { + icoppositeselection = TIM_ICSelection_DirectTI; + } + if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1) + { + /* TI1 Configuration */ + TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + /* TI2 Configuration */ + TI2_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else + { + /* TI2 Configuration */ + TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + /* TI1 Configuration */ + TI1_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } +} + +/** + * @brief Gets the TIMx Input Capture 1 value. + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17 to select the TIM peripheral. + * @retval Capture Compare 1 Register value. + */ +uint32_t TIM_GetCapture1(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + + /* Get the Capture 1 Register value */ + return TIMx->CCR1; +} + +/** + * @brief Gets the TIMx Input Capture 2 value. + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 to select the TIM + * peripheral. + * @retval Capture Compare 2 Register value. + */ +uint32_t TIM_GetCapture2(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + + /* Get the Capture 2 Register value */ + return TIMx->CCR2; +} + +/** + * @brief Gets the TIMx Input Capture 3 value. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @retval Capture Compare 3 Register value. + */ +uint32_t TIM_GetCapture3(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + + /* Get the Capture 3 Register value */ + return TIMx->CCR3; +} + +/** + * @brief Gets the TIMx Input Capture 4 value. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @retval Capture Compare 4 Register value. + */ +uint32_t TIM_GetCapture4(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + + /* Get the Capture 4 Register value */ + return TIMx->CCR4; +} + +/** + * @brief Sets the TIMx Input Capture 1 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture1 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + + /* Reset the IC1PSC Bits */ + TIMx->CCMR1 &= (uint32_t)~TIM_CCMR1_IC1PSC; + + /* Set the IC1PSC value */ + TIMx->CCMR1 |= TIM_ICPSC; +} + +/** + * @brief Sets the TIMx Input Capture 2 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 to select the TIM + * peripheral. + * @param TIM_ICPSC: specifies the Input Capture2 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + + /* Reset the IC2PSC Bits */ + TIMx->CCMR1 &= (uint32_t)~TIM_CCMR1_IC2PSC; + + /* Set the IC2PSC value */ + TIMx->CCMR1 |= (uint32_t)((uint32_t)TIM_ICPSC << 8); +} + +/** + * @brief Sets the TIMx Input Capture 3 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture3 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + + /* Reset the IC3PSC Bits */ + TIMx->CCMR2 &= (uint16_t)~TIM_CCMR2_IC3PSC; + + /* Set the IC3PSC value */ + TIMx->CCMR2 |= TIM_ICPSC; +} + +/** + * @brief Sets the TIMx Input Capture 4 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture4 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + + /* Reset the IC4PSC Bits */ + TIMx->CCMR2 &= (uint16_t)~TIM_CCMR2_IC4PSC; + + /* Set the IC4PSC value */ + TIMx->CCMR2 |= (uint16_t)(TIM_ICPSC << 8); +} +/** + * @} + */ + +/** @defgroup TIM_Group4 Advanced-control timers (TIM1 and TIM8) specific features + * @brief Advanced-control timers (TIM1 and TIM8) specific features + * +@verbatim + =============================================================================== + ##### Advanced-control timers (TIM1 and TIM8) specific features ##### + =============================================================================== + + *** TIM Driver: how to use the Break feature *** + ================================================ + [..] + After configuring the Timer channel(s) in the appropriate Output Compare mode: + + (#) Fill the TIM_BDTRInitStruct with the desired parameters for the Timer + Break Polarity, dead time, Lock level, the OSSI/OSSR State and the + AOE(automatic output enable). + + (#) Call TIM_BDTRConfig(TIMx, &TIM_BDTRInitStruct) to configure the Timer + + (#) Enable the Main Output using TIM_CtrlPWMOutputs(TIM1, ENABLE) + + (#) Once the break even occurs, the Timer's output signals are put in reset + state or in a known state (according to the configuration made in + TIM_BDTRConfig() function). + +@endverbatim + * @{ + */ + +/** + * @brief Configures the Break feature, dead time, Lock level, OSSI/OSSR State + * and the AOE(automatic output enable). + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIM + * @param TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure that + * contains the BDTR Register configuration information for the TIM peripheral. + * @retval None + */ +void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_OSSR_STATE(TIM_BDTRInitStruct->TIM_OSSRState)); + assert_param(IS_TIM_OSSI_STATE(TIM_BDTRInitStruct->TIM_OSSIState)); + assert_param(IS_TIM_LOCK_LEVEL(TIM_BDTRInitStruct->TIM_LOCKLevel)); + assert_param(IS_TIM_BREAK_STATE(TIM_BDTRInitStruct->TIM_Break)); + assert_param(IS_TIM_BREAK_POLARITY(TIM_BDTRInitStruct->TIM_BreakPolarity)); + assert_param(IS_TIM_AUTOMATIC_OUTPUT_STATE(TIM_BDTRInitStruct->TIM_AutomaticOutput)); + + /* Set the Lock level, the Break enable Bit and the Polarity, the OSSR State, + the OSSI State, the dead time value and the Automatic Output Enable Bit */ + TIMx->BDTR = (uint32_t)TIM_BDTRInitStruct->TIM_OSSRState | TIM_BDTRInitStruct->TIM_OSSIState | + TIM_BDTRInitStruct->TIM_LOCKLevel | TIM_BDTRInitStruct->TIM_DeadTime | + TIM_BDTRInitStruct->TIM_Break | TIM_BDTRInitStruct->TIM_BreakPolarity | + TIM_BDTRInitStruct->TIM_AutomaticOutput; +} + +/** + * @brief Configures the Break1 feature. + * @param TIMx: where x can be 1 or 8 to select the TIM + * @param TIM_Break1Polarity: specifies the Break1 polarity. + * This parameter can be one of the following values: + * @arg TIM_Break1Polarity_Low: Break1 input is active low + * @arg TIM_Break1Polarity_High: Break1 input is active high + * @param TIM_Break1Filter: specifies the Break1 filter value. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_Break1Config(TIM_TypeDef* TIMx, uint32_t TIM_Break1Polarity, uint8_t TIM_Break1Filter) +{ /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_BREAK1_FILTER(TIM_Break1Filter)); + + /* Reset the BKP and BKF Bits */ + TIMx->BDTR &= (uint32_t)~ (TIM_BDTR_BKP | TIM_BDTR_BKF); + /* Configure the Break1 polarity and filter */ + TIMx->BDTR |= TIM_Break1Polarity |((uint32_t)TIM_Break1Filter << 16); +} + +/** + * @brief Configures the Break2 feature. + * @param TIMx: where x can be 1 or 8 to select the TIM + * @param TIM_Break2Polarity: specifies the Break2 polarity. + * This parameter can be one of the following values: + * @arg TIM_Break2Polarity_Low: Break2 input is active low + * @arg TIM_Break2Polarity_High: Break2 input is active high + * @param TIM_Break2Filter: specifies the Break2 filter value. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_Break2Config(TIM_TypeDef* TIMx, uint32_t TIM_Break2Polarity, uint8_t TIM_Break2Filter) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_BREAK2_FILTER(TIM_Break2Filter)); + + /* Reset the BKP and BKF Bits */ + TIMx->BDTR &= (uint32_t)~ (TIM_BDTR_BK2P | TIM_BDTR_BK2F); + + /* Configure the Break1 polarity and filter */ + TIMx->BDTR |= TIM_Break2Polarity |((uint32_t)TIM_Break2Filter << 20); +} + +/** + * @brief Enables or disables the TIM Break1 input. + * @param TIMx: where x can be 1, 8, 1, 16 or 17 to select the TIMx peripheral. + * @param NewState: new state of the TIM Break1 input. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_Break1Cmd(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Break1 */ + TIMx->BDTR |= TIM_BDTR_BKE; + } + else + { + /* Disable the Break1 */ + TIMx->BDTR &= (uint32_t)~TIM_BDTR_BKE; + } +} + +/** + * @brief Enables or disables the TIM Break2 input. + * @param TIMx: where x can be 1 or 8 to select the TIMx peripheral. + * @param NewState: new state of the TIM Break2 input. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_Break2Cmd(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Break1 */ + TIMx->BDTR |= TIM_BDTR_BK2E; + } + else + { + /* Disable the Break1 */ + TIMx->BDTR &= (uint32_t)~TIM_BDTR_BK2E; + } +} + +/** + * @brief Fills each TIM_BDTRInitStruct member with its default value. + * @param TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure which + * will be initialized. + * @retval None + */ +void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct) +{ + /* Set the default configuration */ + TIM_BDTRInitStruct->TIM_OSSRState = TIM_OSSRState_Disable; + TIM_BDTRInitStruct->TIM_OSSIState = TIM_OSSIState_Disable; + TIM_BDTRInitStruct->TIM_LOCKLevel = TIM_LOCKLevel_OFF; + TIM_BDTRInitStruct->TIM_DeadTime = 0x00; + TIM_BDTRInitStruct->TIM_Break = TIM_Break_Disable; + TIM_BDTRInitStruct->TIM_BreakPolarity = TIM_BreakPolarity_Low; + TIM_BDTRInitStruct->TIM_AutomaticOutput = TIM_AutomaticOutput_Disable; +} + +/** + * @brief Enables or disables the TIM peripheral Main Outputs. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIMx peripheral. + * @param NewState: new state of the TIM peripheral Main Outputs. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the TIM Main Output */ + TIMx->BDTR |= TIM_BDTR_MOE; + } + else + { + /* Disable the TIM Main Output */ + TIMx->BDTR &= (uint16_t)~TIM_BDTR_MOE; + } +} + +/** + * @brief Selects the TIM peripheral Commutation event. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIMx peripheral + * @param NewState: new state of the Commutation event. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the COM Bit */ + TIMx->CR2 |= TIM_CR2_CCUS; + } + else + { + /* Reset the COM Bit */ + TIMx->CR2 &= (uint16_t)~TIM_CR2_CCUS; + } +} + +/** + * @brief Sets or Resets the TIM peripheral Capture Compare Preload Control bit. + * @param TIMx: where x can be 1 or 8 to select the TIMx peripheral + * @param NewState: new state of the Capture Compare Preload Control bit + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the CCPC Bit */ + TIMx->CR2 |= TIM_CR2_CCPC; + } + else + { + /* Reset the CCPC Bit */ + TIMx->CR2 &= (uint16_t)~TIM_CR2_CCPC; + } +} +/** + * @} + */ + +/** @defgroup TIM_Group5 Interrupts DMA and flags management functions + * @brief Interrupts, DMA and flags management functions + * +@verbatim + =============================================================================== + ##### Interrupts, DMA and flags management functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified TIM interrupts. + * @param TIMx: where x can be 1, 2, 3, 4, 6, 7, 8, 15, 16 or 17 to select the TIMx peripheral. + * @param TIM_IT: specifies the TIM interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg TIM_IT_Update: TIM update Interrupt source + * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source + * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source + * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source + * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source + * @arg TIM_IT_COM: TIM Commutation Interrupt source + * @arg TIM_IT_Trigger: TIM Trigger Interrupt source + * @arg TIM_IT_Break: TIM Break Interrupt source + * + * @note For TIM6 and TIM7 only the parameter TIM_IT_Update can be used + * @note For TIM9 and TIM12 only one of the following parameters can be used: TIM_IT_Update, + * TIM_IT_CC1, TIM_IT_CC2 or TIM_IT_Trigger. + * @note For TIM10, TIM11, TIM13 and TIM14 only one of the following parameters can + * be used: TIM_IT_Update or TIM_IT_CC1 + * @note TIM_IT_COM and TIM_IT_Break can be used only with TIM1 and TIM8 + * + * @param NewState: new state of the TIM interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_IT(TIM_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Interrupt sources */ + TIMx->DIER |= TIM_IT; + } + else + { + /* Disable the Interrupt sources */ + TIMx->DIER &= (uint16_t)~TIM_IT; + } +} + +/** + * @brief Configures the TIMx event to be generate by software. + * @param TIMx: where x can be 1, 2, 3, 4, 6, 7, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_EventSource: specifies the event source. + * This parameter can be one or more of the following values: + * @arg TIM_EventSource_Update: Timer update Event source + * @arg TIM_EventSource_CC1: Timer Capture Compare 1 Event source + * @arg TIM_EventSource_CC2: Timer Capture Compare 2 Event source + * @arg TIM_EventSource_CC3: Timer Capture Compare 3 Event source + * @arg TIM_EventSource_CC4: Timer Capture Compare 4 Event source + * @arg TIM_EventSource_COM: Timer COM event source + * @arg TIM_EventSource_Trigger: Timer Trigger Event source + * @arg TIM_EventSource_Break: Timer Break event source + * + * @note TIM6 and TIM7 can only generate an update event. + * @note TIM_EventSource_COM and TIM_EventSource_Break are used only with TIM1 and TIM8. + * + * @retval None + */ +void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_EVENT_SOURCE(TIM_EventSource)); + + /* Set the event sources */ + TIMx->EGR = TIM_EventSource; +} + +/** + * @brief Checks whether the specified TIM flag is set or not. + * @param TIMx: where x can be 1, 2, 3, 4, 6, 7, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg TIM_FLAG_Update: TIM update Flag + * @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag + * @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag + * @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag + * @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag + * @arg TIM_FLAG_CC5: TIM Capture Compare 5 Flag + * @arg TIM_FLAG_CC6: TIM Capture Compare 6 Flag + * @arg TIM_FLAG_COM: TIM Commutation Flag + * @arg TIM_FLAG_Trigger: TIM Trigger Flag + * @arg TIM_FLAG_Break: TIM Break Flag + * @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 over capture Flag + * @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 over capture Flag + * @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 over capture Flag + * @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 over capture Flag + * + * @note TIM6 and TIM7 can have only one update flag. + * @note TIM_FLAG_COM and TIM_FLAG_Break are used only with TIM1 and TIM8. + * + * @retval The new state of TIM_FLAG (SET or RESET). + */ +FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint32_t TIM_FLAG) +{ + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_GET_FLAG(TIM_FLAG)); + + + if ((TIMx->SR & TIM_FLAG) != RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the TIMx's pending flags. + * @param TIMx: where x can be 1, 2, 3, 4, 6, 7, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_FLAG: specifies the flag bit to clear. + * This parameter can be any combination of the following values: + * @arg TIM_FLAG_Update: TIM update Flag + * @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag + * @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag + * @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag + * @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag + * @arg TIM_FLAG_CC5: TIM Capture Compare 5 Flag + * @arg TIM_FLAG_CC6: TIM Capture Compare 6 Flag + * @arg TIM_FLAG_COM: TIM Commutation Flag + * @arg TIM_FLAG_Trigger: TIM Trigger Flag + * @arg TIM_FLAG_Break: TIM Break Flag + * @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 over capture Flag + * @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 over capture Flag + * @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 over capture Flag + * @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 over capture Flag + * + * @note TIM6 and TIM7 can have only one update flag. + * @note TIM_FLAG_COM and TIM_FLAG_Break are used only with TIM1 and TIM8. + * + * @retval None + */ +void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + /* Clear the flags */ + TIMx->SR = (uint16_t)~TIM_FLAG; +} + +/** + * @brief Checks whether the TIM interrupt has occurred or not. + * @param TIMx: where x can be 1, 2, 3, 4, 6, 7, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_IT: specifies the TIM interrupt source to check. + * This parameter can be one of the following values: + * @arg TIM_IT_Update: TIM update Interrupt source + * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source + * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source + * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source + * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source + * @arg TIM_IT_COM: TIM Commutation Interrupt source + * @arg TIM_IT_Trigger: TIM Trigger Interrupt source + * @arg TIM_IT_Break: TIM Break Interrupt source + * + * @note TIM6 and TIM7 can generate only an update interrupt. + * @note TIM_IT_COM and TIM_IT_Break are used only with TIM1 and TIM8. + * + * @retval The new state of the TIM_IT(SET or RESET). + */ +ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT) +{ + ITStatus bitstatus = RESET; + uint16_t itstatus = 0x0, itenable = 0x0; + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_GET_IT(TIM_IT)); + + itstatus = TIMx->SR & TIM_IT; + + itenable = TIMx->DIER & TIM_IT; + if ((itstatus != (uint16_t)RESET) && (itenable != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the TIMx's interrupt pending bits. + * @param TIMx: where x can be 1, 2, 3, 4, 6, 7, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_IT: specifies the pending bit to clear. + * This parameter can be any combination of the following values: + * @arg TIM_IT_Update: TIM1 update Interrupt source + * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source + * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source + * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source + * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source + * @arg TIM_IT_COM: TIM Commutation Interrupt source + * @arg TIM_IT_Trigger: TIM Trigger Interrupt source + * @arg TIM_IT_Break: TIM Break Interrupt source + * + * @note TIM6 and TIM7 can generate only an update interrupt. + * @note TIM_IT_COM and TIM_IT_Break are used only with TIM1 and TIM8. + * + * @retval None + */ +void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + /* Clear the IT pending Bit */ + TIMx->SR = (uint16_t)~TIM_IT; +} + +/** + * @brief Configures the TIMx's DMA interface. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_DMABase: DMA Base address. + * This parameter can be one of the following values: + * @arg TIM_DMABase_CR1 + * @arg TIM_DMABase_CR2 + * @arg TIM_DMABase_SMCR + * @arg TIM_DMABase_DIER + * @arg TIM1_DMABase_SR + * @arg TIM_DMABase_EGR + * @arg TIM_DMABase_CCMR1 + * @arg TIM_DMABase_CCMR2 + * @arg TIM_DMABase_CCER + * @arg TIM_DMABase_CNT + * @arg TIM_DMABase_PSC + * @arg TIM_DMABase_ARR + * @arg TIM_DMABase_RCR + * @arg TIM_DMABase_CCR1 + * @arg TIM_DMABase_CCR2 + * @arg TIM_DMABase_CCR3 + * @arg TIM_DMABase_CCR4 + * @arg TIM_DMABase_BDTR + * @arg TIM_DMABase_DCR + * @param TIM_DMABurstLength: DMA Burst length. This parameter can be one value + * between: TIM_DMABurstLength_1Transfer and TIM_DMABurstLength_18Transfers. + * @retval None + */ +void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_DMA_BASE(TIM_DMABase)); + assert_param(IS_TIM_DMA_LENGTH(TIM_DMABurstLength)); + + /* Set the DMA Base and the DMA Burst Length */ + TIMx->DCR = TIM_DMABase | TIM_DMABurstLength; +} + +/** + * @brief Enables or disables the TIMx's DMA Requests. + * @param TIMx: where x can be 1, 2, 3, 4, 6, 7, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_DMASource: specifies the DMA Request sources. + * This parameter can be any combination of the following values: + * @arg TIM_DMA_Update: TIM update Interrupt source + * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source + * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source + * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source + * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source + * @arg TIM_DMA_COM: TIM Commutation DMA source + * @arg TIM_DMA_Trigger: TIM Trigger DMA source + * @param NewState: new state of the DMA Request sources. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_DMA_SOURCE(TIM_DMASource)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the DMA sources */ + TIMx->DIER |= TIM_DMASource; + } + else + { + /* Disable the DMA sources */ + TIMx->DIER &= (uint16_t)~TIM_DMASource; + } +} + +/** + * @brief Selects the TIMx peripheral Capture Compare DMA source. + * @param TIMx: where x can be 1, 2, 3, 4, 8, 15, 16 or 17 to select the TIM peripheral. + * @param NewState: new state of the Capture Compare DMA source + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the CCDS Bit */ + TIMx->CR2 |= TIM_CR2_CCDS; + } + else + { + /* Reset the CCDS Bit */ + TIMx->CR2 &= (uint16_t)~TIM_CR2_CCDS; + } +} +/** + * @} + */ + +/** @defgroup TIM_Group6 Clocks management functions + * @brief Clocks management functions + * +@verbatim + =============================================================================== + ##### Clocks management functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Configures the TIMx internal Clock + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 to select the TIM + * peripheral. + * @retval None + */ +void TIM_InternalClockConfig(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + + /* Disable slave mode to clock the prescaler directly with the internal clock */ + TIMx->SMCR &= (uint16_t)~TIM_SMCR_SMS; +} + +/** + * @brief Configures the TIMx Internal Trigger as External Clock + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 to select the TIM + * peripheral. + * @param TIM_InputTriggerSource: Trigger source. + * This parameter can be one of the following values: + * @arg TIM_TS_ITR0: Internal Trigger 0 + * @arg TIM_TS_ITR1: Internal Trigger 1 + * @arg TIM_TS_ITR2: Internal Trigger 2 + * @arg TIM_TS_ITR3: Internal Trigger 3 + * @retval None + */ +void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_INTERNAL_TRIGGER_SELECTION(TIM_InputTriggerSource)); + + /* Select the Internal Trigger */ + TIM_SelectInputTrigger(TIMx, TIM_InputTriggerSource); + + /* Select the External clock mode1 */ + TIMx->SMCR |= TIM_SlaveMode_External1; +} + +/** + * @brief Configures the TIMx Trigger as External Clock + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 + * to select the TIM peripheral. + * @param TIM_TIxExternalCLKSource: Trigger source. + * This parameter can be one of the following values: + * @arg TIM_TIxExternalCLK1Source_TI1ED: TI1 Edge Detector + * @arg TIM_TIxExternalCLK1Source_TI1: Filtered Timer Input 1 + * @arg TIM_TIxExternalCLK1Source_TI2: Filtered Timer Input 2 + * @param TIM_ICPolarity: specifies the TIx Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param ICFilter: specifies the filter value. + * This parameter must be a value between 0x0 and 0xF. + * @retval None + */ +void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource, + uint16_t TIM_ICPolarity, uint16_t ICFilter) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_IC_POLARITY(TIM_ICPolarity)); + assert_param(IS_TIM_IC_FILTER(ICFilter)); + + /* Configure the Timer Input Clock Source */ + if (TIM_TIxExternalCLKSource == TIM_TIxExternalCLK1Source_TI2) + { + TI2_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter); + } + else + { + TI1_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter); + } + /* Select the Trigger source */ + TIM_SelectInputTrigger(TIMx, TIM_TIxExternalCLKSource); + /* Select the External clock mode1 */ + TIMx->SMCR |= TIM_SlaveMode_External1; +} + +/** + * @brief Configures the External clock Mode1 + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. + * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. + * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. + * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity: The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. + * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. + * @param ExtTRGFilter: External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, + uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter) +{ + uint16_t tmpsmcr = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); + assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); + assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); + /* Configure the ETR Clock source */ + TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter); + + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + + /* Reset the SMS Bits */ + tmpsmcr &= (uint16_t)~TIM_SMCR_SMS; + + /* Select the External clock mode1 */ + tmpsmcr |= TIM_SlaveMode_External1; + + /* Select the Trigger selection : ETRF */ + tmpsmcr &= (uint16_t)~TIM_SMCR_TS; + tmpsmcr |= TIM_TS_ETRF; + + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} + +/** + * @brief Configures the External clock Mode2 + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. + * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. + * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. + * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity: The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. + * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. + * @param ExtTRGFilter: External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, + uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); + assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); + assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); + + /* Configure the ETR Clock source */ + TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter); + + /* Enable the External clock mode2 */ + TIMx->SMCR |= TIM_SMCR_ECE; +} +/** + * @} + */ + +/** @defgroup TIM_Group7 Synchronization management functions + * @brief Synchronization management functions + * +@verbatim + =============================================================================== + ##### Synchronization management functions ##### + =============================================================================== + + *** TIM Driver: how to use it in synchronization Mode *** + ========================================================= + [..] Case of two/several Timers + + (#) Configure the Master Timers using the following functions: + (++) void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource); + (++) void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode); + (#) Configure the Slave Timers using the following functions: + (++) void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); + (++) void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode); + + [..] Case of Timers and external trigger(ETR pin) + + (#) Configure the External trigger using this function: + (++) void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter); + (#) Configure the Slave Timers using the following functions: + (++) void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); + (++) void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode); + +@endverbatim + * @{ + */ + +/** + * @brief Selects the Input Trigger source + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 + * to select the TIM peripheral. + * @param TIM_InputTriggerSource: The Input Trigger source. + * This parameter can be one of the following values: + * @arg TIM_TS_ITR0: Internal Trigger 0 + * @arg TIM_TS_ITR1: Internal Trigger 1 + * @arg TIM_TS_ITR2: Internal Trigger 2 + * @arg TIM_TS_ITR3: Internal Trigger 3 + * @arg TIM_TS_TI1F_ED: TI1 Edge Detector + * @arg TIM_TS_TI1FP1: Filtered Timer Input 1 + * @arg TIM_TS_TI2FP2: Filtered Timer Input 2 + * @arg TIM_TS_ETRF: External Trigger input + * @retval None + */ +void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource) +{ + uint16_t tmpsmcr = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_TRIGGER_SELECTION(TIM_InputTriggerSource)); + + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + + /* Reset the TS Bits */ + tmpsmcr &= (uint16_t)~TIM_SMCR_TS; + + /* Set the Input Trigger source */ + tmpsmcr |= TIM_InputTriggerSource; + + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} + +/** + * @brief Selects the TIMx Trigger Output Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 6, 7, 8 or 15 to select the TIM peripheral. + * + * @param TIM_TRGOSource: specifies the Trigger Output source. + * This parameter can be one of the following values: + * + * - For all TIMx + * @arg TIM_TRGOSource_Reset: The UG bit in the TIM_EGR register is used as the trigger output(TRGO) + * @arg TIM_TRGOSource_Enable: The Counter Enable CEN is used as the trigger output(TRGO) + * @arg TIM_TRGOSource_Update: The update event is selected as the trigger output(TRGO) + * + * - For all TIMx except TIM6 and TIM7 + * @arg TIM_TRGOSource_OC1: The trigger output sends a positive pulse when the CC1IF flag + * is to be set, as soon as a capture or compare match occurs(TRGO) + * @arg TIM_TRGOSource_OC1Ref: OC1REF signal is used as the trigger output(TRGO) + * @arg TIM_TRGOSource_OC2Ref: OC2REF signal is used as the trigger output(TRGO) + * @arg TIM_TRGOSource_OC3Ref: OC3REF signal is used as the trigger output(TRGO) + * @arg TIM_TRGOSource_OC4Ref: OC4REF signal is used as the trigger output(TRGO) + * + * @retval None + */ +void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST7_PERIPH(TIMx)); + assert_param(IS_TIM_TRGO_SOURCE(TIM_TRGOSource)); + + /* Reset the MMS Bits */ + TIMx->CR2 &= (uint16_t)~TIM_CR2_MMS; + /* Select the TRGO source */ + TIMx->CR2 |= TIM_TRGOSource; +} + +/** + * @brief Selects the TIMx Trigger Output Mode2 (TRGO2). + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * + * @param TIM_TRGO2Source: specifies the Trigger Output source. + * This parameter can be one of the following values: + * + * - For all TIMx + * @arg TIM_TRGOSource_Reset: The UG bit in the TIM_EGR register is used as the trigger output(TRGO2) + * @arg TIM_TRGOSource_Enable: The Counter Enable CEN is used as the trigger output(TRGO2) + * @arg TIM_TRGOSource_Update: The update event is selected as the trigger output(TRGO2) + * @arg TIM_TRGOSource_OC1: The trigger output sends a positive pulse when the CC1IF flag + * is to be set, as soon as a capture or compare match occurs(TRGO2) + * @arg TIM_TRGOSource_OC1Ref: OC1REF signal is used as the trigger output(TRGO2) + * @arg TIM_TRGOSource_OC2Ref: OC2REF signal is used as the trigger output(TRGO2) + * @arg TIM_TRGOSource_OC3Ref: OC3REF signal is used as the trigger output(TRGO2) + * @arg TIM_TRGOSource_OC4Ref: OC4REF signal is used as the trigger output(TRGO2) + * @arg TIM_TRGO2Source_OC4Ref_RisingFalling: OC4Ref Rising and Falling are used as the trigger output(TRGO2) + * @arg TIM_TRGO2Source_OC6Ref_RisingFalling: OC6Ref Rising and Falling are used as the trigger output(TRGO2) + * @arg TIM_TRGO2Source_OC4RefRising_OC6RefRising: OC4Ref Rising and OC6Ref Rising are used as the trigger output(TRGO2) + * @arg TIM_TRGO2Source_OC4RefRising_OC6RefFalling: OC4Ref Rising and OC6Ref Falling are used as the trigger output(TRGO2) + * @arg TIM_TRGO2Source_OC5RefRising_OC6RefRising: OC5Ref Rising and OC6Ref Rising are used as the trigger output(TRGO2) + * @arg TIM_TRGO2Source_OC5RefRising_OC6RefFalling: OC5Ref Rising and OC6Ref Falling are used as the trigger output(TRGO2) + * + * @retval None + */ +void TIM_SelectOutputTrigger2(TIM_TypeDef* TIMx, uint32_t TIM_TRGO2Source) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_TRGO2_SOURCE(TIM_TRGO2Source)); + + /* Reset the MMS Bits */ + TIMx->CR2 &= (uint32_t)~TIM_CR2_MMS2; + /* Select the TRGO source */ + TIMx->CR2 |= TIM_TRGO2Source; +} + +/** + * @brief Selects the TIMx Slave Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 to select the TIM peripheral. + * @param TIM_SlaveMode: specifies the Timer Slave Mode. + * This parameter can be one of the following values: + * @arg TIM_SlaveMode_Reset: Rising edge of the selected trigger signal(TRGI) reinitialize + * the counter and triggers an update of the registers + * @arg TIM_SlaveMode_Gated: The counter clock is enabled when the trigger signal (TRGI) is high + * @arg TIM_SlaveMode_Trigger: The counter starts at a rising edge of the trigger TRGI + * @arg TIM_SlaveMode_External1: Rising edges of the selected trigger (TRGI) clock the counter + * @arg TIM_SlaveMode_Combined_ResetTrigger: Rising edge of the selected trigger input (TRGI) + * reinitializes the counter, generates an update + * of the registers and starts the counter. + * @retval None + */ +void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint32_t TIM_SlaveMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_SLAVE_MODE(TIM_SlaveMode)); + + /* Reset the SMS Bits */ + TIMx->SMCR &= (uint32_t)~TIM_SMCR_SMS; + + /* Select the Slave Mode */ + TIMx->SMCR |= (uint32_t)TIM_SlaveMode; +} + +/** + * @brief Sets or Resets the TIMx Master/Slave Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 to select the TIM peripheral. + * @param TIM_MasterSlaveMode: specifies the Timer Master Slave Mode. + * This parameter can be one of the following values: + * @arg TIM_MasterSlaveMode_Enable: synchronization between the current timer + * and its slaves (through TRGO) + * @arg TIM_MasterSlaveMode_Disable: No action + * @retval None + */ +void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_MSM_STATE(TIM_MasterSlaveMode)); + + /* Reset the MSM Bit */ + TIMx->SMCR &= (uint16_t)~TIM_SMCR_MSM; + + /* Set or Reset the MSM Bit */ + TIMx->SMCR |= TIM_MasterSlaveMode; +} + +/** + * @brief Configures the TIMx External Trigger (ETR). + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM peripheral. + * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. + * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. + * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. + * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity: The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. + * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. + * @param ExtTRGFilter: External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, + uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter) +{ + uint16_t tmpsmcr = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); + assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); + assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); + + tmpsmcr = TIMx->SMCR; + + /* Reset the ETR Bits */ + tmpsmcr &= SMCR_ETR_MASK; + + /* Set the Prescaler, the Filter value and the Polarity */ + tmpsmcr |= (uint16_t)(TIM_ExtTRGPrescaler | (uint16_t)(TIM_ExtTRGPolarity | (uint16_t)(ExtTRGFilter << (uint16_t)8))); + + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} +/** + * @} + */ + +/** @defgroup TIM_Group8 Specific interface management functions + * @brief Specific interface management functions + * +@verbatim + =============================================================================== + ##### Specific interface management functions ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Configures the TIMx Encoder Interface. + * @param TIMx: where x can be 1, 2, 3, 4 or 8 to select the TIM + * peripheral. + * @param TIM_EncoderMode: specifies the TIMx Encoder Mode. + * This parameter can be one of the following values: + * @arg TIM_EncoderMode_TI1: Counter counts on TI1FP1 edge depending on TI2FP2 level. + * @arg TIM_EncoderMode_TI2: Counter counts on TI2FP2 edge depending on TI1FP1 level. + * @arg TIM_EncoderMode_TI12: Counter counts on both TI1FP1 and TI2FP2 edges depending + * on the level of the other input. + * @param TIM_IC1Polarity: specifies the IC1 Polarity + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Falling: IC Falling edge. + * @arg TIM_ICPolarity_Rising: IC Rising edge. + * @param TIM_IC2Polarity: specifies the IC2 Polarity + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Falling: IC Falling edge. + * @arg TIM_ICPolarity_Rising: IC Rising edge. + * @retval None + */ +void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode, + uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity) +{ + uint16_t tmpsmcr = 0; + uint16_t tmpccmr1 = 0; + uint16_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_ENCODER_MODE(TIM_EncoderMode)); + assert_param(IS_TIM_IC_POLARITY(TIM_IC1Polarity)); + assert_param(IS_TIM_IC_POLARITY(TIM_IC2Polarity)); + + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = TIMx->CCMR1; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + + /* Set the encoder Mode */ + tmpsmcr &= (uint16_t)~TIM_SMCR_SMS; + tmpsmcr |= TIM_EncoderMode; + + /* Select the Capture Compare 1 and the Capture Compare 2 as input */ + tmpccmr1 &= ((uint16_t)~TIM_CCMR1_CC1S) & ((uint16_t)~TIM_CCMR1_CC2S); + tmpccmr1 |= TIM_CCMR1_CC1S_0 | TIM_CCMR1_CC2S_0; + + /* Set the TI1 and the TI2 Polarities */ + tmpccer &= ((uint16_t)~TIM_CCER_CC1P) & ((uint16_t)~TIM_CCER_CC2P); + tmpccer |= (uint16_t)(TIM_IC1Polarity | (uint16_t)(TIM_IC2Polarity << (uint16_t)4)); + + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmr1; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Enables or disables the TIMx's Hall sensor interface. + * @param TIMx: where x can be 1, 2, 3, 4, 8 or 15 to select the TIM + * peripheral. + * @param NewState: new state of the TIMx Hall sensor interface. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Set the TI1S Bit */ + TIMx->CR2 |= TIM_CR2_TI1S; + } + else + { + /* Reset the TI1S Bit */ + TIMx->CR2 &= (uint16_t)~TIM_CR2_TI1S; + } +} +/** + * @} + */ + +/** @defgroup TIM_Group9 Specific remapping management function + * @brief Specific remapping management function + * +@verbatim + =============================================================================== + ##### Specific remapping management function ##### + =============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Configures the TIM16 Remapping input Capabilities. + * @param TIMx: where x can be 1, 8 or 16 to select the TIM peripheral. + * @param TIM_Remap: specifies the TIM input reampping source. + * This parameter can be one of the following values: + * @arg TIM16_GPIO: TIM16 Channel 1 is connected to GPIO. + * @arg TIM16_RTC_CLK: TIM16 Channel 1 is connected to RTC input clock. + * @arg TIM16_HSE_DIV32: TIM16 Channel 1 is connected to HSE/32 clock. + * @arg TIM16_MCO: TIM16 Channel 1 is connected to MCO clock. + * @arg TIM1_ADC1_AWDG1: TIM1 ETR is connected to ADC1 AWDG1. + * @arg TIM1_ADC1_AWDG2: TIM1 ETR is connected to ADC1 AWDG2. + * @arg TIM1_ADC1_AWDG3: TIM1 ETR is connected to ADC1 AWDG3. + * @arg TIM1_ADC4_AWDG1: TIM1 ETR is connected to ADC4 AWDG1. + * @arg TIM1_ADC4_AWDG2: TIM1 ETR is connected to ADC4 AWDG2. + * @arg TIM1_ADC4_AWDG3: TIM1 ETR is connected to ADC4 AWDG3. + * @arg TIM8_ADC2_AWDG1: TIM8 ETR is connected to ADC2 AWDG1. + * @arg TIM8_ADC2_AWDG2: TIM8 ETR is connected to ADC2 AWDG2. + * @arg TIM8_ADC2_AWDG3: TIM8 ETR is connected to ADC2 AWDG3. + * @arg TIM8_ADC4_AWDG1: TIM8 ETR is connected to ADC4 AWDG1. + * @arg TIM8_ADC4_AWDG2: TIM8 ETR is connected to ADC4 AWDG2. + * @arg TIM8_ADC4_AWDG3: TIM8 ETR is connected to ADC4 AWDG3. + * @retval : None + */ +void TIM_RemapConfig(TIM_TypeDef* TIMx, uint16_t TIM_Remap) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_REMAP(TIM_Remap)); + + /* Set the Timer remapping configuration */ + TIMx->OR = TIM_Remap; +} +/** + * @} + */ + +/** + * @brief Configure the TI1 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 10, 11, 12, 13 or 14 + * to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @arg TIM_ICPolarity_BothEdge + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 1 is selected to be connected to IC1. + * @arg TIM_ICSelection_IndirectTI: TIM Input 1 is selected to be connected to IC2. + * @arg TIM_ICSelection_TRC: TIM Input 1 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint32_t tmpccmr1 = 0, tmpccer = 0; + + /* Disable the Channel 1: Reset the CC1E Bit */ + TIMx->CCER &= (uint32_t)~TIM_CCER_CC1E; + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + + /* Select the Input and set the filter */ + tmpccmr1 &= ((uint32_t)~TIM_CCMR1_CC1S) & ((uint32_t)~TIM_CCMR1_IC1F); + tmpccmr1 |= (uint32_t)(TIM_ICSelection | (uint32_t)((uint32_t)TIM_ICFilter << 4)); + + /* Select the Polarity and set the CC1E Bit */ + tmpccer &= (uint32_t)~(TIM_CCER_CC1P | TIM_CCER_CC1NP); + tmpccer |= (uint32_t)(TIM_ICPolarity | (uint32_t)TIM_CCER_CC1E); + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI2 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM + * peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @arg TIM_ICPolarity_BothEdge + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 2 is selected to be connected to IC2. + * @arg TIM_ICSelection_IndirectTI: TIM Input 2 is selected to be connected to IC1. + * @arg TIM_ICSelection_TRC: TIM Input 2 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint32_t tmpccmr1 = 0, tmpccer = 0, tmp = 0; + + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= (uint16_t)~TIM_CCER_CC2E; + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + tmp = (uint16_t)(TIM_ICPolarity << 4); + + /* Select the Input and set the filter */ + tmpccmr1 &= ((uint32_t)~TIM_CCMR1_CC2S) & ((uint32_t)~TIM_CCMR1_IC2F); + tmpccmr1 |= (uint32_t)((uint32_t)TIM_ICFilter << 12); + tmpccmr1 |= (uint32_t)((uint32_t)TIM_ICSelection << 8); + + /* Select the Polarity and set the CC2E Bit */ + tmpccer &= (uint16_t)~(TIM_CCER_CC2P | TIM_CCER_CC2NP); + tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC2E); + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1 ; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI3 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @arg TIM_ICPolarity_BothEdge + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 3 is selected to be connected to IC3. + * @arg TIM_ICSelection_IndirectTI: TIM Input 3 is selected to be connected to IC4. + * @arg TIM_ICSelection_TRC: TIM Input 3 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0; + + /* Disable the Channel 3: Reset the CC3E Bit */ + TIMx->CCER &= (uint16_t)~TIM_CCER_CC3E; + tmpccmr2 = TIMx->CCMR2; + tmpccer = TIMx->CCER; + tmp = (uint16_t)(TIM_ICPolarity << 8); + + /* Select the Input and set the filter */ + tmpccmr2 &= ((uint16_t)~TIM_CCMR1_CC1S) & ((uint16_t)~TIM_CCMR2_IC3F); + tmpccmr2 |= (uint16_t)(TIM_ICSelection | (uint16_t)(TIM_ICFilter << (uint16_t)4)); + + /* Select the Polarity and set the CC3E Bit */ + tmpccer &= (uint16_t)~(TIM_CCER_CC3P | TIM_CCER_CC3NP); + tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC3E); + + /* Write to TIMx CCMR2 and CCER registers */ + TIMx->CCMR2 = tmpccmr2; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI4 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @arg TIM_ICPolarity_BothEdge + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 4 is selected to be connected to IC4. + * @arg TIM_ICSelection_IndirectTI: TIM Input 4 is selected to be connected to IC3. + * @arg TIM_ICSelection_TRC: TIM Input 4 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0; + + /* Disable the Channel 4: Reset the CC4E Bit */ + TIMx->CCER &= (uint16_t)~TIM_CCER_CC4E; + tmpccmr2 = TIMx->CCMR2; + tmpccer = TIMx->CCER; + tmp = (uint16_t)(TIM_ICPolarity << 12); + + /* Select the Input and set the filter */ + tmpccmr2 &= ((uint16_t)~TIM_CCMR1_CC2S) & ((uint16_t)~TIM_CCMR1_IC2F); + tmpccmr2 |= (uint16_t)(TIM_ICSelection << 8); + tmpccmr2 |= (uint16_t)(TIM_ICFilter << 12); + + /* Select the Polarity and set the CC4E Bit */ + tmpccer &= (uint16_t)~(TIM_CCER_CC4P | TIM_CCER_CC4NP); + tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC4E); + + /* Write to TIMx CCMR2 and CCER registers */ + TIMx->CCMR2 = tmpccmr2; + TIMx->CCER = tmpccer ; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_usart.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_usart.c new file mode 100644 index 0000000..1b69b83 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_usart.c @@ -0,0 +1,2084 @@ +/** + ****************************************************************************** + * @file stm32f30x_usart.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the Universal synchronous asynchronous receiver + * transmitter (USART): + * + Initialization and Configuration + * + STOP Mode + * + AutoBaudRate + * + Data transfers + * + Multi-Processor Communication + * + LIN mode + * + Half-duplex mode + * + Smartcard mode + * + IrDA mode + * + RS485 mode + * + DMA transfers management + * + Interrupts and flags management + * + * @verbatim + =============================================================================== + ##### How to use this driver ##### + =============================================================================== + [..] + (#) Enable peripheral clock using RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE) + function for USART1 or using RCC_APB1PeriphClockCmd(RCC_APB1Periph_USARTx, ENABLE) + function for USART2, USART3, UART4 and UART5. + (#) According to the USART mode, enable the GPIO clocks using + RCC_AHBPeriphClockCmd() function. (The I/O can be TX, RX, CTS, + or and SCLK). + (#) Peripheral's alternate function: + (++) Connect the pin to the desired peripherals' Alternate + Function (AF) using GPIO_PinAFConfig() function. + (++) Configure the desired pin in alternate function by: + GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF. + (++) Select the type, pull-up/pull-down and output speed via + GPIO_PuPd, GPIO_OType and GPIO_Speed members. + (++) Call GPIO_Init() function. + (#) Program the Baud Rate, Word Length , Stop Bit, Parity, Hardware + flow control and Mode(Receiver/Transmitter) using the SPI_Init() + function. + (#) For synchronous mode, enable the clock and program the polarity, + phase and last bit using the USART_ClockInit() function. + (#) Enable the USART using the USART_Cmd() function. + (#) Enable the NVIC and the corresponding interrupt using the function + USART_ITConfig() if you need to use interrupt mode. + (#) When using the DMA mode: + (++) Configure the DMA using DMA_Init() function. + (++) Activate the needed channel Request using USART_DMACmd() function. + (#) Enable the DMA using the DMA_Cmd() function, when using DMA mode. + [..] + Refer to Multi-Processor, LIN, half-duplex, Smartcard, IrDA sub-sections + for more details. + + @endverbatim + + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_usart.h" +#include "stm32f30x_rcc.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup USART + * @brief USART driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ + +/*!< USART CR1 register clear Mask ((~(uint32_t)0xFFFFE6F3)) */ +#define CR1_CLEAR_MASK ((uint32_t)(USART_CR1_M | USART_CR1_PCE | \ + USART_CR1_PS | USART_CR1_TE | \ + USART_CR1_RE)) + +/*!< USART CR2 register clock bits clear Mask ((~(uint32_t)0xFFFFF0FF)) */ +#define CR2_CLOCK_CLEAR_MASK ((uint32_t)(USART_CR2_CLKEN | USART_CR2_CPOL | \ + USART_CR2_CPHA | USART_CR2_LBCL)) + +/*!< USART CR3 register clear Mask ((~(uint32_t)0xFFFFFCFF)) */ +#define CR3_CLEAR_MASK ((uint32_t)(USART_CR3_RTSE | USART_CR3_CTSE)) + +/*!< USART Interrupts mask */ +#define IT_MASK ((uint32_t)0x000000FF) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup USART_Private_Functions + * @{ + */ + +/** @defgroup USART_Group1 Initialization and Configuration functions + * @brief Initialization and Configuration functions + * +@verbatim + =============================================================================== + ##### Initialization and Configuration functions ##### + =============================================================================== + [..] + This subsection provides a set of functions allowing to initialize the USART + in asynchronous and in synchronous modes. + (+) For the asynchronous mode only these parameters can be configured: + (++) Baud Rate. + (++) Word Length. + (++) Stop Bit. + (++) Parity: If the parity is enabled, then the MSB bit of the data written + in the data register is transmitted but is changed by the parity bit. + Depending on the frame length defined by the M bit (8-bits or 9-bits), + the possible USART frame formats are as listed in the following table: + [..] + +-------------------------------------------------------------+ + | M bit | PCE bit | USART frame | + |---------------------|---------------------------------------| + | 0 | 0 | | SB | 8 bit data | STB | | + |---------|-----------|---------------------------------------| + | 0 | 1 | | SB | 7 bit data | PB | STB | | + |---------|-----------|---------------------------------------| + | 1 | 0 | | SB | 9 bit data | STB | | + |---------|-----------|---------------------------------------| + | 1 | 1 | | SB | 8 bit data | PB | STB | | + +-------------------------------------------------------------+ + [..] + (++) Hardware flow control. + (++) Receiver/transmitter modes. + [..] The USART_Init() function follows the USART asynchronous configuration + procedure(details for the procedure are available in reference manual. + (+) For the synchronous mode in addition to the asynchronous mode parameters + these parameters should be also configured: + (++) USART Clock Enabled. + (++) USART polarity. + (++) USART phase. + (++) USART LastBit. + [..] These parameters can be configured using the USART_ClockInit() function. + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the USARTx peripheral registers to their default reset values. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @retval None + */ +void USART_DeInit(USART_TypeDef* USARTx) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + if (USARTx == USART1) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, DISABLE); + } + else if (USARTx == USART2) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, DISABLE); + } + else if (USARTx == USART3) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, DISABLE); + } + else if (USARTx == UART4) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, DISABLE); + } + else + { + if (USARTx == UART5) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, DISABLE); + } + } +} + +/** + * @brief Initializes the USARTx peripheral according to the specified + * parameters in the USART_InitStruct . + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_InitStruct: pointer to a USART_InitTypeDef structure + * that contains the configuration information for the specified USART peripheral. + * @retval None + */ +void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct) +{ + uint32_t divider = 0, apbclock = 0, tmpreg = 0; + RCC_ClocksTypeDef RCC_ClocksStatus; + + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_BAUDRATE(USART_InitStruct->USART_BaudRate)); + assert_param(IS_USART_WORD_LENGTH(USART_InitStruct->USART_WordLength)); + assert_param(IS_USART_STOPBITS(USART_InitStruct->USART_StopBits)); + assert_param(IS_USART_PARITY(USART_InitStruct->USART_Parity)); + assert_param(IS_USART_MODE(USART_InitStruct->USART_Mode)); + assert_param(IS_USART_HARDWARE_FLOW_CONTROL(USART_InitStruct->USART_HardwareFlowControl)); + + /* Disable USART */ + USARTx->CR1 &= (uint32_t)~((uint32_t)USART_CR1_UE); + + /*---------------------------- USART CR2 Configuration -----------------------*/ + tmpreg = USARTx->CR2; + /* Clear STOP[13:12] bits */ + tmpreg &= (uint32_t)~((uint32_t)USART_CR2_STOP); + + /* Configure the USART Stop Bits, Clock, CPOL, CPHA and LastBit ------------*/ + /* Set STOP[13:12] bits according to USART_StopBits value */ + tmpreg |= (uint32_t)USART_InitStruct->USART_StopBits; + + /* Write to USART CR2 */ + USARTx->CR2 = tmpreg; + + /*---------------------------- USART CR1 Configuration -----------------------*/ + tmpreg = USARTx->CR1; + /* Clear M, PCE, PS, TE and RE bits */ + tmpreg &= (uint32_t)~((uint32_t)CR1_CLEAR_MASK); + + /* Configure the USART Word Length, Parity and mode ----------------------- */ + /* Set the M bits according to USART_WordLength value */ + /* Set PCE and PS bits according to USART_Parity value */ + /* Set TE and RE bits according to USART_Mode value */ + tmpreg |= (uint32_t)USART_InitStruct->USART_WordLength | USART_InitStruct->USART_Parity | + USART_InitStruct->USART_Mode; + + /* Write to USART CR1 */ + USARTx->CR1 = tmpreg; + + /*---------------------------- USART CR3 Configuration -----------------------*/ + tmpreg = USARTx->CR3; + /* Clear CTSE and RTSE bits */ + tmpreg &= (uint32_t)~((uint32_t)CR3_CLEAR_MASK); + + /* Configure the USART HFC -------------------------------------------------*/ + /* Set CTSE and RTSE bits according to USART_HardwareFlowControl value */ + tmpreg |= USART_InitStruct->USART_HardwareFlowControl; + + /* Write to USART CR3 */ + USARTx->CR3 = tmpreg; + + /*---------------------------- USART BRR Configuration -----------------------*/ + /* Configure the USART Baud Rate -------------------------------------------*/ + RCC_GetClocksFreq(&RCC_ClocksStatus); + + if (USARTx == USART1) + { + apbclock = RCC_ClocksStatus.USART1CLK_Frequency; + } + else if (USARTx == USART2) + { + apbclock = RCC_ClocksStatus.USART2CLK_Frequency; + } + else if (USARTx == USART3) + { + apbclock = RCC_ClocksStatus.USART3CLK_Frequency; + } + else if (USARTx == UART4) + { + apbclock = RCC_ClocksStatus.UART4CLK_Frequency; + } + else + { + apbclock = RCC_ClocksStatus.UART5CLK_Frequency; + } + + /* Determine the integer part */ + if ((USARTx->CR1 & USART_CR1_OVER8) != 0) + { + /* (divider * 10) computing in case Oversampling mode is 8 Samples */ + divider = (uint32_t)((2 * apbclock) / (USART_InitStruct->USART_BaudRate)); + tmpreg = (uint32_t)((2 * apbclock) % (USART_InitStruct->USART_BaudRate)); + } + else /* if ((USARTx->CR1 & CR1_OVER8_Set) == 0) */ + { + /* (divider * 10) computing in case Oversampling mode is 16 Samples */ + divider = (uint32_t)((apbclock) / (USART_InitStruct->USART_BaudRate)); + tmpreg = (uint32_t)((apbclock) % (USART_InitStruct->USART_BaudRate)); + } + + /* round the divider : if fractional part i greater than 0.5 increment divider */ + if (tmpreg >= (USART_InitStruct->USART_BaudRate) / 2) + { + divider++; + } + + /* Implement the divider in case Oversampling mode is 8 Samples */ + if ((USARTx->CR1 & USART_CR1_OVER8) != 0) + { + /* get the LSB of divider and shift it to the right by 1 bit */ + tmpreg = (divider & (uint16_t)0x000F) >> 1; + + /* update the divider value */ + divider = (divider & (uint16_t)0xFFF0) | tmpreg; + } + + /* Write to USART BRR */ + USARTx->BRR = (uint16_t)divider; +} + +/** + * @brief Fills each USART_InitStruct member with its default value. + * @param USART_InitStruct: pointer to a USART_InitTypeDef structure + * which will be initialized. + * @retval None + */ +void USART_StructInit(USART_InitTypeDef* USART_InitStruct) +{ + /* USART_InitStruct members default value */ + USART_InitStruct->USART_BaudRate = 9600; + USART_InitStruct->USART_WordLength = USART_WordLength_8b; + USART_InitStruct->USART_StopBits = USART_StopBits_1; + USART_InitStruct->USART_Parity = USART_Parity_No ; + USART_InitStruct->USART_Mode = USART_Mode_Rx | USART_Mode_Tx; + USART_InitStruct->USART_HardwareFlowControl = USART_HardwareFlowControl_None; +} + +/** + * @brief Initializes the USARTx peripheral Clock according to the + * specified parameters in the USART_ClockInitStruct. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3. + * @param USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef + * structure that contains the configuration information for the specified + * USART peripheral. + * @retval None + */ +void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + assert_param(IS_USART_CLOCK(USART_ClockInitStruct->USART_Clock)); + assert_param(IS_USART_CPOL(USART_ClockInitStruct->USART_CPOL)); + assert_param(IS_USART_CPHA(USART_ClockInitStruct->USART_CPHA)); + assert_param(IS_USART_LASTBIT(USART_ClockInitStruct->USART_LastBit)); +/*---------------------------- USART CR2 Configuration -----------------------*/ + tmpreg = USARTx->CR2; + /* Clear CLKEN, CPOL, CPHA, LBCL and SSM bits */ + tmpreg &= (uint32_t)~((uint32_t)CR2_CLOCK_CLEAR_MASK); + /* Configure the USART Clock, CPOL, CPHA, LastBit and SSM ------------*/ + /* Set CLKEN bit according to USART_Clock value */ + /* Set CPOL bit according to USART_CPOL value */ + /* Set CPHA bit according to USART_CPHA value */ + /* Set LBCL bit according to USART_LastBit value */ + tmpreg |= (uint32_t)(USART_ClockInitStruct->USART_Clock | USART_ClockInitStruct->USART_CPOL | + USART_ClockInitStruct->USART_CPHA | USART_ClockInitStruct->USART_LastBit); + /* Write to USART CR2 */ + USARTx->CR2 = tmpreg; +} + +/** + * @brief Fills each USART_ClockInitStruct member with its default value. + * @param USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef + * structure which will be initialized. + * @retval None + */ +void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct) +{ + /* USART_ClockInitStruct members default value */ + USART_ClockInitStruct->USART_Clock = USART_Clock_Disable; + USART_ClockInitStruct->USART_CPOL = USART_CPOL_Low; + USART_ClockInitStruct->USART_CPHA = USART_CPHA_1Edge; + USART_ClockInitStruct->USART_LastBit = USART_LastBit_Disable; +} + +/** + * @brief Enables or disables the specified USART peripheral. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param NewState: new state of the USARTx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected USART by setting the UE bit in the CR1 register */ + USARTx->CR1 |= USART_CR1_UE; + } + else + { + /* Disable the selected USART by clearing the UE bit in the CR1 register */ + USARTx->CR1 &= (uint32_t)~((uint32_t)USART_CR1_UE); + } +} + +/** + * @brief Enables or disables the USART's transmitter or receiver. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_Direction: specifies the USART direction. + * This parameter can be any combination of the following values: + * @arg USART_Mode_Tx: USART Transmitter + * @arg USART_Mode_Rx: USART Receiver + * @param NewState: new state of the USART transfer direction. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_DirectionModeCmd(USART_TypeDef* USARTx, uint32_t USART_DirectionMode, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_MODE(USART_DirectionMode)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the USART's transfer interface by setting the TE and/or RE bits + in the USART CR1 register */ + USARTx->CR1 |= USART_DirectionMode; + } + else + { + /* Disable the USART's transfer interface by clearing the TE and/or RE bits + in the USART CR3 register */ + USARTx->CR1 &= (uint32_t)~USART_DirectionMode; + } +} + +/** + * @brief Enables or disables the USART's 8x oversampling mode. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param NewState: new state of the USART 8x oversampling mode. + * This parameter can be: ENABLE or DISABLE. + * @note + * This function has to be called before calling USART_Init() + * function in order to have correct baudrate Divider value. + * @retval None + */ +void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the 8x Oversampling mode by setting the OVER8 bit in the CR1 register */ + USARTx->CR1 |= USART_CR1_OVER8; + } + else + { + /* Disable the 8x Oversampling mode by clearing the OVER8 bit in the CR1 register */ + USARTx->CR1 &= (uint32_t)~((uint32_t)USART_CR1_OVER8); + } +} + +/** + * @brief Enables or disables the USART's one bit sampling method. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param NewState: new state of the USART one bit sampling method. + * This parameter can be: ENABLE or DISABLE. + * @note + * This function has to be called before calling USART_Cmd() function. + * @retval None + */ +void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the one bit method by setting the ONEBIT bit in the CR3 register */ + USARTx->CR3 |= USART_CR3_ONEBIT; + } + else + { + /* Disable the one bit method by clearing the ONEBIT bit in the CR3 register */ + USARTx->CR3 &= (uint32_t)~((uint32_t)USART_CR3_ONEBIT); + } +} + +/** + * @brief Enables or disables the USART's most significant bit first + * transmitted/received following the start bit. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param NewState: new state of the USART most significant bit first + * transmitted/received following the start bit. + * This parameter can be: ENABLE or DISABLE. + * @note + * This function has to be called before calling USART_Cmd() function. + * @retval None + */ +void USART_MSBFirstCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the most significant bit first transmitted/received following the + start bit by setting the MSBFIRST bit in the CR2 register */ + USARTx->CR2 |= USART_CR2_MSBFIRST; + } + else + { + /* Disable the most significant bit first transmitted/received following the + start bit by clearing the MSBFIRST bit in the CR2 register */ + USARTx->CR2 &= (uint32_t)~((uint32_t)USART_CR2_MSBFIRST); + } +} + +/** + * @brief Enables or disables the binary data inversion. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param NewState: new defined levels for the USART data. + * This parameter can be: ENABLE or DISABLE. + * @arg ENABLE: Logical data from the data register are send/received in negative + * logic. (1=L, 0=H). The parity bit is also inverted. + * @arg DISABLE: Logical data from the data register are send/received in positive + * logic. (1=H, 0=L) + * @note + * This function has to be called before calling USART_Cmd() function. + * @retval None + */ +void USART_DataInvCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the binary data inversion feature by setting the DATAINV bit in + the CR2 register */ + USARTx->CR2 |= USART_CR2_DATAINV; + } + else + { + /* Disable the binary data inversion feature by clearing the DATAINV bit in + the CR2 register */ + USARTx->CR2 &= (uint32_t)~((uint32_t)USART_CR2_DATAINV); + } +} + +/** + * @brief Enables or disables the Pin(s) active level inversion. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_InvPin: specifies the USART pin(s) to invert. + * This parameter can be any combination of the following values: + * @arg USART_InvPin_Tx: USART Tx pin active level inversion. + * @arg USART_InvPin_Rx: USART Rx pin active level inversion. + * @param NewState: new active level status for the USART pin(s). + * This parameter can be: ENABLE or DISABLE. + * - ENABLE: pin(s) signal values are inverted (Vdd =0, Gnd =1). + * - DISABLE: pin(s) signal works using the standard logic levels (Vdd =1, Gnd =0). + * @note + * This function has to be called before calling USART_Cmd() function. + * @retval None + */ +void USART_InvPinCmd(USART_TypeDef* USARTx, uint32_t USART_InvPin, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_INVERSTION_PIN(USART_InvPin)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the active level inversion for selected pins by setting the TXINV + and/or RXINV bits in the USART CR2 register */ + USARTx->CR2 |= USART_InvPin; + } + else + { + /* Disable the active level inversion for selected requests by clearing the + TXINV and/or RXINV bits in the USART CR2 register */ + USARTx->CR2 &= (uint32_t)~USART_InvPin; + } +} + +/** + * @brief Enables or disables the swap Tx/Rx pins. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param NewState: new state of the USARTx TX/RX pins pinout. + * This parameter can be: ENABLE or DISABLE. + * @arg ENABLE: The TX and RX pins functions are swapped. + * @arg DISABLE: TX/RX pins are used as defined in standard pinout + * @note + * This function has to be called before calling USART_Cmd() function. + * @retval None + */ +void USART_SWAPPinCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the SWAP feature by setting the SWAP bit in the CR2 register */ + USARTx->CR2 |= USART_CR2_SWAP; + } + else + { + /* Disable the SWAP feature by clearing the SWAP bit in the CR2 register */ + USARTx->CR2 &= (uint32_t)~((uint32_t)USART_CR2_SWAP); + } +} + +/** + * @brief Enables or disables the receiver Time Out feature. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param NewState: new state of the USARTx receiver Time Out. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_ReceiverTimeOutCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the receiver time out feature by setting the RTOEN bit in the CR2 + register */ + USARTx->CR2 |= USART_CR2_RTOEN; + } + else + { + /* Disable the receiver time out feature by clearing the RTOEN bit in the CR2 + register */ + USARTx->CR2 &= (uint32_t)~((uint32_t)USART_CR2_RTOEN); + } +} + +/** + * @brief Sets the receiver Time Out value. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_ReceiverTimeOut: specifies the Receiver Time Out value. + * @retval None + */ +void USART_SetReceiverTimeOut(USART_TypeDef* USARTx, uint32_t USART_ReceiverTimeOut) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_TIMEOUT(USART_ReceiverTimeOut)); + + /* Clear the receiver Time Out value by clearing the RTO[23:0] bits in the RTOR + register */ + USARTx->RTOR &= (uint32_t)~((uint32_t)USART_RTOR_RTO); + /* Set the receiver Time Out value by setting the RTO[23:0] bits in the RTOR + register */ + USARTx->RTOR |= USART_ReceiverTimeOut; +} + +/** + * @brief Sets the system clock prescaler. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_Prescaler: specifies the prescaler clock. + * @note + * This function has to be called before calling USART_Cmd() function. + * @retval None + */ +void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + /* Clear the USART prescaler */ + USARTx->GTPR &= USART_GTPR_GT; + /* Set the USART prescaler */ + USARTx->GTPR |= USART_Prescaler; +} + +/** + * @} + */ + + +/** @defgroup USART_Group2 STOP Mode functions + * @brief STOP Mode functions + * +@verbatim + =============================================================================== + ##### STOP Mode functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to manage + WakeUp from STOP mode. + + [..] The USART is able to WakeUp from Stop Mode if USART clock is set to HSI + or LSI. + + [..] The WakeUp source is configured by calling USART_StopModeWakeUpSourceConfig() + function. + + [..] After configuring the source of WakeUp and before entering in Stop Mode + USART_STOPModeCmd() function should be called to allow USART WakeUp. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified USART peripheral in STOP Mode. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param NewState: new state of the USARTx peripheral state in stop mode. + * This parameter can be: ENABLE or DISABLE. + * @note + * This function has to be called when USART clock is set to HSI or LSE. + * @retval None + */ +void USART_STOPModeCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected USART in STOP mode by setting the UESM bit in the CR1 + register */ + USARTx->CR1 |= USART_CR1_UESM; + } + else + { + /* Disable the selected USART in STOP mode by clearing the UE bit in the CR1 + register */ + USARTx->CR1 &= (uint32_t)~((uint32_t)USART_CR1_UESM); + } +} + +/** + * @brief Selects the USART WakeUp method form stop mode. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_WakeUp: specifies the selected USART wakeup method. + * This parameter can be one of the following values: + * @arg USART_WakeUpSource_AddressMatch: WUF active on address match. + * @arg USART_WakeUpSource_StartBit: WUF active on Start bit detection. + * @arg USART_WakeUpSource_RXNE: WUF active on RXNE. + * @note + * This function has to be called before calling USART_Cmd() function. + * @retval None + */ +void USART_StopModeWakeUpSourceConfig(USART_TypeDef* USARTx, uint32_t USART_WakeUpSource) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_STOPMODE_WAKEUPSOURCE(USART_WakeUpSource)); + + USARTx->CR3 &= (uint32_t)~((uint32_t)USART_CR3_WUS); + USARTx->CR3 |= USART_WakeUpSource; +} + +/** + * @} + */ + + +/** @defgroup USART_Group3 AutoBaudRate functions + * @brief AutoBaudRate functions + * +@verbatim + =============================================================================== + ##### AutoBaudRate functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to manage + the AutoBaudRate detections. + + [..] Before Enabling AutoBaudRate detection using USART_AutoBaudRateCmd () + The character patterns used to calculate baudrate must be chosen by calling + USART_AutoBaudRateConfig() function. These function take as parameter : + (#)USART_AutoBaudRate_StartBit : any character starting with a bit 1. + (#)USART_AutoBaudRate_FallingEdge : any character starting with a 10xx bit pattern. + + [..] At any later time, another request for AutoBaudRate detection can be performed + using USART_RequestCmd() function. + + [..] The AutoBaudRate detection is monitored by the status of ABRF flag which indicate + that the AutoBaudRate detection is completed. In addition to ABRF flag, the ABRE flag + indicate that this procedure is completed without success. USART_GetFlagStatus () + function should be used to monitor the status of these flags. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the Auto Baud Rate. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param NewState: new state of the USARTx auto baud rate. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_AutoBaudRateCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the auto baud rate feature by setting the ABREN bit in the CR2 + register */ + USARTx->CR2 |= USART_CR2_ABREN; + } + else + { + /* Disable the auto baud rate feature by clearing the ABREN bit in the CR2 + register */ + USARTx->CR2 &= (uint32_t)~((uint32_t)USART_CR2_ABREN); + } +} + +/** + * @brief Selects the USART auto baud rate method. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_AutoBaudRate: specifies the selected USART auto baud rate method. + * This parameter can be one of the following values: + * @arg USART_AutoBaudRate_StartBit: Start Bit duration measurement. + * @arg USART_AutoBaudRate_FallingEdge: Falling edge to falling edge measurement. + * @arg USART_AutoBaudRate_0x7FFrame: 0x7F frame. + * @arg USART_AutoBaudRate_0x55Frame: 0x55 frame. + * @note + * This function has to be called before calling USART_Cmd() function. + * @retval None + */ +void USART_AutoBaudRateConfig(USART_TypeDef* USARTx, uint32_t USART_AutoBaudRate) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_AUTOBAUDRATE_MODE(USART_AutoBaudRate)); + + USARTx->CR2 &= (uint32_t)~((uint32_t)USART_CR2_ABRMODE); + USARTx->CR2 |= USART_AutoBaudRate; +} + +/** + * @} + */ + + +/** @defgroup USART_Group4 Data transfers functions + * @brief Data transfers functions + * +@verbatim + =============================================================================== + ##### Data transfers functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to manage + the USART data transfers. + [..] During an USART reception, data shifts in least significant bit first + through the RX pin. When a transmission is taking place, a write instruction to + the USART_TDR register stores the data in the shift register. + [..] The read access of the USART_RDR register can be done using + the USART_ReceiveData() function and returns the RDR value. + Whereas a write access to the USART_TDR can be done using USART_SendData() + function and stores the written data into TDR. + +@endverbatim + * @{ + */ + +/** + * @brief Transmits single data through the USARTx peripheral. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param Data: the data to transmit. + * @retval None + */ +void USART_SendData(USART_TypeDef* USARTx, uint16_t Data) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_DATA(Data)); + + /* Transmit Data */ + USARTx->TDR = (Data & (uint16_t)0x01FF); +} + +/** + * @brief Returns the most recent received data by the USARTx peripheral. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @retval The received data. + */ +uint16_t USART_ReceiveData(USART_TypeDef* USARTx) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + /* Receive Data */ + return (uint16_t)(USARTx->RDR & (uint16_t)0x01FF); +} + +/** + * @} + */ + +/** @defgroup USART_Group5 MultiProcessor Communication functions + * @brief Multi-Processor Communication functions + * +@verbatim + =============================================================================== + ##### Multi-Processor Communication functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to manage the USART + multiprocessor communication. + [..] For instance one of the USARTs can be the master, its TX output is + connected to the RX input of the other USART. The others are slaves, + their respective TX outputs are logically ANDed together and connected + to the RX input of the master. USART multiprocessor communication is + possible through the following procedure: + (#) Program the Baud rate, Word length = 9 bits, Stop bits, Parity, + Mode transmitter or Mode receiver and hardware flow control values + using the USART_Init() function. + (#) Configures the USART address using the USART_SetAddress() function. + (#) Configures the wake up methode (USART_WakeUp_IdleLine or + USART_WakeUp_AddressMark) using USART_WakeUpConfig() function only + for the slaves. + (#) Enable the USART using the USART_Cmd() function. + (#) Enter the USART slaves in mute mode using USART_ReceiverWakeUpCmd() + function. + [..] The USART Slave exit from mute mode when receive the wake up condition. + +@endverbatim + * @{ + */ + +/** + * @brief Sets the address of the USART node. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_Address: Indicates the address of the USART node. + * @retval None + */ +void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + /* Clear the USART address */ + USARTx->CR2 &= (uint32_t)~((uint32_t)USART_CR2_ADD); + /* Set the USART address node */ + USARTx->CR2 |=((uint32_t)USART_Address << (uint32_t)0x18); +} + +/** + * @brief Enables or disables the USART's mute mode. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param NewState: new state of the USART mute mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_MuteModeCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the USART mute mode by setting the MME bit in the CR1 register */ + USARTx->CR1 |= USART_CR1_MME; + } + else + { + /* Disable the USART mute mode by clearing the MME bit in the CR1 register */ + USARTx->CR1 &= (uint32_t)~((uint32_t)USART_CR1_MME); + } +} + +/** + * @brief Selects the USART WakeUp method from mute mode. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_WakeUp: specifies the USART wakeup method. + * This parameter can be one of the following values: + * @arg USART_WakeUp_IdleLine: WakeUp by an idle line detection + * @arg USART_WakeUp_AddressMark: WakeUp by an address mark + * @retval None + */ +void USART_MuteModeWakeUpConfig(USART_TypeDef* USARTx, uint32_t USART_WakeUp) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_MUTEMODE_WAKEUP(USART_WakeUp)); + + USARTx->CR1 &= (uint32_t)~((uint32_t)USART_CR1_WAKE); + USARTx->CR1 |= USART_WakeUp; +} + +/** + * @brief Configure the the USART Address detection length. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_AddressLength: specifies the USART address length detection. + * This parameter can be one of the following values: + * @arg USART_AddressLength_4b: 4-bit address length detection + * @arg USART_AddressLength_7b: 7-bit address length detection + * @retval None + */ +void USART_AddressDetectionConfig(USART_TypeDef* USARTx, uint32_t USART_AddressLength) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_ADDRESS_DETECTION(USART_AddressLength)); + + USARTx->CR2 &= (uint32_t)~((uint32_t)USART_CR2_ADDM7); + USARTx->CR2 |= USART_AddressLength; +} + +/** + * @} + */ + +/** @defgroup USART_Group6 LIN mode functions + * @brief LIN mode functions + * +@verbatim + =============================================================================== + ##### LIN mode functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to manage the USART + LIN Mode communication. + [..] In LIN mode, 8-bit data format with 1 stop bit is required in accordance + with the LIN standard. + [..] Only this LIN Feature is supported by the USART IP: + (+) LIN Master Synchronous Break send capability and LIN slave break + detection capability : 13-bit break generation and 10/11 bit break + detection. + [..] USART LIN Master transmitter communication is possible through the + following procedure: + (#) Program the Baud rate, Word length = 8bits, Stop bits = 1bit, Parity, + Mode transmitter or Mode receiver and hardware flow control values + using the USART_Init() function. + (#) Enable the LIN mode using the USART_LINCmd() function. + (#) Enable the USART using the USART_Cmd() function. + (#) Send the break character using USART_SendBreak() function. + [..] USART LIN Master receiver communication is possible through the + following procedure: + (#) Program the Baud rate, Word length = 8bits, Stop bits = 1bit, Parity, + Mode transmitter or Mode receiver and hardware flow control values + using the USART_Init() function. + (#) Configures the break detection length + using the USART_LINBreakDetectLengthConfig() function. + (#) Enable the LIN mode using the USART_LINCmd() function. + (#) Enable the USART using the USART_Cmd() function. + [..] + (@) In LIN mode, the following bits must be kept cleared: + (+@) CLKEN in the USART_CR2 register. + (+@) STOP[1:0], SCEN, HDSEL and IREN in the USART_CR3 register. + +@endverbatim + * @{ + */ + +/** + * @brief Sets the USART LIN Break detection length. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_LINBreakDetectLength: specifies the LIN break detection length. + * This parameter can be one of the following values: + * @arg USART_LINBreakDetectLength_10b: 10-bit break detection + * @arg USART_LINBreakDetectLength_11b: 11-bit break detection + * @retval None + */ +void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint32_t USART_LINBreakDetectLength) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_LIN_BREAK_DETECT_LENGTH(USART_LINBreakDetectLength)); + + USARTx->CR2 &= (uint32_t)~((uint32_t)USART_CR2_LBDL); + USARTx->CR2 |= USART_LINBreakDetectLength; +} + +/** + * @brief Enables or disables the USART's LIN mode. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param NewState: new state of the USART LIN mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the LIN mode by setting the LINEN bit in the CR2 register */ + USARTx->CR2 |= USART_CR2_LINEN; + } + else + { + /* Disable the LIN mode by clearing the LINEN bit in the CR2 register */ + USARTx->CR2 &= (uint32_t)~((uint32_t)USART_CR2_LINEN); + } +} + +/** + * @} + */ + +/** @defgroup USART_Group7 Halfduplex mode function + * @brief Half-duplex mode function + * +@verbatim + =============================================================================== + ##### Half-duplex mode function ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to manage the USART + Half-duplex communication. + [..] The USART can be configured to follow a single-wire half-duplex protocol + where the TX and RX lines are internally connected. + [..] USART Half duplex communication is possible through the following procedure: + (#) Program the Baud rate, Word length, Stop bits, Parity, Mode transmitter + or Mode receiver and hardware flow control values using the USART_Init() + function. + (#) Configures the USART address using the USART_SetAddress() function. + (#) Enable the half duplex mode using USART_HalfDuplexCmd() function. + (#) Enable the USART using the USART_Cmd() function. + [..] + (@) The RX pin is no longer used. + (@) In Half-duplex mode the following bits must be kept cleared: + (+@) LINEN and CLKEN bits in the USART_CR2 register. + (+@) SCEN and IREN bits in the USART_CR3 register. + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the USART's Half Duplex communication. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param NewState: new state of the USART Communication. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Half-Duplex mode by setting the HDSEL bit in the CR3 register */ + USARTx->CR3 |= USART_CR3_HDSEL; + } + else + { + /* Disable the Half-Duplex mode by clearing the HDSEL bit in the CR3 register */ + USARTx->CR3 &= (uint32_t)~((uint32_t)USART_CR3_HDSEL); + } +} + +/** + * @} + */ + + +/** @defgroup USART_Group8 Smartcard mode functions + * @brief Smartcard mode functions + * +@verbatim + =============================================================================== + ##### Smartcard mode functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to manage the USART + Smartcard communication. + [..] The Smartcard interface is designed to support asynchronous protocol + Smartcards as defined in the ISO 7816-3 standard. The USART can provide + a clock to the smartcard through the SCLK output. In smartcard mode, + SCLK is not associated to the communication but is simply derived from + the internal peripheral input clock through a 5-bit prescaler. + [..] Smartcard communication is possible through the following procedure: + (#) Configures the Smartcard Prsecaler using the USART_SetPrescaler() + function. + (#) Configures the Smartcard Guard Time using the USART_SetGuardTime() + function. + (#) Program the USART clock using the USART_ClockInit() function as following: + (++) USART Clock enabled. + (++) USART CPOL Low. + (++) USART CPHA on first edge. + (++) USART Last Bit Clock Enabled. + (#) Program the Smartcard interface using the USART_Init() function as + following: + (++) Word Length = 9 Bits. + (++) 1.5 Stop Bit. + (++) Even parity. + (++) BaudRate = 12096 baud. + (++) Hardware flow control disabled (RTS and CTS signals). + (++) Tx and Rx enabled + (#) Optionally you can enable the parity error interrupt using + the USART_ITConfig() function. + (#) Enable the Smartcard NACK using the USART_SmartCardNACKCmd() function. + (#) Enable the Smartcard interface using the USART_SmartCardCmd() function. + (#) Enable the USART using the USART_Cmd() function. + [..] + Please refer to the ISO 7816-3 specification for more details. + [..] + (@) It is also possible to choose 0.5 stop bit for receiving but it is + recommended to use 1.5 stop bits for both transmitting and receiving + to avoid switching between the two configurations. + (@) In smartcard mode, the following bits must be kept cleared: + (+@) LINEN bit in the USART_CR2 register. + (+@) HDSEL and IREN bits in the USART_CR3 register. + +@endverbatim + * @{ + */ + +/** + * @brief Sets the specified USART guard time. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3. + * @param USART_GuardTime: specifies the guard time. + * @retval None + */ +void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime) +{ + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + + /* Clear the USART Guard time */ + USARTx->GTPR &= USART_GTPR_PSC; + /* Set the USART guard time */ + USARTx->GTPR |= (uint16_t)((uint16_t)USART_GuardTime << 0x08); +} + +/** + * @brief Enables or disables the USART's Smart Card mode. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3. + * @param NewState: new state of the Smart Card mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the SC mode by setting the SCEN bit in the CR3 register */ + USARTx->CR3 |= USART_CR3_SCEN; + } + else + { + /* Disable the SC mode by clearing the SCEN bit in the CR3 register */ + USARTx->CR3 &= (uint32_t)~((uint32_t)USART_CR3_SCEN); + } +} + +/** + * @brief Enables or disables NACK transmission. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3. + * @param NewState: new state of the NACK transmission. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the NACK transmission by setting the NACK bit in the CR3 register */ + USARTx->CR3 |= USART_CR3_NACK; + } + else + { + /* Disable the NACK transmission by clearing the NACK bit in the CR3 register */ + USARTx->CR3 &= (uint32_t)~((uint32_t)USART_CR3_NACK); + } +} + +/** + * @brief Sets the Smart Card number of retries in transmit and receive. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3. + * @param USART_AutoCount: specifies the Smart Card auto retry count. + * @retval None + */ +void USART_SetAutoRetryCount(USART_TypeDef* USARTx, uint8_t USART_AutoCount) +{ + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + assert_param(IS_USART_AUTO_RETRY_COUNTER(USART_AutoCount)); + /* Clear the USART auto retry count */ + USARTx->CR3 &= (uint32_t)~((uint32_t)USART_CR3_SCARCNT); + /* Set the USART auto retry count*/ + USARTx->CR3 |= (uint32_t)((uint32_t)USART_AutoCount << 0x11); +} + +/** + * @brief Sets the Smart Card Block length. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3. + * @param USART_BlockLength: specifies the Smart Card block length. + * @retval None + */ +void USART_SetBlockLength(USART_TypeDef* USARTx, uint8_t USART_BlockLength) +{ + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + + /* Clear the Smart card block length */ + USARTx->RTOR &= (uint32_t)~((uint32_t)USART_RTOR_BLEN); + /* Set the Smart Card block length */ + USARTx->RTOR |= (uint32_t)((uint32_t)USART_BlockLength << 0x18); +} + +/** + * @} + */ + +/** @defgroup USART_Group9 IrDA mode functions + * @brief IrDA mode functions + * +@verbatim + =============================================================================== + ##### IrDA mode functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to manage the USART + IrDA communication. + [..] IrDA is a half duplex communication protocol. If the Transmitter is busy, + any data on the IrDA receive line will be ignored by the IrDA decoder + and if the Receiver is busy, data on the TX from the USART to IrDA will + not be encoded by IrDA. While receiving data, transmission should be + avoided as the data to be transmitted could be corrupted. + [..] IrDA communication is possible through the following procedure: + (#) Program the Baud rate, Word length = 8 bits, Stop bits, Parity, + Transmitter/Receiver modes and hardware flow control values using + the USART_Init() function. + (#) Configures the IrDA pulse width by configuring the prescaler using + the USART_SetPrescaler() function. + (#) Configures the IrDA USART_IrDAMode_LowPower or USART_IrDAMode_Normal + mode using the USART_IrDAConfig() function. + (#) Enable the IrDA using the USART_IrDACmd() function. + (#) Enable the USART using the USART_Cmd() function. + [..] + (@) A pulse of width less than two and greater than one PSC period(s) may or + may not be rejected. + (@) The receiver set up time should be managed by software. The IrDA physical + layer specification specifies a minimum of 10 ms delay between + transmission and reception (IrDA is a half duplex protocol). + (@) In IrDA mode, the following bits must be kept cleared: + (+@) LINEN, STOP and CLKEN bits in the USART_CR2 register. + (+@) SCEN and HDSEL bits in the USART_CR3 register. + +@endverbatim + * @{ + */ + +/** + * @brief Configures the USART's IrDA interface. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_IrDAMode: specifies the IrDA mode. + * This parameter can be one of the following values: + * @arg USART_IrDAMode_LowPower + * @arg USART_IrDAMode_Normal + * @retval None + */ +void USART_IrDAConfig(USART_TypeDef* USARTx, uint32_t USART_IrDAMode) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_IRDA_MODE(USART_IrDAMode)); + + USARTx->CR3 &= (uint32_t)~((uint32_t)USART_CR3_IRLP); + USARTx->CR3 |= USART_IrDAMode; +} + +/** + * @brief Enables or disables the USART's IrDA interface. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param NewState: new state of the IrDA mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the IrDA mode by setting the IREN bit in the CR3 register */ + USARTx->CR3 |= USART_CR3_IREN; + } + else + { + /* Disable the IrDA mode by clearing the IREN bit in the CR3 register */ + USARTx->CR3 &= (uint32_t)~((uint32_t)USART_CR3_IREN); + } +} +/** + * @} + */ + +/** @defgroup USART_Group10 RS485 mode function + * @brief RS485 mode function + * +@verbatim + =============================================================================== + ##### RS485 mode functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to manage the USART + RS485 flow control. + [..] RS485 flow control (Driver enable feature) handling is possible through + the following procedure: + (#) Program the Baud rate, Word length = 8 bits, Stop bits, Parity, + Transmitter/Receiver modes and hardware flow control values using + the USART_Init() function. + (#) Enable the Driver Enable using the USART_DECmd() function. + (#) Configures the Driver Enable polarity using the USART_DEPolarityConfig() + function. + (#) Configures the Driver Enable assertion time using USART_SetDEAssertionTime() + function and deassertion time using the USART_SetDEDeassertionTime() + function. + (#) Enable the USART using the USART_Cmd() function. + [..] + (@) The assertion and dessertion times are expressed in sample time units (1/8 or + 1/16 bit time, depending on the oversampling rate). + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the USART's DE functionality. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param NewState: new state of the driver enable mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_DECmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the DE functionality by setting the DEM bit in the CR3 register */ + USARTx->CR3 |= USART_CR3_DEM; + } + else + { + /* Disable the DE functionality by clearing the DEM bit in the CR3 register */ + USARTx->CR3 &= (uint32_t)~((uint32_t)USART_CR3_DEM); + } +} + +/** + * @brief Configures the USART's DE polarity + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_DEPolarity: specifies the DE polarity. + * This parameter can be one of the following values: + * @arg USART_DEPolarity_Low + * @arg USART_DEPolarity_High + * @retval None + */ +void USART_DEPolarityConfig(USART_TypeDef* USARTx, uint32_t USART_DEPolarity) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_DE_POLARITY(USART_DEPolarity)); + + USARTx->CR3 &= (uint32_t)~((uint32_t)USART_CR3_DEP); + USARTx->CR3 |= USART_DEPolarity; +} + +/** + * @brief Sets the specified RS485 DE assertion time + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_AssertionTime: specifies the time between the activation of the DE + * signal and the beginning of the start bit + * @retval None + */ +void USART_SetDEAssertionTime(USART_TypeDef* USARTx, uint32_t USART_DEAssertionTime) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_DE_ASSERTION_DEASSERTION_TIME(USART_DEAssertionTime)); + + /* Clear the DE assertion time */ + USARTx->CR1 &= (uint32_t)~((uint32_t)USART_CR1_DEAT); + /* Set the new value for the DE assertion time */ + USARTx->CR1 |=((uint32_t)USART_DEAssertionTime << (uint32_t)0x15); +} + +/** + * @brief Sets the specified RS485 DE deassertion time + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_DeassertionTime: specifies the time between the middle of the last + * stop bit in a transmitted message and the de-activation of the DE signal + * @retval None + */ +void USART_SetDEDeassertionTime(USART_TypeDef* USARTx, uint32_t USART_DEDeassertionTime) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_DE_ASSERTION_DEASSERTION_TIME(USART_DEDeassertionTime)); + + /* Clear the DE deassertion time */ + USARTx->CR1 &= (uint32_t)~((uint32_t)USART_CR1_DEDT); + /* Set the new value for the DE deassertion time */ + USARTx->CR1 |=((uint32_t)USART_DEDeassertionTime << (uint32_t)0x10); +} + +/** + * @} + */ + +/** @defgroup USART_Group11 DMA transfers management functions + * @brief DMA transfers management functions + * +@verbatim + =============================================================================== + ##### DMA transfers management functions ##### + =============================================================================== + [..] This section provides two functions that can be used only in DMA mode. + [..] In DMA Mode, the USART communication can be managed by 2 DMA Channel + requests: + (#) USART_DMAReq_Tx: specifies the Tx buffer DMA transfer request. + (#) USART_DMAReq_Rx: specifies the Rx buffer DMA transfer request. + [..] In this Mode it is advised to use the following function: + (+) void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, + FunctionalState NewState). +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the USART's DMA interface. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4. + * @param USART_DMAReq: specifies the DMA request. + * This parameter can be any combination of the following values: + * @arg USART_DMAReq_Tx: USART DMA transmit request + * @arg USART_DMAReq_Rx: USART DMA receive request + * @param NewState: new state of the DMA Request sources. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_DMACmd(USART_TypeDef* USARTx, uint32_t USART_DMAReq, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_1234_PERIPH(USARTx)); + assert_param(IS_USART_DMAREQ(USART_DMAReq)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the DMA transfer for selected requests by setting the DMAT and/or + DMAR bits in the USART CR3 register */ + USARTx->CR3 |= USART_DMAReq; + } + else + { + /* Disable the DMA transfer for selected requests by clearing the DMAT and/or + DMAR bits in the USART CR3 register */ + USARTx->CR3 &= (uint32_t)~USART_DMAReq; + } +} + +/** + * @brief Enables or disables the USART's DMA interface when reception error occurs. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4. + * @param USART_DMAOnError: specifies the DMA status in case of reception error. + * This parameter can be any combination of the following values: + * @arg USART_DMAOnError_Enable: DMA receive request enabled when the USART DMA + * reception error is asserted. + * @arg USART_DMAOnError_Disable: DMA receive request disabled when the USART DMA + * reception error is asserted. + * @retval None + */ +void USART_DMAReceptionErrorConfig(USART_TypeDef* USARTx, uint32_t USART_DMAOnError) +{ + /* Check the parameters */ + assert_param(IS_USART_1234_PERIPH(USARTx)); + assert_param(IS_USART_DMAONERROR(USART_DMAOnError)); + + /* Clear the DMA Reception error detection bit */ + USARTx->CR3 &= (uint32_t)~((uint32_t)USART_CR3_DDRE); + /* Set the new value for the DMA Reception error detection bit */ + USARTx->CR3 |= USART_DMAOnError; +} + +/** + * @} + */ + +/** @defgroup USART_Group12 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + =============================================================================== + ##### Interrupts and flags management functions ##### + =============================================================================== + [..] This subsection provides a set of functions allowing to configure the + USART Interrupts sources, Requests and check or clear the flags or pending bits status. + The user should identify which mode will be used in his application to + manage the communication: Polling mode, Interrupt mode. + + *** Polling Mode *** + ==================== + [..] In Polling Mode, the SPI communication can be managed by these flags: + (#) USART_FLAG_REACK: to indicate the status of the Receive Enable + acknowledge flag + (#) USART_FLAG_TEACK: to indicate the status of the Transmit Enable + acknowledge flag. + (#) USART_FLAG_WUF: to indicate the status of the Wake up flag. + (#) USART_FLAG_RWU: to indicate the status of the Receive Wake up flag. + (#) USART_FLAG_SBK: to indicate the status of the Send Break flag. + (#) USART_FLAG_CMF: to indicate the status of the Character match flag. + (#) USART_FLAG_BUSY: to indicate the status of the Busy flag. + (#) USART_FLAG_ABRF: to indicate the status of the Auto baud rate flag. + (#) USART_FLAG_ABRE: to indicate the status of the Auto baud rate error flag. + (#) USART_FLAG_EOBF: to indicate the status of the End of block flag. + (#) USART_FLAG_RTOF: to indicate the status of the Receive time out flag. + (#) USART_FLAG_nCTSS: to indicate the status of the Inverted nCTS input + bit status. + (#) USART_FLAG_TXE: to indicate the status of the transmit buffer register. + (#) USART_FLAG_RXNE: to indicate the status of the receive buffer register. + (#) USART_FLAG_TC: to indicate the status of the transmit operation. + (#) USART_FLAG_IDLE: to indicate the status of the Idle Line. + (#) USART_FLAG_CTS: to indicate the status of the nCTS input. + (#) USART_FLAG_LBD: to indicate the status of the LIN break detection. + (#) USART_FLAG_NE: to indicate if a noise error occur. + (#) USART_FLAG_FE: to indicate if a frame error occur. + (#) USART_FLAG_PE: to indicate if a parity error occur. + (#) USART_FLAG_ORE: to indicate if an Overrun error occur. + [..] In this Mode it is advised to use the following functions: + (+) FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG). + (+) void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG). + + *** Interrupt Mode *** + ====================== + [..] In Interrupt Mode, the USART communication can be managed by 8 interrupt + sources and 10 pending bits: + (+) Pending Bits: + (##) USART_IT_WU: to indicate the status of the Wake up interrupt. + (##) USART_IT_CM: to indicate the status of Character match interrupt. + (##) USART_IT_EOB: to indicate the status of End of block interrupt. + (##) USART_IT_RTO: to indicate the status of Receive time out interrupt. + (##) USART_IT_CTS: to indicate the status of CTS change interrupt. + (##) USART_IT_LBD: to indicate the status of LIN Break detection interrupt. + (##) USART_IT_TC: to indicate the status of Transmission complete interrupt. + (##) USART_IT_IDLE: to indicate the status of IDLE line detected interrupt. + (##) USART_IT_ORE: to indicate the status of OverRun Error interrupt. + (##) USART_IT_NE: to indicate the status of Noise Error interrupt. + (##) USART_IT_FE: to indicate the status of Framing Error interrupt. + (##) USART_IT_PE: to indicate the status of Parity Error interrupt. + + (+) Interrupt Source: + (##) USART_IT_WU: specifies the interrupt source for Wake up interrupt. + (##) USART_IT_CM: specifies the interrupt source for Character match + interrupt. + (##) USART_IT_EOB: specifies the interrupt source for End of block + interrupt. + (##) USART_IT_RTO: specifies the interrupt source for Receive time-out + interrupt. + (##) USART_IT_CTS: specifies the interrupt source for CTS change interrupt. + (##) USART_IT_LBD: specifies the interrupt source for LIN Break + detection interrupt. + (##) USART_IT_TXE: specifies the interrupt source for Tansmit Data + Register empty interrupt. + (##) USART_IT_TC: specifies the interrupt source for Transmission + complete interrupt. + (##) USART_IT_RXNE: specifies the interrupt source for Receive Data + register not empty interrupt. + (##) USART_IT_IDLE: specifies the interrupt source for Idle line + detection interrupt. + (##) USART_IT_PE: specifies the interrupt source for Parity Error interrupt. + (##) USART_IT_ERR: specifies the interrupt source for Error interrupt + (Frame error, noise error, overrun error) + -@@- Some parameters are coded in order to use them as interrupt + source or as pending bits. + [..] In this Mode it is advised to use the following functions: + (+) void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState). + (+) ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT). + (+) void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT). + +@endverbatim + * @{ + */ + +/** + * @brief Enables or disables the specified USART interrupts. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_IT: specifies the USART interrupt sources to be enabled or disabled. + * This parameter can be one of the following values: + * @arg USART_IT_WU: Wake up interrupt. + * @arg USART_IT_CM: Character match interrupt. + * @arg USART_IT_EOB: End of block interrupt. + * @arg USART_IT_RTO: Receive time out interrupt. + * @arg USART_IT_CTS: CTS change interrupt. + * @arg USART_IT_LBD: LIN Break detection interrupt. + * @arg USART_IT_TXE: Tansmit Data Register empty interrupt. + * @arg USART_IT_TC: Transmission complete interrupt. + * @arg USART_IT_RXNE: Receive Data register not empty interrupt. + * @arg USART_IT_IDLE: Idle line detection interrupt. + * @arg USART_IT_PE: Parity Error interrupt. + * @arg USART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) + * @param NewState: new state of the specified USARTx interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_ITConfig(USART_TypeDef* USARTx, uint32_t USART_IT, FunctionalState NewState) +{ + uint32_t usartreg = 0, itpos = 0, itmask = 0; + uint32_t usartxbase = 0; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_CONFIG_IT(USART_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + usartxbase = (uint32_t)USARTx; + + /* Get the USART register index */ + usartreg = (((uint16_t)USART_IT) >> 0x08); + + /* Get the interrupt position */ + itpos = USART_IT & IT_MASK; + itmask = (((uint32_t)0x01) << itpos); + + if (usartreg == 0x02) /* The IT is in CR2 register */ + { + usartxbase += 0x04; + } + else if (usartreg == 0x03) /* The IT is in CR3 register */ + { + usartxbase += 0x08; + } + else /* The IT is in CR1 register */ + { + } + if (NewState != DISABLE) + { + *(__IO uint32_t*)usartxbase |= itmask; + } + else + { + *(__IO uint32_t*)usartxbase &= ~itmask; + } +} + +/** + * @brief Enables the specified USART's Request. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_Request: specifies the USART request. + * This parameter can be any combination of the following values: + * @arg USART_Request_TXFRQ: Transmit data flush ReQuest + * @arg USART_Request_RXFRQ: Receive data flush ReQuest + * @arg USART_Request_MMRQ: Mute Mode ReQuest + * @arg USART_Request_SBKRQ: Send Break ReQuest + * @arg USART_Request_ABRRQ: Auto Baud Rate ReQuest + * @param NewState: new state of the DMA interface when reception error occurs. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_RequestCmd(USART_TypeDef* USARTx, uint32_t USART_Request, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_REQUEST(USART_Request)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the USART ReQuest by setting the dedicated request bit in the RQR + register.*/ + USARTx->RQR |= USART_Request; + } + else + { + /* Disable the USART ReQuest by clearing the dedicated request bit in the RQR + register.*/ + USARTx->RQR &= (uint32_t)~USART_Request; + } +} + +/** + * @brief Enables or disables the USART's Overrun detection. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_OVRDetection: specifies the OVR detection status in case of OVR error. + * This parameter can be any combination of the following values: + * @arg USART_OVRDetection_Enable: OVR error detection enabled when the USART OVR error + * is asserted. + * @arg USART_OVRDetection_Disable: OVR error detection disabled when the USART OVR error + * is asserted. + * @retval None + */ +void USART_OverrunDetectionConfig(USART_TypeDef* USARTx, uint32_t USART_OVRDetection) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_OVRDETECTION(USART_OVRDetection)); + + /* Clear the OVR detection bit */ + USARTx->CR3 &= (uint32_t)~((uint32_t)USART_CR3_OVRDIS); + /* Set the new value for the OVR detection bit */ + USARTx->CR3 |= USART_OVRDetection; +} + +/** + * @brief Checks whether the specified USART flag is set or not. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg USART_FLAG_REACK: Receive Enable acknowledge flag. + * @arg USART_FLAG_TEACK: Transmit Enable acknowledge flag. + * @arg USART_FLAG_WUF: Wake up flag. + * @arg USART_FLAG_RWU: Receive Wake up flag. + * @arg USART_FLAG_SBK: Send Break flag. + * @arg USART_FLAG_CMF: Character match flag. + * @arg USART_FLAG_BUSY: Busy flag. + * @arg USART_FLAG_ABRF: Auto baud rate flag. + * @arg USART_FLAG_ABRE: Auto baud rate error flag. + * @arg USART_FLAG_EOBF: End of block flag. + * @arg USART_FLAG_RTOF: Receive time out flag. + * @arg USART_FLAG_nCTSS: Inverted nCTS input bit status. + * @arg USART_FLAG_CTS: CTS Change flag. + * @arg USART_FLAG_LBD: LIN Break detection flag. + * @arg USART_FLAG_TXE: Transmit data register empty flag. + * @arg USART_FLAG_TC: Transmission Complete flag. + * @arg USART_FLAG_RXNE: Receive data register not empty flag. + * @arg USART_FLAG_IDLE: Idle Line detection flag. + * @arg USART_FLAG_ORE: OverRun Error flag. + * @arg USART_FLAG_NE: Noise Error flag. + * @arg USART_FLAG_FE: Framing Error flag. + * @arg USART_FLAG_PE: Parity Error flag. + * @retval The new state of USART_FLAG (SET or RESET). + */ +FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint32_t USART_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_FLAG(USART_FLAG)); + + if ((USARTx->ISR & USART_FLAG) != (uint16_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the USARTx's pending flags. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg USART_FLAG_WUF: Wake up flag. + * @arg USART_FLAG_CMF: Character match flag. + * @arg USART_FLAG_EOBF: End of block flag. + * @arg USART_FLAG_RTOF: Receive time out flag. + * @arg USART_FLAG_CTS: CTS Change flag. + * @arg USART_FLAG_LBD: LIN Break detection flag. + * @arg USART_FLAG_TC: Transmission Complete flag. + * @arg USART_FLAG_IDLE: IDLE line detected flag. + * @arg USART_FLAG_ORE: OverRun Error flag. + * @arg USART_FLAG_NE: Noise Error flag. + * @arg USART_FLAG_FE: Framing Error flag. + * @arg USART_FLAG_PE: Parity Errorflag. + * + * @note + * - RXNE pending bit is cleared by a read to the USART_RDR register + * (USART_ReceiveData()) or by writing 1 to the RXFRQ in the register USART_RQR + * (USART_RequestCmd()). + * - TC flag can be also cleared by software sequence: a read operation to + * USART_SR register (USART_GetFlagStatus()) followed by a write operation + * to USART_TDR register (USART_SendData()). + * - TXE flag is cleared by a write to the USART_TDR register + * (USART_SendData()) or by writing 1 to the TXFRQ in the register USART_RQR + * (USART_RequestCmd()). + * - SBKF flag is cleared by 1 to the SBKRQ in the register USART_RQR + * (USART_RequestCmd()). + * @retval None + */ +void USART_ClearFlag(USART_TypeDef* USARTx, uint32_t USART_FLAG) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_CLEAR_FLAG(USART_FLAG)); + + USARTx->ICR = USART_FLAG; +} + +/** + * @brief Checks whether the specified USART interrupt has occurred or not. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_IT: specifies the USART interrupt source to check. + * This parameter can be one of the following values: + * @arg USART_IT_WU: Wake up interrupt. + * @arg USART_IT_CM: Character match interrupt. + * @arg USART_IT_EOB: End of block interrupt. + * @arg USART_IT_RTO: Receive time out interrupt. + * @arg USART_IT_CTS: CTS change interrupt. + * @arg USART_IT_LBD: LIN Break detection interrupt. + * @arg USART_IT_TXE: Tansmit Data Register empty interrupt. + * @arg USART_IT_TC: Transmission complete interrupt. + * @arg USART_IT_RXNE: Receive Data register not empty interrupt. + * @arg USART_IT_IDLE: Idle line detection interrupt. + * @arg USART_IT_ORE: OverRun Error interrupt. + * @arg USART_IT_NE: Noise Error interrupt. + * @arg USART_IT_FE: Framing Error interrupt. + * @arg USART_IT_PE: Parity Error interrupt. + * @retval The new state of USART_IT (SET or RESET). + */ +ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint32_t USART_IT) +{ + uint32_t bitpos = 0, itmask = 0, usartreg = 0; + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_GET_IT(USART_IT)); + + /* Get the USART register index */ + usartreg = (((uint16_t)USART_IT) >> 0x08); + /* Get the interrupt position */ + itmask = USART_IT & IT_MASK; + itmask = (uint32_t)0x01 << itmask; + + if (usartreg == 0x01) /* The IT is in CR1 register */ + { + itmask &= USARTx->CR1; + } + else if (usartreg == 0x02) /* The IT is in CR2 register */ + { + itmask &= USARTx->CR2; + } + else /* The IT is in CR3 register */ + { + itmask &= USARTx->CR3; + } + + bitpos = USART_IT >> 0x10; + bitpos = (uint32_t)0x01 << bitpos; + bitpos &= USARTx->ISR; + if ((itmask != (uint16_t)RESET)&&(bitpos != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + + return bitstatus; +} + +/** + * @brief Clears the USARTx's interrupt pending bits. + * @param USARTx: Select the USART peripheral. This parameter can be one of the + * following values: USART1 or USART2 or USART3 or UART4 or UART5. + * @param USART_IT: specifies the interrupt pending bit to clear. + * This parameter can be one of the following values: + * @arg USART_IT_WU: Wake up interrupt. + * @arg USART_IT_CM: Character match interrupt. + * @arg USART_IT_EOB: End of block interrupt. + * @arg USART_IT_RTO: Receive time out interrupt. + * @arg USART_IT_CTS: CTS change interrupt. + * @arg USART_IT_LBD: LIN Break detection interrupt. + * @arg USART_IT_TC: Transmission complete interrupt. + * @arg USART_IT_IDLE: IDLE line detected interrupt. + * @arg USART_IT_ORE: OverRun Error interrupt. + * @arg USART_IT_NE: Noise Error interrupt. + * @arg USART_IT_FE: Framing Error interrupt. + * @arg USART_IT_PE: Parity Error interrupt. + * @note + * - RXNE pending bit is cleared by a read to the USART_RDR register + * (USART_ReceiveData()) or by writing 1 to the RXFRQ in the register USART_RQR + * (USART_RequestCmd()). + * - TC pending bit can be also cleared by software sequence: a read + * operation to USART_SR register (USART_GetITStatus()) followed by a write + * operation to USART_TDR register (USART_SendData()). + * - TXE pending bit is cleared by a write to the USART_TDR register + * (USART_SendData()) or by writing 1 to the TXFRQ in the register USART_RQR + * (USART_RequestCmd()). + * @retval None + */ +void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint32_t USART_IT) +{ + uint32_t bitpos = 0, itmask = 0; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_CLEAR_IT(USART_IT)); + + bitpos = USART_IT >> 0x10; + itmask = ((uint32_t)0x01 << (uint32_t)bitpos); + USARTx->ICR = (uint32_t)itmask; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_wwdg.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_wwdg.c new file mode 100644 index 0000000..13e23e7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/lib/STM32F30x_StdPeriph_Driver/src/stm32f30x_wwdg.c @@ -0,0 +1,304 @@ +/** + ****************************************************************************** + * @file stm32f30x_wwdg.c + * @author MCD Application Team + * @version V1.1.1 + * @date 04-April-2014 + * @brief This file provides firmware functions to manage the following + * functionalities of the Window watchdog (WWDG) peripheral: + * + Prescaler, Refresh window and Counter configuration + * + WWDG activation + * + Interrupts and flags management + * + * @verbatim + * + ============================================================================== + ##### WWDG features ##### + ============================================================================== + + [..] Once enabled the WWDG generates a system reset on expiry of a programmed + time period, unless the program refreshes the counter (downcounter) + before to reach 0x3F value (i.e. a reset is generated when the counter + value rolls over from 0x40 to 0x3F). + [..] An MCU reset is also generated if the counter value is refreshed + before the counter has reached the refresh window value. This + implies that the counter must be refreshed in a limited window. + + [..] Once enabled the WWDG cannot be disabled except by a system reset. + + [..] WWDGRST flag in RCC_CSR register can be used to inform when a WWDG + reset occurs. + + [..] The WWDG counter input clock is derived from the APB clock divided + by a programmable prescaler. + + [..] WWDG counter clock = PCLK1 / Prescaler. + [..] WWDG timeout = (WWDG counter clock) * (counter value). + + [..] Min-max timeout value @36MHz (PCLK1): ~114us / ~58.3ms. + + ##### How to use this driver ##### + ============================================================================== + [..] + (#) Enable WWDG clock using RCC_APB1PeriphClockCmd(RCC_APB1Periph_WWDG, ENABLE) + function. + + (#) Configure the WWDG prescaler using WWDG_SetPrescaler() function. + + (#) Configure the WWDG refresh window using WWDG_SetWindowValue() function. + + (#) Set the WWDG counter value and start it using WWDG_Enable() function. + When the WWDG is enabled the counter value should be configured to + a value greater than 0x40 to prevent generating an immediate reset. + + (#) Optionally you can enable the Early wakeup interrupt which is + generated when the counter reach 0x40. + Once enabled this interrupt cannot be disabled except by a system reset. + + (#) Then the application program must refresh the WWDG counter at regular + intervals during normal operation to prevent an MCU reset, using + WWDG_SetCounter() function. This operation must occur only when + the counter value is lower than the refresh window value, + programmed using WWDG_SetWindowValue(). + + @endverbatim + + ****************************************************************************** + * @attention + * + *

    © COPYRIGHT 2014 STMicroelectronics

    + * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f30x_wwdg.h" +#include "stm32f30x_rcc.h" + +/** @addtogroup STM32F30x_StdPeriph_Driver + * @{ + */ + +/** @defgroup WWDG + * @brief WWDG driver modules + * @{ + */ + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* --------------------- WWDG registers bit mask ---------------------------- */ +/* CFR register bit mask */ +#define CFR_WDGTB_MASK ((uint32_t)0xFFFFFE7F) +#define CFR_W_MASK ((uint32_t)0xFFFFFF80) +#define BIT_MASK ((uint8_t)0x7F) + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/** @defgroup WWDG_Private_Functions + * @{ + */ + +/** @defgroup WWDG_Group1 Prescaler, Refresh window and Counter configuration functions + * @brief Prescaler, Refresh window and Counter configuration functions + * +@verbatim + ============================================================================== + ##### Prescaler, Refresh window and Counter configuration functions ##### + ============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Deinitializes the WWDG peripheral registers to their default reset values. + * @param None + * @retval None + */ +void WWDG_DeInit(void) +{ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, DISABLE); +} + +/** + * @brief Sets the WWDG Prescaler. + * @param WWDG_Prescaler: specifies the WWDG Prescaler. + * This parameter can be one of the following values: + * @arg WWDG_Prescaler_1: WWDG counter clock = (PCLK1/4096)/1 + * @arg WWDG_Prescaler_2: WWDG counter clock = (PCLK1/4096)/2 + * @arg WWDG_Prescaler_4: WWDG counter clock = (PCLK1/4096)/4 + * @arg WWDG_Prescaler_8: WWDG counter clock = (PCLK1/4096)/8 + * @retval None + */ +void WWDG_SetPrescaler(uint32_t WWDG_Prescaler) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_WWDG_PRESCALER(WWDG_Prescaler)); + /* Clear WDGTB[1:0] bits */ + tmpreg = WWDG->CFR & CFR_WDGTB_MASK; + /* Set WDGTB[1:0] bits according to WWDG_Prescaler value */ + tmpreg |= WWDG_Prescaler; + /* Store the new value */ + WWDG->CFR = tmpreg; +} + +/** + * @brief Sets the WWDG window value. + * @param WindowValue: specifies the window value to be compared to the downcounter. + * This parameter value must be lower than 0x80. + * @retval None + */ +void WWDG_SetWindowValue(uint8_t WindowValue) +{ + __IO uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_WWDG_WINDOW_VALUE(WindowValue)); + /* Clear W[6:0] bits */ + + tmpreg = WWDG->CFR & CFR_W_MASK; + + /* Set W[6:0] bits according to WindowValue value */ + tmpreg |= WindowValue & (uint32_t) BIT_MASK; + + /* Store the new value */ + WWDG->CFR = tmpreg; +} + +/** + * @brief Enables the WWDG Early Wakeup interrupt(EWI). + * @note Once enabled this interrupt cannot be disabled except by a system reset. + * @param None + * @retval None + */ +void WWDG_EnableIT(void) +{ + WWDG->CFR |= WWDG_CFR_EWI; +} + +/** + * @brief Sets the WWDG counter value. + * @param Counter: specifies the watchdog counter value. + * This parameter must be a number between 0x40 and 0x7F (to prevent generating + * an immediate reset). + * @retval None + */ +void WWDG_SetCounter(uint8_t Counter) +{ + /* Check the parameters */ + assert_param(IS_WWDG_COUNTER(Counter)); + /* Write to T[6:0] bits to configure the counter value, no need to do + a read-modify-write; writing a 0 to WDGA bit does nothing */ + WWDG->CR = Counter & BIT_MASK; +} + +/** + * @} + */ + +/** @defgroup WWDG_Group2 WWDG activation functions + * @brief WWDG activation functions + * +@verbatim + ============================================================================== + ##### WWDG activation function ##### + ============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Enables WWDG and load the counter value. + * @param Counter: specifies the watchdog counter value. + * This parameter must be a number between 0x40 and 0x7F (to prevent generating + * an immediate reset). + * @retval None + */ +void WWDG_Enable(uint8_t Counter) +{ + /* Check the parameters */ + assert_param(IS_WWDG_COUNTER(Counter)); + WWDG->CR = WWDG_CR_WDGA | Counter; +} + +/** + * @} + */ + +/** @defgroup WWDG_Group3 Interrupts and flags management functions + * @brief Interrupts and flags management functions + * +@verbatim + ============================================================================== + ##### Interrupts and flags management functions ##### + ============================================================================== + +@endverbatim + * @{ + */ + +/** + * @brief Checks whether the Early Wakeup interrupt flag is set or not. + * @param None + * @retval The new state of the Early Wakeup interrupt flag (SET or RESET). + */ +FlagStatus WWDG_GetFlagStatus(void) +{ + FlagStatus bitstatus = RESET; + + if ((WWDG->SR) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears Early Wakeup interrupt flag. + * @param None + * @retval None + */ +void WWDG_ClearFlag(void) +{ + WWDG->SR = (uint32_t)RESET; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/main.c b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/main.c new file mode 100644 index 0000000..7f551c5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/main.c @@ -0,0 +1,51 @@ +/* + main.c : entry routine for for STM32F103CB + + Adapted from https://github.com/multiwii/baseflight/blob/master/src/main.c + + This file is part of BreezySTM32. + + BreezySTM32 is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + BreezySTM32 is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with BreezySTM32. If not, see . + */ + +#include "breezystm32.h" + +serialPort_t * Serial1; + +extern void SetSysClock(bool overclock); + +static void _putc(void *p, char c) +{ + (void)p; // avoid compiler warning about unused variable + serialWrite(Serial1, c); + + while (!isSerialTransmitBufferEmpty(Serial1)); +} + +int main(void) +{ + // Configure clock, this figures out HSE for hardware autodetect + SetSysClock(0); + + systemInit(); + + Serial1 = uartOpen(USART1, NULL, 115200, MODE_RXTX); + + setup(); + + init_printf( NULL, _putc); + + while (1) + loop(); +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/startup_stm32f10x_md_gcc.S b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/startup_stm32f10x_md_gcc.S new file mode 100644 index 0000000..4bd8b2b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/startup_stm32f10x_md_gcc.S @@ -0,0 +1,408 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_md.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Medium Density Devices vector table for Atollic toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

    © COPYRIGHT 2011 STMicroelectronics

    + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + ldr r0, =0x20004FF0 // HJI - TC bootloader entry on reset mod + ldr r1, =0xDEADBEEF // HJI - TC bootloader entry on reset mod + ldr r2, [r0, #0] // HJI - TC bootloader entry on reset mod + str r0, [r0, #0] // HJI - TC bootloader entry on reset mod + cmp r2, r1 // HJI - TC bootloader entry on reset mod + beq Reboot_Loader // HJI - TC bootloader entry on reset mod + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main +/* Atollic update, branch LoopForever */ +LoopForever: + b LoopForever + +.equ RCC_APB2ENR, 0x40021018 // HJI - TC bootloader entry on reset mod +.equ GPIO_AFIO_MASK, 0x00000009 // HJI - TC bootloader entry on reset mod +.equ GPIOB_CRL, 0x40010C00 // HJI - TC bootloader entry on reset mod +.equ GPIOB_BRR, 0x40010C14 // HJI - TC bootloader entry on reset mod +.equ AFIO_MAPR, 0x40010004 // HJI - TC bootloader entry on reset mod + +Reboot_Loader: // HJI - TC bootloader entry on reset mod + // RCC Enable GPIOB+AFIO // HJI - TC bootloader entry on reset mod + ldr r6, =RCC_APB2ENR // HJI - TC bootloader entry on reset mod + ldr r0, =GPIO_AFIO_MASK // HJI - TC bootloader entry on reset mod + str R0, [r6]; // HJI - TC bootloader entry on reset mod + + // MAPR pt1 // HJI - TC bootloader entry on reset mod + ldr r0, =AFIO_MAPR // HJI - TC bootloader entry on reset mod + ldr r1, [r0] // HJI - TC bootloader entry on reset mod + bic r1, r1, #0x0F000000 // HJI - TC bootloader entry on reset mod + str r1, [r0] // HJI - TC bootloader entry on reset mod + + // MAPR pt2 // HJI - TC bootloader entry on reset mod + lsls r1, r0, #9 // HJI - TC bootloader entry on reset mod + str r1, [r0] // HJI - TC bootloader entry on reset mod + + // BRR // HJI - TC bootloader entry on reset mod + ldr r4, =GPIOB_BRR // HJI - TC bootloader entry on reset mod + movs r0, #0x18 // HJI - TC bootloader entry on reset mod + str r0, [r4] // HJI - TC bootloader entry on reset mod + + // CRL // HJI - TC bootloader entry on reset mod + ldr r1, =GPIOB_CRL // HJI - TC bootloader entry on reset mod + ldr r0, =0x44433444 // HJI - TC bootloader entry on reset mod + str r0, [r1] // HJI - TC bootloader entry on reset mod + + // Reboot to ROM // HJI - TC bootloader entry on reset mod + ldr r0, =0x1FFFF000 // HJI - TC bootloader entry on reset mod + ldr sp,[r0, #0] // HJI - TC bootloader entry on reset mod + ldr r0,[r0, #4] // HJI - TC bootloader entry on reset mod + bx r0 // HJI - TC bootloader entry on reset mod + +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Medium Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/stm32_flash.ld b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/stm32_flash.ld new file mode 100644 index 0000000..7d6cbb9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/lib/breezystm32/stm32_flash.ld @@ -0,0 +1,150 @@ +/* +***************************************************************************** +** +** File : stm32_flash.ld +** +** Abstract : Linker script for STM32F103CB Device with +** 128KByte FLASH, 20KByte RAM +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20005000; /* end of 20K RAM */ + +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Specify the memory areas. Flash is limited for last 2K for configuration storage */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 126K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(.fini_array*)) + KEEP (*(SORT(.fini_array.*))) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = .; + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + /* MEMORY_bank1 section, code must be located here explicitly */ + /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ + .memory_b1_text : + { + *(.mb1text) /* .mb1text sections (code) */ + *(.mb1text*) /* .mb1text* sections (code) */ + *(.mb1rodata) /* read-only data (constants) */ + *(.mb1rodata*) + } >MEMORY_B1 + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/main.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/main.cpp new file mode 100644 index 0000000..a3068b3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/main.cpp @@ -0,0 +1,48 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include "naze32.h" +#include "rosflight.h" +//#include "mavlink.h" + +int main(void) +{ + rosflight_firmware::Naze32 board; + rosflight_firmware::ROSflight firmware(board); + + firmware.init(); + + while(1) + { + firmware.run(); + } + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/naze32.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/naze32.cpp new file mode 100644 index 0000000..e2a54c2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/naze32.cpp @@ -0,0 +1,296 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +extern "C" +{ +#include +#include "flash.h" +extern void SetSysClock(bool overclock); + +void WWDG_IRQHandler() +{ + volatile int debug = 1; +} +} + +#include "naze32.h" + +namespace rosflight_firmware { + +Naze32::Naze32(){} + +void Naze32::init_board(void) +{ + // Configure clock, this figures out HSE for hardware autodetect + SetSysClock(0); + systemInit(); + _board_revision = 2; +} + +void Naze32::board_reset(bool bootloader) +{ + systemReset(bootloader); +} + +// clock + +uint32_t Naze32::clock_millis() +{ + return millis(); +} + +uint64_t Naze32::clock_micros() +{ + return micros(); +} + +void Naze32::clock_delay(uint32_t milliseconds) +{ + delay(milliseconds); +} + +// serial + +void Naze32::serial_init(uint32_t baud_rate) +{ + Serial1 = uartOpen(USART1, NULL, baud_rate, MODE_RXTX); +} + +void Naze32::serial_write(const uint8_t *src, size_t len) +{ + for (size_t i = 0; i < len; i++) + { + serialWrite(Serial1, src[i]); + } +} + +uint16_t Naze32::serial_bytes_available(void) +{ + return serialTotalBytesWaiting(Serial1); +} + +uint8_t Naze32::serial_read(void) +{ + return serialRead(Serial1); +} + +// sensors + +void Naze32::sensors_init() +{ + _board_revision = 2; + // Initialize I2c + i2cInit(I2CDEV_2); + + while(millis() < 50); + + i2cWrite(0,0,0); + ms5611_init(); + hmc5883lInit(_board_revision); + mb1242_init(); + ms4525_init(); + + // IMU + uint16_t acc1G; + mpu6050_init(true, &acc1G, &_gyro_scale, _board_revision); + _accel_scale = 9.80665f/acc1G; +} + +uint16_t Naze32::num_sensor_errors(void) +{ + return i2cGetErrorCounter(); +} + +bool Naze32::new_imu_data() +{ + return mpu6050_new_data(); +} + +bool Naze32::imu_read(float accel[3], float* temperature, float gyro[3], uint64_t* time_us) +{ + volatile int16_t gyro_raw[3], accel_raw[3]; + volatile int16_t raw_temp; + mpu6050_async_read_all(accel_raw, &raw_temp, gyro_raw, time_us); + + accel[0] = accel_raw[0] * _accel_scale; + accel[1] = -accel_raw[1] * _accel_scale; + accel[2] = -accel_raw[2] * _accel_scale; + + gyro[0] = gyro_raw[0] * _gyro_scale; + gyro[1] = -gyro_raw[1] * _gyro_scale; + gyro[2] = -gyro_raw[2] * _gyro_scale; + + (*temperature) = (float)raw_temp/340.0f + 36.53f; + + if (accel[0] == 0 && accel[1] == 0 && accel[2] == 0) + { + return false; + } + else return true; +} + +void Naze32::imu_not_responding_error(void) +{ + // If the IMU is not responding, then we need to change where we look for the + // interrupt + _board_revision = (_board_revision < 4) ? 5 : 2; + sensors_init(); +} + +void Naze32::mag_read(float mag[3]) +{ + // Convert to NED + int16_t raw_mag[3]; + // hmc5883l_update(); + hmc5883l_request_async_update(); + hmc5883l_async_read(raw_mag); + mag[0] = (float)raw_mag[0]; + mag[1] = (float)raw_mag[1]; + mag[2] = (float)raw_mag[2]; +} + +bool Naze32::mag_check(void) +{ + return hmc5883l_present(); +} + +void Naze32::baro_read(float *pressure, float *temperature) +{ + ms5611_async_update(); + ms5611_async_read(pressure, temperature); +} + +bool Naze32::baro_check() +{ + ms5611_async_update(); + return ms5611_present(); +} + +bool Naze32::diff_pressure_check(void) +{ + ms4525_async_update(); + return ms4525_present(); +} + +void Naze32::diff_pressure_read(float *diff_pressure, float *temperature) +{ + ms4525_async_update(); + ms4525_async_read(diff_pressure, temperature); +} + +bool Naze32::sonar_check(void) +{ + mb1242_async_update(); + if (mb1242_present()) + { + sonar_type = SONAR_I2C; + return true; + } + else if (sonarPresent()) + { + sonar_type = SONAR_PWM; + return true; + } + else + { + sonar_type = SONAR_NONE; + return false; + } +} + +float Naze32::sonar_read(void) +{ + if (sonar_type == SONAR_I2C) + { + mb1242_async_update(); + return mb1242_async_read(); + } + else if (sonar_type == SONAR_PWM) + return sonarRead(6); + else + return 0.0f; +} + +uint16_t num_sensor_errors(void) +{ + return i2cGetErrorCounter(); +} + +// PWM + +void Naze32::pwm_init(bool cppm, uint32_t refresh_rate, uint16_t idle_pwm) +{ + pwmInit(cppm, false, false, refresh_rate, idle_pwm); +} + +uint16_t Naze32::pwm_read(uint8_t channel) +{ + return pwmRead(channel); +} + +void Naze32::pwm_write(uint8_t channel, uint16_t value) +{ + pwmWriteMotor(channel, value); +} + +bool Naze32::pwm_lost() +{ + return ((millis() - pwmLastUpdate()) > 40); +} + +// non-volatile memory + +void Naze32::memory_init(void) +{ + initEEPROM(); +} + +bool Naze32::memory_read(void * dest, size_t len) +{ + return readEEPROM(dest, len); +} + +bool Naze32::memory_write(const void * src, size_t len) +{ + return writeEEPROM(src, len); +} + +// LED + +void Naze32::led0_on(void) { LED0_ON; } +void Naze32::led0_off(void) { LED0_OFF; } +void Naze32::led0_toggle(void) { LED0_TOGGLE; } + +void Naze32::led1_on(void) { LED1_ON; } +void Naze32::led1_off(void) { LED1_OFF; } +void Naze32::led1_toggle(void) { LED1_TOGGLE; } + +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/naze32.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/naze32.h new file mode 100644 index 0000000..eda87e3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/boards/naze/naze32.h @@ -0,0 +1,131 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +extern "C" +{ +#include +} + +#include "board.h" + +namespace rosflight_firmware { + +class Naze32 : public Board +{ + +private: + serialPort_t *Serial1; + + std::function imu_callback_; + + int _board_revision = 2; + + float _accel_scale = 1.0; + float _gyro_scale = 1.0; + + enum + { + SONAR_NONE, + SONAR_I2C, + SONAR_PWM + }; + uint8_t sonar_type = SONAR_NONE; + + + +public: + Naze32(); + + bool new_imu_data_; + uint64_t imu_time_us_; + + // setup + void init_board(void); + void board_reset(bool bootloader); + + // clock + uint32_t clock_millis(); + uint64_t clock_micros(); + void clock_delay(uint32_t milliseconds); + + // serial + void serial_init(uint32_t baud_rate); + void serial_write(const uint8_t *src, size_t len); + uint16_t serial_bytes_available(void); + uint8_t serial_read(void); + + // sensors + void sensors_init(); + uint16_t num_sensor_errors(void); + + bool new_imu_data(); + bool imu_read(float accel[3], float* temperature, float gyro[3], uint64_t* time_us); + void imu_not_responding_error(); + + bool mag_check(void); + void mag_read(float mag[3]); + + bool baro_check(); + void baro_read(float *pressure, float *temperature); + + bool diff_pressure_check(void); + void diff_pressure_read(float *diff_pressure, float *temperature); + + bool sonar_check(void); + float sonar_read(void); + + // PWM + // TODO make these deal in normalized (-1 to 1 or 0 to 1) values (not pwm-specific) + void pwm_init(bool cppm, uint32_t refresh_rate, uint16_t idle_pwm); + bool pwm_lost(); + uint16_t pwm_read(uint8_t channel); + void pwm_write(uint8_t channel, uint16_t value); + + // non-volatile memory + void memory_init(void); + bool memory_read(void * dest, size_t len); + bool memory_write(const void * src, size_t len); + + // LEDs + void led0_on(void); + void led0_off(void); + void led0_toggle(void); + + void led1_on(void); + void led1_off(void); + void led1_toggle(void); +}; + +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/custom_theme/extra.css b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/custom_theme/extra.css new file mode 100644 index 0000000..0a7b741 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/custom_theme/extra.css @@ -0,0 +1,3 @@ +.wy-nav-content { + max-width: 960px; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/custom_theme/img/favicon.ico b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/custom_theme/img/favicon.ico new file mode 100644 index 0000000..d4c4092 Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/custom_theme/img/favicon.ico differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/index.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/index.md new file mode 100644 index 0000000..43d1255 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/index.md @@ -0,0 +1,23 @@ +# Welcome to ROSflight + +ROSflight is an autopilot system that is designed from the ground up for integration with [ROS](http://www.ros.org/). It's purpose is to accomplish two main tasks: + + 1. Stream high-rate sensor data from the embedded flight controller to ROS + 2. Provide a simple API for sending control setpoints to the embedded flight controller + +A ROSflight setup consists of two main components: + + 1. **The embedded flight controller:** Typically a Naze32 or one of its variants, running the ROSflight [firmware](https://github.com/rosflight/firmware) + 2. **The onboard computer:** Any computer that runs ROS, located on the vehicle with a physical serial connection to the embedded flight controller + +## Why ROSflight? + +There are a lot of excellent autopilots out there, with a lot of great firmware options. Why did we feel like the world needed ROSflight? Because in our experience none of the other available options satisfied our research needs. Specifically, we needed an autopilot that could stream sensor data at high rates, easily accept control setpoints from an onboard computer, and accomplish all of this with a lean, easy to understand code base. + +The other options that we tried were limited in bandwidth for streaming sensor data, and the APIs for sending control setpoints were confusing and difficult to implement. Perhaps most importantly, the code was sometimes so complex (feature-rich, but complicated) that it was difficult to figure out what the autopilot was actually doing. In talking to other researchers and industry members, we found that many people shared similar frustrations. So we decided to create the autopilot that we wanted and share it in the hopes that it will be useful to other people as well. + +## Our Vision + +Perhaps more important than what we're trying to accomplish with ROSflight is what we're _not_ trying to accomplish. This is not intended to be, out-of-the-box, a fully-featured autopilot for high-level tasks such as autonomous GPS waypoint following. There are many good autopilots out there that already do this. Instead, ROSflight is intended to provide the minimal functionality required to keep a multirotor or fixed-wing vehicle in the air, and to serve as a building block for writing new code to perform these higher-level tasks (the [ROSplane](https://github.com/byu-magicc/ros_plane) and [ROScopter](https://github.com/byu-magicc/ros_copter) projects are excellent examples of what can be accomplished by building on top of the ROSflight architecture). + +Therefore, one of the primary objectives of the ROSflight autopilot is to avoid feature creep and remain _lean_. We hope that others will extend our code and build on top of it, and would love to hear about your successes. But for the most part, we will not be incorporating these new features back into the main project. Instead, we hope that ROSflight will remain a lean, core code base that will continue to serve as a launch pad for exciting new projects and applications. diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/requirements.txt b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/requirements.txt new file mode 100644 index 0000000..1cb2637 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/requirements.txt @@ -0,0 +1 @@ +https://github.com/mitya57/python-markdown-math/archive/master.zip diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/autonomous-flight.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/autonomous-flight.md new file mode 100644 index 0000000..ef04e3e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/autonomous-flight.md @@ -0,0 +1,78 @@ +# Autonomous flight + +One of the core functionalities of the ROSflight autopilot is to allow the onboard computer to send control setpoints to the embedded flight controller. These setpoints would typically be computed by a controller running as a ROS node, normally on the onboard computer. + +## Provide control from an onboard computer + +Control setpoints are sent to the autopilot by publishing to the `/command` topic that is advertised by the `rosflight_io` node. This topic accepts message of type `rosflight_msgs/Command`, which have the following structure: + +``` +std_msgs/Header header +uint8 mode +uint8 ignore +float32 x +float32 y +float32 z +float32 F +``` + +The `header` field is a standard ROS message header. The `x`, `y`, `z`, and `F` fields are the control setpoint values, which are interpreted according to the `mode` and `ignore` fields. + +The following table describes the different values that the `mode` field can take, as well as how the setpoint values are interpreted for each of these modes: + +| Value | Enum | x | y | z | F | +|-------|------|---|---|---|---| +| 0 | `MODE_PASS_THROUGH` | aileron deflection (-1 to 1) | elevator deflection (-1 to 1) | rudder deflection (-1 to 1) | throttle (0 to 1) | +| 1 | `MODE_ROLLRATE_PITCHRATE_YAWRATE_THROTTLE` | roll rate (rad/s) | pitch rate (rad/s) | yaw rate (rad/s) | throttle (0 to 1) | +| 2 | `MODE_ROLL_PITCH_YAWRATE_THROTTLE` | roll angle (rad) | pitch angle (rad) | yaw rate (rad/s) | throttle (0 to 1) | + +The `MODE_PASS_THROUGH` mode is used for fixed-wing vehicles to directly specify the control surface deflections and throttle, while the `MODE_ROLLRATE_PITCHRATE_YAWRATE_THROTTLE` and `MODE_ROLL_PITCH_YAWRATE_THROTTLE` modes are used for multirotor vehicles to specify the attitude rates or angles respectively. + +The `ignore` field is used if you want to specify control setpoints for some, but not all, of the axes. For example, I may want to specify a throttle setpoint to perform altitude hold, but still let the RC pilot specify the attitude setpoints. The `ignore` field is a bitmask that can be populated by combining the following values: + +| Value | Enum | Result | +|-------|------|--------| +| 0 | `IGNORE_NONE` | Ignore none of the fields (default) | +| 1 | `IGNORE_X` | Ignore the `x` field | +| 2 | `IGNORE_Y` | Ignore the `y` field | +| 4 | `IGNORE_Z` | Ignore the `z` field | +| 8 | `IGNORE_F` | Ignore the `F` field | + +For the previous example, I would set the `ignore` field to a value of +``` +ignore = IGNORE_X | IGNORE_Y | IGNORE_Z +``` + +The best practice is to use enum names rather than the actual numeric values for the `mode` and `ignore` fields. For example, to specify a multirotor attitude angle command in C++ I might have +```cpp +#include +#include + +rosflight_msgs::Command msg; +msg.header.stamp = ros::Time::now(); +msg.mode = rosflight_msgs::Command::MODE_ROLL_PITCH_YAWRATE_THROTTLE; +msg.ignore = rosflight_msgs::Command::IGNORE_NONE; +msg.x = 0.0; +msg.y = 0.0; +msg.z = 0.0; +msg.F = 0.6; +``` +and in Python I might have +```python +import rospy +from rosflight_msgs.msg import Command + +msg = Command() +msg.header.stamp = rospy.Time.now() +msg.mode = Command.MODE_ROLL_PITCH_YAWRATE_THROTTLE +msg.ignore = Command.IGNORE_NONE +msg.x = 0.0 +msg.y = 0.0 +msg.z = 0.0 +msg.F = 0.6 +``` +I would then publish this message to the `/command` topic to forward it to the embedded flight controller. + +## Fly waypoints with ros_plane or ros_copter + +Waypoint following is not supported natively by the ROSflight stack. However, the [ROSplane](https://github.com/byu-magicc/ros_plane) and [ROScopter](https://github.com/byu-magicc/ros_copter) projects are good example implementations of how to achieve this using ROSflight. They also provide good examples of how you might go about integrating your own guidance or control algorithms with the ROSflight stack. diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/autopilot-setup.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/autopilot-setup.md new file mode 100644 index 0000000..571f652 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/autopilot-setup.md @@ -0,0 +1,40 @@ +# Compatible hardware + +As of June 2017 ROSflight is only supported on flight controllers with STM32F103 processors, specifically, the naze32 and the flip32. Both the 6-DOF and 10-DOF versions of each board are fully supported. We have had most success with flip32 boards purchased directly from [readytoflyquads.com](http://www.readytoflyquads.com/). We have had weird issues with knock-off boards from Chinese vendors. + +# Flashing firmware using the Cleanflight Configurator + +* Download the latest version of ROSflight [here](https://github.com/rosflight/firmware/releases). +* Install the cleanflight configurator - It is an extension to Google Chrome - [link](https://chrome.google.com/webstore/detail/cleanflight-configurator/enacoimjcgeinfnnnpajinjgmkahmfgb?hl=en) +* Be sure your user is in the `dialout` group so you have access to the serial ports +* Load the firmware and flash using cleanflight configurator + + * Open the configurator, open firmware flasher. Connect your flight controller, and make sure that you have selected the right port. Then select "Load Firmware (Local)" and select your .hex file you downloaded earlier. +![cleanflight_gui_1](images/cleanflight_configurator-1.png) + * Short the boot pins on your flight controller, unplug it, and and plug back in. +![boot_pins](images/boot_pins.png) +* If you scroll to the bottom of the screen, you will then see the green bar indicate progress as the hex is flashed to the flight controller. You should then see something like the following +![success](images/sucessful_flash.png) + +* You're done! Great job + + +# Flashing Firmware using stm32flash (CLI Linux) + +You can also use stm32flash to flash firmware. This is helpful if you need (or prefer) a command-line interface. + +* Download and install stm32flash +``` bash +git clone git://git.code.sf.net/p/stm32flash/code stm32flash-code +cd stm32flash-code +sudo make install +cd .. +rm -rf stm32flash-code +``` +* Make sure you are in the dialout group (same instructions as above) +* Short boot pins, restart the naze (by unplugging and plugging back in) +* Download the latest rosflight.hex file [here](https://github.com/rosflight/firmware/releases). +* Flash the firmware to the proper device (replace `/dev/ttyUSB0`) +``` bash + stm32flash -w rosflight.hex -v -g 0x0 -b 921600 /dev/ttyUSB0 +``` diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/getting-started.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/getting-started.md new file mode 100644 index 0000000..5cce0f8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/getting-started.md @@ -0,0 +1,12 @@ +# Getting Started + +Reading through the pages in this user guide in order should provide you with the information you need to get a vehicle flying with ROSflight. The following is a summary of the steps you'll need to follow to get your vehicle set up, with links to the corresponding documentation pages: + + 1. [Set up your hardware](/user-guide/hardware-setup) (fixed-wing or multirotor platform, autopilot, and onboard computer) + 2. [Flash your autopilot with the latest ROSflight firmware](/user-guide/autopilot-setup) + 3. [Set up ROS on your onboard computer](/user-guide/ros-setup) + 4. [Configure the autopilot for your setup](/user-guide/parameter-configuration) + 5. [Set up your RC transmitter](/user-guide/rc-configuration) + 6. [Run through your preflight checks](/user-guide/preflight-checks) + 7. [Tune the attitude controller gains](/user-guide/performance) (multirotors only) + 8. [Set up autonomous flight via offboard control](/user-guide/autonomous-flight) (optional) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/hardware-setup.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/hardware-setup.md new file mode 100644 index 0000000..4e81269 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/hardware-setup.md @@ -0,0 +1,116 @@ +# Parts list + +To use ROSflight to its full potential, you will need the following parts on your MAV (Minature Aerial Vehicle). ROSflight supports both multirotor and fixedwing vehicles. + +1. Aircraft Frame, Motor(s), ESC(s), Battery and Propeller(s) +2. Flight Controller (FC) +3. Any external sensors +4. Vibration Isolation for FC +5. Onboard Computer +6. Wi-Fi Router and Dongle +7. RC transmitter and receiver +8. Laptop or base station computer +9. Joystick (Xbox controller) + +## Frame, Motors, ESCs, Battery and Propeller + +We do not officially support any specific multirotor or airplane frame, motor, ESC, Battery or Propeller combination. There are a lot of great resources for building your own MAV, and there are a lot of great kits out there that have all of these parts. + +If you are designing your own multirotor or airplane, you may want to look at [ecalc](https://www.ecalc.ch/), an online tool which can help you design a proper ESC/Battery/Motor/Propeller system for your MAV. + +Some things to keep in mind as you design or build your MAV. + +* Most kits do not include space for an onboard computer, cameras, laser scanners or other sensors. Be sure to think about where these components are going to go, and how their placement will affect the CG of the MAV. +* You will likely also need to customize the power circuitry of your MAV to provide power at some specific voltage to your onboard computer. Many people like to separate the power electronics (The ESCs and motors) from the computer and onboard sensors. This can really come in handy if you are trying to develop code on the MAV, because you can have the computer on and sensors powered, and not worry at all about propellers turning on and causing injury as you move the aircraft about by hand. We will talk about this more when we talk about wiring up your MAV. +* Cheap propellers can cause a huge amount of vibration. Consider buying high-quality propellers, doing a propeller balance, or both. RCGroups, DIY Drones and Youtube have some awesome guides on how to do propeller balancing. +* ESCs will need to be calibrated from 2000 to 1000 us + + +## Flight Controller + +ROSflight is best supported on the flip32+ from [readytoflyquads.com](http://www.readytoflyquads.com/the-flip32-187). It works on any variant of the naze32 flight controller, but the flip32 has the convenience of having through-hole boot pins. The naze32 and flip32 have identical schematics, they differ only in the layout of the board. We have seen some problems using off-brand versions of the naze32 or flip32 because there are fake versions of accelerometers which can mess with the firmware; try to avoid those if you can. + +## External Sensors + +Additional Sensors you may want for your ROSflight setup include: + +* Sonar – MB1030 – [$25 on MaxBotix](https://www.maxbotix.com/Ultrasonic_Sensors/MB1030.htm) +* GPS – u-blox NEO-M8N – [$35 from Drotek](https://drotek.com/shop/en/511-ublox-neo-m8-gps-module.html) +* Digital Airspeed Sensor – [$65 on JDrones](http://store.jdrones.com/digital_airspeed_sensor_p/senair02kit.html) + +The I2C sonar (MB124X) is also supported, but PWM sonars are preferred. + +## Vibration Isolation + +It is really important to isolate your flight controller from vibrations from propellers and motors. We recommend using small amounts of [Kyosho Zeal](https://www.amazon.com/Kyosho-Z8006-Vibration-Absorption-Sheet/dp/B002U2GS2K/ref=sr_1_1?ie=UTF8&qid=1490068378&sr=8-1&keywords=kyosho+zeal) to mount a fiberglass plate holding the FC to the MAV. You may also want to try adding mass to the flight control board. We have accomplished this by gluing steel washers to the fiberglass mounting plate. + +![Vibration Isloation](images/vibration_isolation.png) + +You may need to experiment with the amount of gel you use, how far apart the gel is spaced, and the amount of mass added to the flight control board. The interaction of these factors is difficult to predict, therefore it takes a little bit of experimentation to get it right. + +## Onboard Computer + +The only requirement for the onboard computer is that it runs Linux 16.04, ROS, has at least one USB port, and can be carried by the aircraft. We have had success with the following onboard computers, but by no means is this a comprehensive list, it is more by way of suggestion. + +* MSI CUBI – i7-5500U – [$350 on Amazon](https://www.amazon.com/MSI-Intel-Support-Barebones-Cubi-028BUS/dp/B011Q6BBMW/ref=sr_1_6?s=electronics&ie=UTF8&qid=1490068829&sr=1-6&keywords=i7+NUC) +* GIGABYTE BRIX Gaming- i7-4710HQ/GTX 760 – [$850 on Amazon](https://www.amazon.com/dp/B00OJZVGFU/ref=cm_sw_su_dp) +* Intel NUC Skullcanyon – i7-6770HQ – [$570 on Amazon](https://www.amazon.com/dp/B01DJ9XS52/ref=cm_sw_su_dp) +* ODROID-XU4 – Exynos5 2GHz 8-core – [$77 on Ameridroid](http://ameridroid.com/products/odroid-xu4) +* ODROID-C2 – Cortex A53 2GHz 4-core – [$42 on Ameridroid](http://ameridroid.com/products/odroid-c2) +* Rasberry Pi 3 – Cortex A53 1.2GHz 4-core – [$36 on Amazon](https://www.amazon.com/dp/B01CD5VC92/ref=cm_sw_su_dp) +* NVIDIA Tegra TX1 - Cortex-A57 4-core CPU, 256-core Maxwell GPU - [$435 from NVIDA](http://www.nvidia.com/object/embedded-systems-dev-kits-modules.html) (Educational Discounts Available) + +## Wi-Fi + +You will need Wi-Fi to communicate with your MAV when it is in the air. ROS communicates over TCP, so it is really easy to use ROS to view what is going on in your MAV while it is flying, send commands and read sensor data. For most applications, a standard Wi-Fi router and dongle will suffice. For long-range applications, you may want to look into [Ubiquiti](https://www.ubnt.com/) point-to-point Wi-Fi. (We have seen ranges over a mile with these networks) + +## RC Transmitter and Reciever + +For RC Control, you will need a transmitter with between 6 and 8 channels. Any additional channels will be wasted. We require RC control for safe operation, and only support arming and disarming via RC control. + +As of version 1.0, ROSflight only supports PPM (pulse position modulation) receivers. Support for serial RC (Spektrum Sattelites) is expected in future releases. A recommended RC setup is described below, but is meant as an example. Any configurations with PPM and 6-8 channels will be sufficient. + +* Transmitter – [Spektrum DX8 $300 at Horizon Hobby](http://www.horizonhobby.com/dx8-transmitter-only-mode-2-spmr8000) +* Receiver – [Orange Rx 8Ch PPM $22 on HobbyKing](https://hobbyking.com/en_us/orangerx-r820x-v2-6ch-2-4ghz-dsm2-dsmx-comp-full-range-rx-w-sat-div-ant-f-safe-cppm.html/?___store=en_us) + + +## Laptop or Base Station Computer + +You will need a laptop which can run Ubuntu 16.04 and ROS to communicate with the MAV over WiFi. If you are new to Linux, I would recommend dual booting your computer rather than using VirtualBox. + +## Joystick + +The Joystick is not technically a required component, because it is possible to control your MAV over command line. It does make things easier, however. We recommend XBOX 360 controllers and have default parameters set for the XBOX configuration. Other joysticks are supported, but you may need to perform custom axis and button mappings. + +# Wiring diagram + +Below is an example wiring diagram for a multirotor using a MSI Cubi as an onboard computer. This diagram also includes the motor power switch, which allows for the sensors, flight controller and onboard computer to be power on while the motors are off. This is a safer way to work on the aircraft as the motors are unable to spin while the switch is off. + +![Wiring Diagram](images/Wiring_Diagram.png) + +Your needs will likely be slightly different than what is shown. This is meant as an example only and can be adapted to fit your needs. + +# Motor layouts + +The desired mixer can be chosen by setting the the "MIXER" parameter to the following values: + +| # | Mixer | +|---|---------| +| 0 | ESC calibration | +| 1 | Quad + | +| 2 | Quad X | +| 3 | Hex + | +| 4 | Hex X | +| 5 | Octo + | +| 6 | Octo X | +| 7 | Y6 | +| 8 | X8 | +| 9 | Tricopter | +| 10 | Fixed wing (traditional AETR) | + +The associated motor layouts are shown below for each mixer. +The _ESC calibration_ mixer outputs the throttle command equally to each motor, and can be used for calibrating the ESCs. + +![Mixer_1](images/mixers_1.png) + +![Mixer_2](images/mixers_2.png) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/CF_Diagram.png b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/CF_Diagram.png new file mode 100644 index 0000000..f51b09b Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/CF_Diagram.png differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/Wiring_Diagram.png b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/Wiring_Diagram.png new file mode 100644 index 0000000..35ae66b Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/Wiring_Diagram.png differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/boot_pins.png b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/boot_pins.png new file mode 100644 index 0000000..1c34e42 Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/boot_pins.png differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/cleanflight_configurator-1.png b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/cleanflight_configurator-1.png new file mode 100644 index 0000000..6953f18 Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/cleanflight_configurator-1.png differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/mixers_1.png b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/mixers_1.png new file mode 100644 index 0000000..97a44b9 Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/mixers_1.png differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/mixers_2.png b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/mixers_2.png new file mode 100644 index 0000000..0ae2403 Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/mixers_2.png differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/sticks.png b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/sticks.png new file mode 100644 index 0000000..dc6d2f0 Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/sticks.png differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/sucessful_flash.png b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/sucessful_flash.png new file mode 100644 index 0000000..8f0ab18 Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/sucessful_flash.png differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/tuning_flowchart.png b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/tuning_flowchart.png new file mode 100644 index 0000000..2708953 Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/tuning_flowchart.png differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/vibration_isolation.png b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/vibration_isolation.png new file mode 100644 index 0000000..a08bfae Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/images/vibration_isolation.png differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/parameter-configuration.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/parameter-configuration.md new file mode 100644 index 0000000..ff7a20f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/parameter-configuration.md @@ -0,0 +1,203 @@ +# Parameter interface + +The ROSflight firmware has several dozen parameters which it uses to customize performance. Parameters are considered semi-static variables. That is, parameters do not change during flight, but they may change between vehicles. Examples of parameters you may wish to change are: + +* Fixed-wing vehicle flag +* PID gains +* Mixer choice +* IMU low-pass filter constant +* RC receiver type + +and so on. All parameter access is enabled via ROS services advertised by `rosflight_io` while the flight controller is connected. + +## Getting Parameter Values + +Sometimes it is handy to ask the flight controller what the current value of a parameter is. This is accomplished using the `param_get` service. As an example, let's retrieve the roll angle controller P gain. + +``` +rosservice call /param_get PID_ROLL_ANG_P +``` + +You should get a response similar to (this happens to be the default value with floating-point error) + +``` +exists: True +value: 0.15000000596 +``` + +## Changing Parameters + +Parameters are changed via the `param_set` service. As an example, let's change the roll angle controller P gain. (I will assume that the flight controller is connected and `rosflight_io` is running in the root namespace). + +``` +rosservice call /param_set PID_ROLL_ANG_P 0.08 +``` + +You should get a prompt from `rosflight_io` saying +``` +[ INFO] [1491672408.585339558]: Parameter PID_ROLL_ANG_P has new value 0.08 +[ WARN] [1491672408.585508849]: There are unsaved changes to onboard parameters +``` + +Notice that the parameters have been set, but not saved. Parameter changes take effect immediately, however they will not persist over a reboot unless you *write* them to the non-volatile memory. This brings us to the next task. + +## Writing Parameters + +To ensure that parameter values persist between reboots, you must write the parameters to the non-volatile memory. This is done by calling `param_write` + +``` +rosservice call /param_write +``` + +`rosflight_io` should then respond with +``` +[ INFO] [1491672597.123201952]: Param write succeeded +[ INFO] [1491672597.123452908]: Onboard parameters have been saved +``` + +Parameter writing can only happen if the flight controller is disarmed. If the param write failed for some reason, you may want to make sure you are disarmed and try again. + +## Backing Up and Loading Parameters from File + +It is good practice to backup your parameter configuration in case you have to re-flash your firmware or you want to share configurations between vehicles. We can do this via the `param_save_to_file` and `param_load_from_file` services. + +First, let's back up our current parameter configuration: + +``` +rosservice call /param_save_to_file ~/parameters.yml +``` + +Parameters are saved in YAML format. You must also specify the absolute file name of where you would like your parameters to be saved. The current active set of parameters will be saved, regardless of what is in the non-volatile memory. + +Now, let's say we want to re-load this parameter file +``` +rosservice call /param_load_from_file ~/parameters.yml +``` +Again, you must specify the absolute file name of the file to be loaded + + +# Fixed-Wing Parameter Configuration + +Because ROSflight ships with default parameters for multirotors, you will probably want to change the following parameters if you want to fly a fixed wing aircraft. + + +| Parameter | Description | Type | Fixed Wing Value +|-----------|-------------|------|---------------| +| MOTOR_PWM_UPDATE | Refresh rate of motor commands to motors and servos (Hz) - See motor documentation | int | 50 | +| ARM_SPIN_MOTORS | Enforce MOTOR_IDLE_PWM | int | false | +| MOTOR_IDLE_THR | min throttle command sent to motors when armed (Set above 0.1 to spin when armed) | float | 0.1 | +| ARM_CHANNEL | RC switch channel mapped to arming [0 indexed, -1 to disable] | int | 4 | +| FIXED_WING | switches on passthrough commands for fixedwing operation | int | true | +| MIXER | Which mixer to choose - See [Mixer documentation](hardware-setup/#motor-layouts) | int | 4 | +| ELEVATOR_REV | reverses elevator servo output | int | 0/1 | +| AIL_REV | reverses aileron servo output | int | 0/1 | +| RUDDER_REV | reverses rudder servo output | int | 0/1 | +| CAL_GYRO_ARM | Calibrate gyros when arming - generally only for multirotors | int | false | 0 | 1 | + + +# Description of all Parameters + +This is a list of all parameters on ROSflight, their types, default values, and minimum and maximum recommended setting: + +| Parameter | Description | Type | Default Value | Min | Max | +|-----------|-------------|------|---------------|-----|-----| +| BAUD_RATE | Baud rate of MAVlink communication with onboard computer | int | 921600 | 9600 | 921600 | +| SYS_ID | Mavlink System ID | int | 1 | 1 | 255 | +| STRM_HRTBT | Rate of heartbeat streaming (Hz) | int | 1 | 0 | 1000 | +| STRM_STATUS | Rate of status streaming (Hz) | int | 10 | 0 | 1000 | +| STRM_ATTITUDE | Rate of attitude stream (Hz) | int | 200 | 0 | 1000 | +| STRM_IMU | Rate of IMU stream (Hz) | int | 500 | 0 | 1000 | +| STRM_MAG | Rate of magnetometer stream (Hz) | int | 50 | 0 | 75 | +| STRM_BARO | Rate of barometer stream (Hz) | int | 50 | 0 | 100 | +| STRM_AIRSPEED | Rate of airspeed stream (Hz) | int | 20 | 0 | 50 | +| STRM_SONAR | Rate of sonar stream (Hz) | int | 40 | 0 | 40 | +| STRM_SERVO | Rate of raw output stream | int | 50 | 0 | 490 | +| STRM_RC | Rate of raw RC input stream | int | 50 | 0 | 50 | +| PARAM_MAX_CMD | saturation point for PID controller output | float | 1.0 | 0 | 1.0 | +| PID_ROLL_RATE_P | Roll Rate Proportional Gain | float | 0.070f | 0.0 | 1000.0 | +| PID_ROLL_RATE_I | Roll Rate Integral Gain | float | 0.000f | 0.0 | 1000.0 | +| PID_ROLL_RATE_D | Rall Rate Derivative Gain | float | 0.000f | 0.0 | 1000.0 | +| PID_PITCH_RATE_P | Pitch Rate Proporitional Gain | float | 0.070f | 0.0 | 1000.0 | +| PID_PITCH_RATE_I | Pitch Rate Integral Gain | float | 0.0000f | 0.0 | 1000.0 | +| PID_PITCH_RATE_D | Pitch Rate Derivative Gain | float | 0.0000f | 0.0 | 1000.0 | +| PID_YAW_RATE_P | Yaw Rate Proporitional Gain | float | 0.25f | 0.0 | 1000.0 | +| PID_YAW_RATE_I | Yaw Rate Integral Gain | float | 0.0f | 0.0 | 1000.0 | +| PID_YAW_RATE_D | Yaw Rate Derivative Gain | float | 0.0f | 0.0 | 1000.0 | +| PID_ROLL_ANG_P | Roll Angle Proporitional Gain | float | 0.15f | 0.0 | 1000.0 | +| PID_ROLL_ANG_I | Roll Angle Integral Gain | float | 0.0f | 0.0 | 1000.0 | +| PID_ROLL_ANG_D | Roll Angle Derivative Gain | float | 0.05f | 0.0 | 1000.0 | +| PID_PITCH_ANG_P | Pitch Angle Proporitional Gain | float | 0.15f | 0.0 | 1000.0 | +| PID_PITCH_ANG_I | Pitch Angle Integral Gain | float | 0.0f | 0.0 | 1000.0 | +| PID_PITCH_ANG_D | Pitch Angle Derivative Gain | float | 0.05f | 0.0 | 1000.0 | +| X_EQ_TORQUE | Equilibrium torque added to output of controller on x axis | float | 0.0f | -1.0 | 1.0 | +| Y_EQ_TORQUE | Equilibrium torque added to output of controller on y axis | float | 0.0f | -1.0 | 1.0 | +| Z_EQ_TORQUE | Equilibrium torque added to output of controller on z axis | float | 0.0f | -1.0 | 1.0 | +| PID_TAU | Dirty Derivative time constant - See controller documentation | float | 0.05f | 0.0 | 1.0 | +| MOTOR_PWM_UPDATE | Refresh rate of motor commands to motors - See motor documentation | int | 490 | 0 | 1000 | +| MOTOR_IDLE_THR | min throttle command sent to motors when armed (Set above 0.1 to spin when armed) | float | 0.1 | 0.0 | 1.0 | +| FAILSAFE_THR | Throttle sent to motors in failsafe condition (set just below hover throttle) | float | 0.3 | 0.0 | 1.0 | +| MOTOR_MIN_PWM | PWM value sent to motor ESCs at zero throttle | int | 1000 | 1000 | 2000 | +| MOTOR_MAX_PWM | PWM value sent to motor ESCs at full throttle | int | 2000 | 1000 | 2000 | +| ARM_SPIN_MOTORS | Enforce MOTOR_IDLE_THR | int | true | 0 | 1 | +| FILTER_INIT_T | Time in ms to initialize estimator | int | 3000 | 0 | 100000 | +| FILTER_KP | estimator proportional gain - See estimator documentation | float | 0.5f | 0 | 10.0 | +| FILTER_KI | estimator integral gain - See estimator documentation | float | 0.05f | 0 | 1.0 | +| FILTER_QUAD_INT | Perform a quadratic averaging of LPF gyro data prior to integration (adds ~20 us to estimation loop on F1 processors) | int | 1 | 0 | 1 | +| FILTER_MAT_EXP | 1 - Use matrix exponential to improve gyro integration (adds ~90 us to estimation loop in F1 processors) 0 - use euler integration | int | 1 | 0 | 1 | +| FILTER_USE_ACC | Use accelerometer to correct gyro integration drift (adds ~70 us to estimation loop) | int | 1 | 0 | 1 | +| CAL_GYRO_ARM | True if desired to calibrate gyros on arm | int | false | 0 | 1 | +| GYRO_LPF_ALPHA | Low-pass filter constant - See estimator documentation | float | 0.3f | 0 | 1.0 | +| ACC_LPF_ALPHA | Low-pass filter constant - See estimator documentation | float | 0.5f | 0 | 1.0 | +| GYRO_X_BIAS | Constant x-bias of gyroscope readings | float | 0.0f | -1.0 | 1.0 | +| GYRO_Y_BIAS | Constant y-bias of gyroscope readings | float | 0.0f | -1.0 | 1.0 | +| GYRO_Z_BIAS | Constant z-bias of gyroscope readings | float | 0.0f | -1.0 | 1.0 | +| ACC_X_BIAS | Constant x-bias of accelerometer readings | float | 0.0f | -2.0 | 2.0 | +| ACC_Y_BIAS | Constant y-bias of accelerometer readings | float | 0.0f | -2.0 | 2.0 | +| ACC_Z_BIAS | Constant z-bias of accelerometer readings | float | 0.0f | -2.0 | 2.0 | +| ACC_X_TEMP_COMP | Linear x-axis temperature compensation constant | float | 0.0f | -2.0 | 2.0 | +| ACC_Y_TEMP_COMP | Linear y-axis temperature compensation constant | float | 0.0f | -2.0 | 2.0 | +| ACC_Z_TEMP_COMP | Linear z-axis temperature compensation constant | float | 0.0f | -2.0 | 2.0 | +| MAG_A11_COMP | Soft iron compensation constant | float | 1.0f | -999.0 | 999.0 | +| MAG_A12_COMP | Soft iron compensation constant | float | 0.0f | -999.0 | 999.0 | +| MAG_A13_COMP | Soft iron compensation constant | float | 0.0f | -999.0 | 999.0 | +| MAG_A21_COMP | Soft iron compensation constant | float | 0.0f | -999.0 | 999.0 | +| MAG_A22_COMP | Soft iron compensation constant | float | 1.0f | -999.0 | 999.0 | +| MAG_A23_COMP | Soft iron compensation constant | float | 0.0f | -999.0 | 999.0 | +| MAG_A31_COMP | Soft iron compensation constant | float | 0.0f | -999.0 | 999.0 | +| MAG_A32_COMP | Soft iron compensation constant | float | 0.0f | -999.0 | 999.0 | +| MAG_A33_COMP | Soft iron compensation constant | float | 1.0f | -999.0 | 999.0 | +| MAG_X_BIAS | Hard iron compensation constant | float | 0.0f | -999.0 | 999.0 | +| MAG_Y_BIAS | Hard iron compensation constant | float | 0.0f | -999.0 | 999.0 | +| MAG_Z_BIAS | Hard iron compensation constant | float | 0.0f | -999.0 | 999.0 | +| BARO_BIAS | Barometer measurement bias (Pa) | float | 0.0f | 0 | inf | +| GROUND_LEVEL | Altitude of ground level (m) | float | 1387.0f | -1000 | 10000 | +| DIFF_PRESS_BIAS | Differential Pressure Bias (Pa) | float | 0.0f | -10 | 10 | +| RC_TYPE | Type of RC input 0 - Parallel PWM (PWM), 1 - Pulse-Position Modulation (PPM) | int | 1 | 0 | 1 | +| RC_X_CHN | RC input channel mapped to x-axis commands [0 - indexed] | int | 0 | 0 | 3 | +| RC_Y_CHN | RC input channel mapped to y-axis commands [0 - indexed] | int | 1 | 0 | 3 | +| RC_Z_CHN | RC input channel mapped to z-axis commands [0 - indexed] | int | 3 | 0 | 3 | +| RC_F_CHN | RC input channel mapped to F-axis commands [0 - indexed] | int | 2 | 0 | 3 | +| RC_ATT_OVRD_CHN | RC switch mapped to attitude override [0 indexed, -1 to disable] | int | 4 | 4 | 7 | +| RC_THR_OVRD_CHN | RC switch channel mapped to throttle override [0 indexed, -1 to disable] | int | 4 | 4 | 7 | +| RC_ATT_CTRL_CHN | RC switch channel mapped to attitude control type [0 indexed, -1 to disable] | int | -1 | 4 | 7 | +| ARM_CHANNEL | RC switch channel mapped to arming (only if PARAM_ARM_STICKS is false) [0 indexed, -1 to disable] | int | -1 | 4 | 7 | +| RC_NUM_CHN | number of RC input channels | int | 6 | 1 | 8 | +| SWITCH_5_DIR | RC switch 5 toggle direction | int | 1 | -1 | 1 | +| SWITCH_6_DIR | RC switch 6 toggle direction | int | 1 | -1 | 1 | +| SWITCH_7_DIR | RC switch 7 toggle direction | int | 1 | -1 | 1 | +| SWITCH_8_DIR | RC switch 8 toggle direction | int | 1 | -1 | 1 | +| RC_OVRD_DEV | RC stick deviation from center for overrride | float | 0.1 | 0.0 | 1.0 | +| OVRD_LAG_TIME | RC stick deviation lag time before returning control (ms) | int | 1000 | 0 | 100000 | +| MIN_THROTTLE | Take minimum throttle between RC and computer at all times | int | false | 0 | 1 | +| RC_ATT_MODE | Attitude mode for RC sticks (0: rate, 1: angle). Overridden if RC_ATT_CTRL_CHN is set. | int | 1 | 0 | 1 | +| RC_MAX_ROLL | Maximum roll angle command sent by full deflection of RC sticks | float | 0.786f | 0.0 | 3.14159 | +| RC_MAX_PITCH | Maximum pitch angle command sent by full stick deflection of RC sticks | float | 0.786f | 0.0 | 3.14159 | +| RC_MAX_ROLLRATE | Maximum roll rate command sent by full stick deflection of RC sticks | float | 3.14159f | 0.0 | 9.42477796077 | +| RC_MAX_PITCHRATE | Maximum pitch command sent by full stick deflection of RC sticks | float | 3.14159f | 0.0 | 3.14159 | +| RC_MAX_YAWRATE | Maximum pitch command sent by full stick deflection of RC sticks | float | 1.507f | 0.0 | 3.14159 | +| MIXER | Which mixer to choose - See Mixer documentation | int | 255 | 0 | 10 | +| FIXED_WING | switches on passthrough commands for fixedwing operation | int | false | 0 | 1 | +| ELEVATOR_REV | reverses elevator servo output | int | 0 | 0 | 1 | +| AIL_REV | reverses aileron servo output | int | 0 | 0 | 1 | +| RUDDER_REV | reverses rudder servo output | int | 0 | 0 | 1 | +| ARM_THRESHOLD | RC deviation from max/min in yaw and throttle for arming and disarming check (us) | float | 0.15 | 0 | 500 | diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/performance.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/performance.md new file mode 100644 index 0000000..210e4ed --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/performance.md @@ -0,0 +1,75 @@ +# Multirotor gain tuning + +Becuase there are a wide variety of multirotors out there, no one set of PID controller gains will work for all vehicles. The default set of gains is relatively conservative for most platforms, and should be somewhat airworthy in most cases, however, depending on the inertia to torque ratio for your MAV, you may have to change these gains considerably. There are some great tutorials online on multirotor gain tuning, however since this is the ROSflight documentation, I'll put my tuning method here for you. + +If you are unfamiliar with PIDs, then you should probably go read about them before trying to tune a multirotor. Getting an understanding for what is going on will definitely guide your decision making process as you try to figure out better gains. + +While tuning controller gains, there is a very likely scenario that the multirotor will oscillate out of control. To handle that, I generally add what I call "training wheels" to the multirotors I'm tuning, which amounts to thin carbon rods in the shape of an X zip-tied to the landing gear. This widens out the base of the quadcopter so if you come down on a hard oscillation, chances are you'll end up upright, hopefully without a prop strike. Here is a video of the maiden flight of ROSflight with "training wheels" attached. + + + +Now, for the procedure on tuning. + + +### Tuning Roll and Pitch Controllers + +Here is a flowchart describing my PID tuning process for roll and pitch: + +![tuning_flowchart](images/tuning_flowchart.png) + +You may want to do another D-tuning iteration, and sometimes it is helpful to do a little tweaking to eek out a little performance from the differences in roll and pitch dynamics. + +Notice, I didn't include any I tuning. As a general rule, try to keep the I gain as low as possible. It will _always_ slow your reponse rate to input, and it can induce low frequency oscillations. + +You should _only_ have I gain on roll and pitch if one of the following is true: + +1. You expect your CG to change or +2. you expect your rotor geometry to change. + +Both of these are pretty rare. Instead, use your RC transmitter to trim the aircraft so it hovers on no stick input. In the RC trim calculation section will use the RC trim to calculate a feed-forward torque on roll, pitch and yawrate. + + +### Tuning Yawrate + +Dynamically and algorithmically speaking, there is really not much advantage to using a D gain in yawrate. Controlling with derivative requires differentiating gyro input, which tends to be pretty noisy. In our experience, putting D in rate controllers on multirotors has always decreased performance. + +Tuning Yawrate is generally pretty easy, basically, keep cranking it up until you feel like it's "locked in". Sometimes a little bit of I (on the order of 0.1P) can help with this as well. + +The problem with too much P on yawrate generally manifests itself in motor saturation. Some, especially larger, multirotors have problems getting enough control authority in yaw with the propellers being aligned flat. After you're done tuning, you might want to look at a plot of motor outputs during a fairly agressive flight. Underactuated yaw will be pretty obvious in these plots, because you'll see the motor outputs railing. To fix this, you can put shims underneath the motors to tilt the motors just a little bit in the direction of yaw for that motor. + +# RC trim calculation + +In the vast majority of cases, your multirotor will not be built perfectly. The CG could be slightly off, or your motors, speed controllers and propellers could be slightly different. One way to fix this is by adding an integrator. Integrators get rid of static offsets like what we are talking about. However, as mentioned above, integrators also always slow your response. In our case, since this offset is going to be constant, we can instead find some "feed-forward" or equilibrium offset torque that you need to apply to hover exactly. + +Use the RC transmitter to find the "equilibrium torques" about the x, y, and z axes to keep the multirotor level. This is done by trimming the aircraft with the RC trims. These are usually the little switches next to sticks on your transmitter. Adjust these until you can hover the multirotor without touching the sticks. + +Next, land the multirotor, disarm, center the sticks and perform a trim calibration with `rosservice call /calibrate_rc_trim`. ROSflight then uses the trim settings on your transmitter to find these equilibrium or feed-forward torques that need to be applied post-controller to keep the multirotor level. These torques will be applied to all future commands, so you will need to zero out your transmitter trims after calibration. + +# Estimator Tuning + +ROSflight uses a non-linear complementary filter, based on the quaternion implementation of "[Non-linear complementary filters on the special orthogonal group](http://ieeexplore.ieee.org/document/4608934/) " by Robert Mahony to estimate attitude and angular rates. The implementation has been improved with suggestions from "[Attitude Representation and Kinematic Propagation for Low-Cost UAVs](https://arc.aiaa.org/doi/abs/10.2514/6.2013-4615)" by Robert Casey. A write-up of the derivation and implementation details can be found in the LaTeX report in `reports/estimator.tex` (You'll need to be able to compile LaTeX sources to view the PDF). + +In addition to the complementary filter, accelerometer and gyro measurements are filtered using a simple low-pass filter (LPF) to cut out noise from vibrations. A block diagram of the estimator is shown below for reference. \(y_{gyro}\) and \(y_{acc}\) are gyro and accelerometer measurements, respectively and \(\beta_{gyro}\) is the estimated gyro biases. + +![CF_diagram](images/CF_Diagram.png) + +### Tuning the Low-Pass Filter Gains + +The `ACC_LPF_ALPHA` and `GYRO_LPF_ALPHA` parameters are used in the following low-pass-filter implementation. (see lines `98-106` of `estimator.c`). + +$$x_t = (1-\alpha)y_t + \alpha x_{t-1}$$ + + +where \(y_t\) is the measurement and \(x_t\) is the filtered value. Lowering \(\alpha\) will reduce lag in response, so if you feel like your MAV is sluggish despite all attempts at controller gain tuning, consider reducing \(\alpha\). Reducing \(\alpha\) too far, however will result in a lot of noise from the sensors making its way into the motors. This can cause motors to get really hot, so make sure you check that if you are changing the low-pass filter constants. + +### Tuning the Complementary Filter +The complementary filter has two gains, \(k_p\) and \(k_i\). For a complete understanding of how these work, I would recommend reading the Mahony Paper, or the technical report in the reports folder. In short, \(k_p\) can be thought of the strength of accelerometer measurements in the filter, and the \(k_i\) gain is the integral constant on the gyro bias. These values should probably not be changed. Before you go changing these values, make sure you _completely_ understand how they work in the filter. + +If you do decide to change these values, you should stick to the following rule of thumb. + +$$k_i \approx \tfrac{k_p}{10}.$$ + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/preflight-checks.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/preflight-checks.md new file mode 100644 index 0000000..4760a3a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/preflight-checks.md @@ -0,0 +1,57 @@ +# Pre-Flight Checklist + +This is an example of a ROSflight pre-flight checklist. You will likely need to augment this with checks specific to your hardware and the code running on the onboard computer. + +## Generic Checklist + +### Before powering up motors +- ROS is running on onboard computer, communicating with base station +- Sensors are calibrated and publishing + + IMU (re-calibrate every flight): `rosservice call /calibrate_imu` + + Barometer: `rosservice call /calibrate_baro` + + Sonar (if attached) + + Airspeed (if attached) +- Estimated attitude is being published and looks accurate +- RC communication +- Arming and disarming +- Published outputs look reasonable +- Failsafe behavior +- RC override behavior +- RC range test +- Wire-wiggle test (wiggle all wires to look for bad connections) +- Parameter Check (if using a fixed wing, there are about 8 parameter you will need to change from default ) + +### After Powering Up Motors (MAKE SURE THE FLIGHT CONTROLLER IS DISARMED!!!) +- Arm/Disarm test +- Propeller spin test (check directions and response to stick inputs) +- Control surface test (Fixed Wing) +- Response to offboard controls (Fixed Wing) + + +## ROSplane Checklist + +### Before Leaving for the Flying Field +- ROS is running and communicating on both the base station and onboard computer +- Set fixed wing parameters +- Wireless network setup is working +- `rosflight_io` reports no errors +- RC communication and override check +- Proper directions on all control surfaces, from both RC and onboard computer +- Failsafe behavior is working +- logging is set up and working (automatic rosbag recording) +- blow into pitot tube and watch airspeed estimate +- move aircraft up and down and watch altitutde estimate (remember NED, so higher altitude = negative z) +- check for GPS fix (go outside) +- wire-wiggle test (look for sensor dropout and brownouts when wiggling all wires) +- walking estimator test (walk around outside with GPS and airspeed and watch estimator) + +### After getting to flying field +- Set up Network +- Check RC communication +- Publish Commands to aircraft, check response +- Check RC switch setup +- Arm/Disarm Test +- GPS fix +- Check automatic logging +- Start external video recording +- Go fly! diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/rc-configuration.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/rc-configuration.md new file mode 100644 index 0000000..efa1ae0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/rc-configuration.md @@ -0,0 +1,33 @@ +# Binding your Transmitter to your Receiver + +We have had the most success using PPM receivers. Parallel PWM recievers are also supported, but they actually require more effort on the part of the flight controller and can occasionally cause I2C errors. + +Follow the instructions in your user manual to bind your transmitter to your RC receiver. You may also be able to find a guide on YouTube with instructions, just search for your particular transmitter and recevier model. + +# RC Calibration + +To avoid confusion and to reduce code complexity in the firmware source, ROSflight does not perform software calibration of RC transmitters. This means that RC calibration must be done on the transmitter itself, as opposed to in software. This is pretty straight-forward in most modern transmitters. To successfully calibrate you have to do the following: + +## Configure the full stick output for each channel + +The easiest way to this is to enter the "Servo Setup" Menu (for Spektrum transmitters) and change the servo travel variable. You can watch the raw RC readings from the flight controller by echoing the rc_raw topic from `rosflight_io` + +``` +rostopic echo /rc_raw +``` + +* center both sticks on your transmiterr +* Apply subtrim until the first four channels all read 1500 exactly (or as close a possible, some RC recievers are worse than others and cannot exactly output 1500) +* Set the channel endpoints so that maximum stick deflections result in readings of 1000 and 2000 us. + +Until we get a video of this for our system, you may want to follow this YouTube guide for channel calibration in betaflight [Calibrating RC endpoints with Taranis X9D](https://www.youtube.com/watch?v=nDsNWZgxmw4&t=186s). + +## Configure stick direction for roll, pitch, and yaw channels. + +You now have to make sure your RC transmitter is sending commands consistent with the north-east-down (NED) frame assumed by ROSflight. + +You may find this graphic helpful. It shows all the basic stick positions, and the associated output from the first four channels when looking at a raw AETR RC signal from `rosflight_io`. Make sure that the stick output is in the right direction. + +![stick_image](images/sticks.png) + +It should be noted, that channel assignment can be modified via the `RC_*_CHN` parameters. So if you are using something other than AETR assignment, the channel index for each stick may be different, but the direction should be the same. diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/ros-setup.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/ros-setup.md new file mode 100644 index 0000000..01402e6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/docs/user-guide/ros-setup.md @@ -0,0 +1,64 @@ +# Installing/setting up ROS + +You will need to install ROS on both the onboard computer and base station laptop. Check out the [Official ROS Installation](http://wiki.ros.org/ROS/Installation) page for details on how to do this. + +Currently only the long-term support [ROS kinetic](http://wiki.ros.org/kinetic/Installation) release is supported, with the recommended operating system being Ubuntu 16.04. If storage is limited on your onboard computer, you can install the bare-bones ROS package (`ros-kinetic-ros-base`) instead of the full desktop version. + +# Installing rosflight + +You will need to install the rosflight packages on both your onboard computer and your base station computer. The onboard computer will run the node that actually communicates with the flight controller over the serial connection, while the base station needs the message and service definitions to be able to subscribe and publish to topics or call services. + +## From the apt repository + +The recommended installation method for Ubuntu or Debian systems is to use the rosflight packages in the official ROS apt repositories. If you have configured your system to use these packages as described in the ROS installation guide, you can install rosflight using +```bash +sudo apt-get install ros-kinetic-rosflight-pkgs +``` + +## From source + +If you prefer, or if you are unable to use the apt packages (e.g. for 64-bit ARM running on an NVIDA TX1/TX2), you can install the rosflight repositories from source instead. You will need a `catkin` workspace set up. If you haven't already done this, you can create a new workspace with something like the following commands: +```bash +source /opt/ros/indigo/setup.bash + +cd +mkdir -p catkin_ws/src +cd catkin_ws/src +catkin_init_workspace +cd .. +catkin_make + +source ~/catkin_ws/devel/setup.bash +``` +In order to ensure that ROS uses this workspace, you can add the last line (`source ~/catkin_ws/devel/setup.bash`) to your `~/.bashrc` file or its equivalent on other systems. Next download the source code into your workspace, +```bash +cd ~/catkin_ws/src +git clone https://github.com/rosflight/rosflight.git +``` +install dependencies, +```bash +rosdep install --ignore-src rosflight +cd ~/catkin_ws/src +rosdep install --ignore-src --from-path rosflight +``` +then build the packages. +```bash +cd ~/catkin_ws +catkin_make +``` + +# Running rosflight_io + +The `rosflight_io` node is the bridge between ROS and the MAVLink communication with the flight controller. This node must be run on the computer that has the physical serial connection to your flight controller. To run this node, use something like the following command (after starting a `roscore`): +```bash +rosrun rosflight rosflight_io _port:=/dev/ttyUSB0 +``` +Replace `/dev/ttyUSB0` with the port your flight controller is connected to. The `rosflight_io` node could also be started from within a launch file with something like +```xml + + + +``` +The optional (but recommended) `output="screen"` option ensures that status messages from `rosflight_io` will be forwarded to the console from which you call `roslaunch`. + +For details on all parameters, topics, and services related to the `rosflight_io` node, refer to the documentation on the [ROS wiki](http://wiki.ros.org/rosflight). diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/fix-code-style.sh b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/fix-code-style.sh new file mode 100644 index 0000000..7bfefdd --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/fix-code-style.sh @@ -0,0 +1,8 @@ +#!/bin/bash + +CMD="astyle --options=.astylerc" + +$CMD include/* +$CMD src/* +$CMD lib/turbotrig/* +$CMD boards/naze/* diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/board.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/board.h new file mode 100644 index 0000000..e3c7e99 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/board.h @@ -0,0 +1,107 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_FIRMWARE_BOARD_H +#define ROSFLIGHT_FIRMWARE_BOARD_H + +#include +#include +#include +#include + +namespace rosflight_firmware +{ + +class Board +{ + +public: +// setup + virtual void init_board(void) = 0; + virtual void board_reset(bool bootloader) = 0; + +// clock + virtual uint32_t clock_millis() = 0; + virtual uint64_t clock_micros() = 0; + virtual void clock_delay(uint32_t milliseconds) = 0; + +// serial + virtual void serial_init(uint32_t baud_rate) = 0; + virtual void serial_write(const uint8_t *src, size_t len) = 0; + virtual uint16_t serial_bytes_available(void) = 0; + virtual uint8_t serial_read(void) = 0; + +// sensors + virtual void sensors_init() = 0; + virtual uint16_t num_sensor_errors(void) = 0; + + virtual bool new_imu_data() = 0; + virtual bool imu_read(float accel[3], float *temperature, float gyro[3], uint64_t* time) = 0; + virtual void imu_not_responding_error(void) = 0; + + virtual bool mag_check(void) = 0; + virtual void mag_read(float mag[3]) = 0; + + virtual bool baro_check(void) = 0; + virtual void baro_read(float *pressure, float *temperature) = 0; + + virtual bool diff_pressure_check(void) = 0; + virtual void diff_pressure_read(float *diff_pressure, float *temperature) = 0; + + virtual bool sonar_check(void) = 0; + virtual float sonar_read(void) = 0; + +// PWM +// TODO make these deal in normalized (-1 to 1 or 0 to 1) values (not pwm-specific) + virtual void pwm_init(bool cppm, uint32_t refresh_rate, uint16_t idle_pwm) = 0; + virtual bool pwm_lost() = 0; + virtual uint16_t pwm_read(uint8_t channel) = 0; + virtual void pwm_write(uint8_t channel, uint16_t value) = 0; + +// non-volatile memory + virtual void memory_init(void) = 0; + virtual bool memory_read(void *dest, size_t len) = 0; + virtual bool memory_write(const void *src, size_t len) = 0; + +// LEDs + virtual void led0_on(void) = 0; + virtual void led0_off(void) = 0; + virtual void led0_toggle(void) = 0; + + virtual void led1_on(void) = 0; + virtual void led1_off(void) = 0; + virtual void led1_toggle(void) = 0; + +}; + +} // namespace rosflight_firmware + +#endif // ROSLFIGHT_FIRMWARE_BOARD_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/command_manager.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/command_manager.h new file mode 100644 index 0000000..e82341e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/command_manager.h @@ -0,0 +1,191 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_FIRMWARE_COMMAND_MANAGER_H +#define ROSFLIGHT_FIRMWARE_COMMAND_MANAGER_H + +#include +#include + +#include "rc.h" + +namespace rosflight_firmware +{ + +class ROSflight; + +typedef enum +{ + RATE, // Channel is is in rate mode (mrad/s) + ANGLE, // Channel command is in angle mode (mrad) + THROTTLE, // Channel is direcly controlling throttle max/1000 + PASSTHROUGH, // Channel directly passes PWM input to the mixer +} control_type_t; + +typedef struct +{ + bool active; // Whether or not the channel is active + control_type_t type; // What type the channel is + float value; // The value of the channel +} control_channel_t; + +typedef struct +{ + uint32_t stamp_ms; + control_channel_t x; + control_channel_t y; + control_channel_t z; + control_channel_t F; +} control_t; + +class CommandManager +{ + +private: + + typedef struct + { + control_channel_t *rc; + control_channel_t *onboard; + control_channel_t *combined; + } mux_t; + + mux_t muxes[4] = + { + {&rc_command_.x, &offboard_command_.x, &combined_command_.x}, + {&rc_command_.y, &offboard_command_.y, &combined_command_.y}, + {&rc_command_.z, &offboard_command_.z, &combined_command_.z}, + {&rc_command_.F, &offboard_command_.F, &combined_command_.F} + }; + + control_t rc_command_ = + { + 0, + {false, ANGLE, 0.0}, + {false, ANGLE, 0.0}, + {false, RATE, 0.0}, + {false, THROTTLE, 0.0} + }; + control_t offboard_command_ = + { + 0, + {false, ANGLE, 0.0}, + {false, ANGLE, 0.0}, + {false, RATE, 0.0}, + {false, THROTTLE, 0.0} + }; + control_t combined_command_ = + { + 0, + {false, ANGLE, 0.0}, + {false, ANGLE, 0.0}, + {false, RATE, 0.0}, + {false, THROTTLE, 0.0} + }; + + control_t multirotor_failsafe_command_ = + { + 0, + {true, ANGLE, 0.0}, + {true, ANGLE, 0.0}, + {true, RATE, 0.0}, + {true, THROTTLE, 0.0} + }; + control_t fixedwing_failsafe_command_ = + { + 0, + {true, PASSTHROUGH, 0.0}, + {true, PASSTHROUGH, 0.0}, + {true, PASSTHROUGH, 0.0}, + {true, THROTTLE, 0.0} + }; + + typedef enum + { + ATT_MODE_RATE, + ATT_MODE_ANGLE + } att_mode_t; + + enum MuxChannel + { + MUX_X, + MUX_Y, + MUX_Z, + MUX_F, + }; + + typedef struct + { + RC::Stick rc_channel; + uint32_t last_override_time; + } rc_stick_override_t; + + rc_stick_override_t rc_stick_override_[3] = + { + { RC::STICK_X, 0 }, + { RC::STICK_Y, 0 }, + { RC::STICK_Z, 0 } + }; + + ROSflight& RF_; + + bool new_command_; + bool rc_override_; + + control_t& failsafe_command_; + + void param_change_callback(uint16_t param_id); + void init_failsafe(); + + bool do_roll_pitch_yaw_muxing(MuxChannel channel); + bool do_throttle_muxing(void); + void do_min_throttle_muxing(); + + void interpret_rc(void); + bool stick_deviated(MuxChannel channel); + +public: + + CommandManager(ROSflight& _rf); + void init(); + bool run(); + bool rc_override_active(); + bool offboard_control_active(); + void set_new_offboard_command(control_t new_offboard_command); + void set_new_rc_command(control_t new_rc_command); + void override_combined_command_with_rc(); + inline const control_t& combined_control() const { return combined_command_; } + inline const control_t& rc_control() const { return rc_command_; } +}; + +} // namespace rosflight_firmware + +#endif // ROSFLIGHT_FIRMWARE_COMMAND_MANAGER_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/controller.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/controller.h new file mode 100644 index 0000000..da06ac3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/controller.h @@ -0,0 +1,109 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_FIRMWARE_CONTROLLER_H +#define ROSFLIGHT_FIRMWARE_CONTROLLER_H + +#include +#include + +#include + +#include "command_manager.h" +#include "estimator.h" + +namespace rosflight_firmware +{ + +class ROSflight; + +class Controller +{ +public: + struct Output + { + float F; + float x; + float y; + float z; + }; + + Controller(ROSflight& rf); + + inline const Output& output() const { return output_; } + + void init(); + void run(); + + void calculate_equilbrium_torque_from_rc(); + void param_change_callback(uint16_t param_id); + +private: + class PID + { + public: + PID(); + void init(float kp, float ki, float kd, float max, float min, float tau); + float run(float dt, float x, float x_c, bool update_integrator); + float run(float dt, float x, float x_c, bool update_integrator, float xdot); + + private: + float kp_; + float ki_; + float kd_; + + float max_; + float min_; + + float integrator_; + float differentiator_; + float prev_x_; + float tau_; + }; + + ROSflight& RF_; + + vector_t run_pid_loops(uint32_t dt, const Estimator::State& state, const control_t& command, bool update_integrators); + + Output output_; + + PID roll_; + PID roll_rate_; + PID pitch_; + PID pitch_rate_; + PID yaw_rate_; + + uint64_t prev_time_us_; +}; + +} // namespace rosflight_firmware + +#endif // ROSFLIGHT_FIRMWARE_CONTROLLER_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/estimator.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/estimator.h new file mode 100644 index 0000000..db829a8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/estimator.h @@ -0,0 +1,94 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_FIRMWARE_ESTIMATOR_H +#define ROSFLIGHT_FIRMWARE_ESTIMATOR_H + +#include +#include +#include + +#include +#include + +namespace rosflight_firmware +{ + +class ROSflight; + +class Estimator +{ + +public: + struct State + { + vector_t angular_velocity; + quaternion_t attitude; + float roll; + float pitch; + float yaw; + uint64_t timestamp_us; + }; + + Estimator(ROSflight& _rf); + + inline const State& state() const { return state_; } + + void init(); + void run(); + void reset_state(); + void reset_adaptive_bias(); + +private: + const vector_t g_ = {0.0f, 0.0f, -1.0f}; + + ROSflight& RF_; + State state_; + + uint64_t last_time_; + uint64_t last_acc_update_us_; + + vector_t w1_; + vector_t w2_; + + vector_t bias_; + + vector_t accel_LPF_; + vector_t gyro_LPF_; + + vector_t w_acc_; + + void run_LPF(); +}; + +} // namespace rosflight_firmware + +#endif // ROSFLIGHT_FIRMWARE_ESTIMATOR_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/mavlink.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/mavlink.h new file mode 100644 index 0000000..6ca95f0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/mavlink.h @@ -0,0 +1,153 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_FIRMWARE_MAVLINK_H +#define ROSFLIGHT_FIRMWARE_MAVLINK_H + +#include +#include "nanoprintf.h" + +namespace rosflight_firmware { + +class ROSflight; + +class Mavlink +{ +private: + enum + { + STREAM_ID_HEARTBEAT, + STREAM_ID_STATUS, + + STREAM_ID_ATTITUDE, + + STREAM_ID_IMU, + STREAM_ID_DIFF_PRESSURE, + STREAM_ID_BARO, + STREAM_ID_SONAR, + STREAM_ID_MAG, + + STREAM_ID_SERVO_OUTPUT_RAW, + STREAM_ID_RC_RAW, + STREAM_ID_LOW_PRIORITY, + STREAM_COUNT + }; + + uint32_t sysid_; + uint32_t compid_; + uint64_t offboard_control_time_; + ROSflight& RF_; + uint8_t send_params_index_; + mavlink_message_t in_buf_; + mavlink_status_t status_; + bool initialized_; + + typedef void (Mavlink::*MavlinkStreamFcn)(void); + + typedef struct + { + uint32_t period_us; + uint64_t next_time_us; + MavlinkStreamFcn send_function; + } mavlink_stream_t; + + void handle_msg_param_request_list(void); + void handle_msg_param_request_read(const mavlink_message_t *const msg); + void handle_msg_param_set(const mavlink_message_t *const msg); + void send_next_param(void); + + void handle_mavlink_message(void); + + void handle_msg_rosflight_cmd(const mavlink_message_t *const msg); + void handle_msg_timesync(const mavlink_message_t *const msg); + void handle_msg_offboard_control(const mavlink_message_t *const msg); + + void send_heartbeat(void); + void send_status(void); + void send_attitude(void); + void send_imu(void); + void send_output_raw(void); + void send_rc_raw(void); + void send_diff_pressure(void); + void send_baro(void); + void send_sonar(void); + void send_mag(void); + void send_low_priority(void); + void send_message(const mavlink_message_t &msg); + void send_log_message(uint8_t severity, const char *text); + void stream_set_period(uint8_t stream_id, uint32_t period_us); + + // Debugging Utils + void send_named_value_int(const char *const name, int32_t value); + // void send_named_command_struct(const char *const name, control_t command_struct); + + mavlink_stream_t mavlink_streams_[STREAM_COUNT] = { + // period_us last_time_us send_function + { 1000000, 0, &rosflight_firmware::Mavlink::send_heartbeat }, + { 1000000, 0, &rosflight_firmware::Mavlink::send_status}, + { 200000, 0, &rosflight_firmware::Mavlink::send_attitude }, + { 1000, 0, &rosflight_firmware::Mavlink::send_imu }, + { 200000, 0, &rosflight_firmware::Mavlink::send_diff_pressure }, + { 200000, 0, &rosflight_firmware::Mavlink::send_baro }, + { 100000, 0, &rosflight_firmware::Mavlink::send_sonar }, + { 6250, 0, &rosflight_firmware::Mavlink::send_mag }, + { 0, 0, &rosflight_firmware::Mavlink::send_output_raw }, + { 0, 0, &rosflight_firmware::Mavlink::send_rc_raw }, + { 5000, 0, &rosflight_firmware::Mavlink::send_low_priority } + }; + + +public: + + enum + { + LOG_INFO = 6, + LOG_WARNING = 4, + LOG_ERROR = 3, + LOG_CRITICAL = 2 + }; + + Mavlink(ROSflight &_rf); + + void init(); + void receive(void); + void stream(); + void update_param(uint16_t param_id); + void set_streaming_rate(uint8_t stream_id, int16_t param_id); + void update_status(); + void log(uint8_t severity, const char *fmt, ...); + + void send_named_value_float(const char *const name, float value); +}; + +} // namespace rosflight_firmware + +#endif // ROSFLIGHT_FIRMWARE_MAVLINK_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/mixer.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/mixer.h new file mode 100644 index 0000000..93a4838 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/mixer.h @@ -0,0 +1,231 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + + +#ifndef ROSFLIGHT_FIRMWARE_MIXER_H +#define ROSFLIGHT_FIRMWARE_MIXER_H + +#include +#include + +namespace rosflight_firmware +{ + +class ROSflight; + +class Mixer +{ + +public: + + enum + { + ESC_CALIBRATION = 0, + QUADCOPTER_PLUS = 1, + QUADCOPTER_X = 2, + HEX_PLUS = 3, + HEX_X = 4, + OCTO_PLUS = 5, + OCTO_X = 6, + Y6 = 7, + X8 = 8, + TRICOPTER = 9, + FIXEDWING = 10, + NUM_MIXERS, + INVALID_MIXER = 255 + }; + + typedef enum + { + NONE, // None + S, // Servo + M, // Motor + G // GPIO + } output_type_t; + + typedef struct + { + output_type_t output_type[8]; + float F[8]; + float x[8]; + float y[8]; + float z[8]; + } mixer_t; + +private: + ROSflight& RF_; + + float raw_outputs_[8]; + float unsaturated_outputs_[8]; + + void write_motor(uint8_t index, float value); + void write_servo(uint8_t index, float value); + + const mixer_t esc_calibration_mixing = + { + {M, M, M, M, M, M, NONE, NONE}, + { 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 1.0f}, // F Mix + { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, // X Mix + { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, // X Mix + { 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, // X Mix + }; + + const mixer_t quadcopter_plus_mixing = + { + {M, M, M, M, NONE, NONE, NONE, NONE}, // output_type + + { 1.0f, 1.0f, 1.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f}, // F Mix + { 0.0f, -1.0f, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f}, // X Mix + { 1.0f, 0.0f, -1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, // Y Mix + { 1.0f, -1.0f, 1.0f, -1.0f, 0.0f, 0.0f, 0.0f, 0.0f} // Z Mix + }; + + const mixer_t quadcopter_x_mixing = + { + {M, M, M, M, NONE, NONE, NONE, NONE}, // output_type + + { 1.0f, 1.0f, 1.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f}, // F Mix + {-1.0f, -1.0f, 1.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f}, // X Mix + { 1.0f, -1.0f,-1.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f}, // Y Mix + { 1.0f, -1.0f, 1.0f,-1.0f, 0.0f, 0.0f, 0.0f, 0.0f} // Z Mix + }; + + const mixer_t hex_plus_mixing = + { + {M, M, M, M, M, M, M, M}, // output_type + + { 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 0.0f, 0.0f}, // F Mix + { 0.0f, -0.866025f, -0.866025f, 0.0f, 0.866025f, 0.866025f, 0.0f, 0.0f}, // X Mix + { 1.0f, 0.5f, -0.5f, -1.0f, -0.5f, 0.5f, 0.0f, 0.0f}, // Y Mix + { 1.0f, -1.0f, 1.0f, -1.0f, 1.0f, -1.0f, 0.0f, 0.0f} // Z Mix + }; + + const mixer_t hex_x_mixing = + { + {M, M, M, M, M, M, M, M}, // output_type + + { 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 0.0f, 0.0f}, // F Mix + { -0.5f, -1.0f, -0.5f, 0.5f, 1.0f, 0.5f, 0.0f, 0.0f}, // X Mix + { 0.866025f, 0.0f, -0.866025f, -0.866025f, 0.0f, 0.866025f, 0.0f, 0.0f}, // Y Mix + { 1.0f, -1.0f, 1.0f, -1.0f, 1.0f, -1.0f, 0.0f, 0.0f} // Z Mix + }; + + const mixer_t octocopter_plus_mixing = + { + {M, M, M, M, M, M, M, M}, // output_type + + { 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 1.0f}, // F Mix + { 0.0f, -0.707f, -1.0f, -0.707f, 0.0f, 0.707f, 1.0f, 0.707f}, // X Mix + { 1.0f, 0.707f, 0.0f, -0.707f, -1.0f, -0.707f, 0.0f, 0.707f}, // Y Mix + { 1.0f, -1.0f, 1.0f, -1.0f, 1.0f, -1.0f, 1.0f, -1.0f} // Z Mix + }; + + const mixer_t octocopter_x_mixing = + { + {M, M, M, M, M, M, M, M}, // output_type + + { 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 1.0f}, // F Mix + {-0.414f, -1.0f, -1.0f, -0.414f, 0.414f, 1.0f, 1.0f, 0.414}, // X Mix + { 1.0f, 0.414f, -0.414f, -1.0f, -1.0f, -0.414f, 0.414f, 1.0}, // Y Mix + { 1.0f, -1.0f, 1.0f, -1.0f, 1.0f, -1.0f, 1.0f, -1.0f} // Z Mix + }; + + const mixer_t Y6_mixing = + { + {M, M, M, M, M, M, NONE, NONE}, // output_type + + { 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 0.0f, 0.0f}, // F Mix + {-1.0f, -1.0f, 0.0f, 0.0f, 1.0f, 1.0f, 0.0f, 0.0f}, // X Mix + { 0.667f, 0.667f, -1.333f, -1.333f, 0.667f, 0.667f, 0.0f, 0.0f}, // Y Mix + { 1.0f, -1.0f, 1.0f, -1.0f, 1.0f, -1.0f, 0.0f, 0.0f} // Z Mix + }; + + const mixer_t X8_mixing = + { + {M, M, M, M, M, M, M, M}, // output_type + + { 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 1.0f, 1.0f}, // F Mix + {-1.0f, -1.0f, -1.0f, -1.0f, 1.0f, 1.0f, 1.0f, 1.0f}, // X Mix + { 1.0f, 1.0f, -1.0f, -1.0f, -1.0f, -1.0f, 1.0f, 1.0f}, // Y Mix + { 1.0f, -1.0f, 1.0f, -1.0f, 1.0f, -1.0f, 1.0f, -1.0f} // Z Mix + }; + + const mixer_t tricopter_mixing = + { + {M, M, M, S, NONE, NONE, NONE, NONE}, // output_type + + { 1.0f, 0.0f, 1.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f}, // F Mix + {-1.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f}, // X Mix + { 0.667f, 0.0f, 0.667f, -1.333f, 0.0f, 0.0f, 0.0f, 0.0f}, // Y Mix + { 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f} // Z Mix + }; + + const mixer_t fixedwing_mixing = + { + {S, S, M, S, S, M, NONE, NONE}, + + { 0.0f, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, // F Mix + { 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, // X Mix + { 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}, // Y Mix + { 0.0f, 0.0f, 0.0f, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f} // Z Mix + }; + + + const mixer_t *mixer_to_use_; + + const mixer_t *array_of_mixers_[NUM_MIXERS] = + { + &esc_calibration_mixing, + &quadcopter_plus_mixing, + &quadcopter_x_mixing, + &hex_plus_mixing, + &hex_x_mixing, + &octocopter_plus_mixing, + &octocopter_x_mixing, + &Y6_mixing, + &X8_mixing, + &tricopter_mixing, + &fixedwing_mixing, + }; + +public: + Mixer(ROSflight& _rf); + void init(); + void init_PWM(); + void init_mixing(); + void mix_output(); + void param_change_callback(uint16_t param_id); + inline const float* get_outputs() const {return raw_outputs_;} +}; + +} // namespace rosflight_firmware + +#endif // ROSFLIGHT_FIRMWARE_MIXER_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/nanoprintf.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/nanoprintf.h new file mode 100644 index 0000000..49ce339 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/nanoprintf.h @@ -0,0 +1,128 @@ +/* +File: printf.h + +Copyright (c) 2004,2012 Kustaa Nyholm / SpareTimeLabs + +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list +of conditions and the following disclaimer. + +Redistributions in binary form must reproduce the above copyright notice, this +list of conditions and the following disclaimer in the documentation and/or other +materials provided with the distribution. + +Neither the name of the Kustaa Nyholm or SpareTimeLabs nor the names of its +contributors may be used to endorse or promote products derived from this software +without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. +IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, +INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT +NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, +OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY +OF SUCH DAMAGE. + +---------------------------------------------------------------------- + +This library is realy just two files: 'printf.h' and 'printf.c'. + +They provide a simple and small (+200 loc) printf functionality to +be used in embedded systems. + +I've found them so usefull in debugging that I do not bother with a +debugger at all. + +They are distributed in source form, so to use them, just compile them +into your project. + +Two printf variants are provided: printf and sprintf. + +The formats supported by this implementation are: 'd' 'u' 'c' 's' 'x' 'X'. + +Zero padding and field width are also supported. + +If the library is compiled with 'PRINTF_SUPPORT_LONG' defined then the +long specifier is also +supported. Note that this will pull in some long math routines (pun intended!) +and thus make your executable noticably longer. + +The memory foot print of course depends on the target cpu, compiler and +compiler options, but a rough guestimate (based on a H8S target) is about +1.4 kB for code and some twenty 'int's and 'char's, say 60 bytes of stack space. +Not too bad. Your milage may vary. By hacking the source code you can +get rid of some hunred bytes, I'm sure, but personally I feel the balance of +functionality and flexibility versus code size is close to optimal for +many embedded systems. + +To use the printf you need to supply your own character output function, +something like : + +void putc ( void* p, char c) + { + while (!SERIAL_PORT_EMPTY) ; + SERIAL_PORT_TX_REGISTER = c; + } + +Before you can call printf you need to initialize it to use your +character output function with something like: + +init_printf(NULL,putc); + +Notice the 'NULL' in 'init_printf' and the parameter 'void* p' in 'putc', +the NULL (or any pointer) you pass into the 'init_printf' will eventually be +passed to your 'putc' routine. This allows you to pass some storage space (or +anything realy) to the character output function, if necessary. +This is not often needed but it was implemented like that because it made +implementing the sprintf function so neat (look at the source code). + +The code is re-entrant, except for the 'init_printf' function, so it +is safe to call it from interupts too, although this may result in mixed output. +If you rely on re-entrancy, take care that your 'putc' function is re-entrant! + +The printf and sprintf functions are actually macros that translate to +'tfp_printf' and 'tfp_sprintf'. This makes it possible +to use them along with 'stdio.h' printf's in a single source file. +You just need to undef the names before you include the 'stdio.h'. +Note that these are not function like macros, so if you have variables +or struct members with these names, things will explode in your face. +Without variadic macros this is the best we can do to wrap these +fucnction. If it is a problem just give up the macros and use the +functions directly or rename them. + +For further details see source code. + +regs Kusti, 23.10.2004 +*/ + +#ifndef ROSFLIGHT_FIRWMARE_NANO_PRINTF_H +#define ROSFLIGHT_FIRWMARE_NANO_PRINTF_H + +#include + +namespace rosflight_firmware +{ +namespace nanoprintf +{ + +void init_printf(void *putp,void (*putf)(void *,char)); + +void tfp_printf(const char *fmt, ...); +void tfp_sprintf(char *s, const char *fmt, va_list va); + +void tfp_format(void *putp, void (*putf)(void *,char), const char *fmt, va_list va); + +} // namespace nanoprintf +} // namespace rosflight_firmware + +#define nano_printf rosflight_firmware::nanoprintf::tfp_printf +#define nano_sprintf rosflight_firmware::nanoprintf::tfp_sprintf + +#endif // ROSFLIGHT_FIRWMARE_NANO_PRINTF_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/param.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/param.h new file mode 100644 index 0000000..ef9e6e8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/param.h @@ -0,0 +1,359 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_FIRMWARE_PARAM_H +#define ROSFLIGHT_FIRMWARE_PARAM_H + +#include +#include +#include + +#ifndef GIT_VERSION_HASH +#define GIT_VERSION_HASH 0x00 +//#pragma message "GIT_VERSION_HASH Undefined, setting to 0x00!" +#endif + +#ifndef GIT_VERSION_STRING +#define GIT_VERSION_STRING "empty" +#endif + +namespace rosflight_firmware +{ + +enum : uint16_t +{ + /******************************/ + /*** HARDWARE CONFIGURATION ***/ + /******************************/ + PARAM_BAUD_RATE = 0, + + /*****************************/ + /*** MAVLINK CONFIGURATION ***/ + /*****************************/ + PARAM_SYSTEM_ID, + PARAM_STREAM_HEARTBEAT_RATE, + PARAM_STREAM_STATUS_RATE, + + PARAM_STREAM_ATTITUDE_RATE, + PARAM_STREAM_IMU_RATE, + PARAM_STREAM_MAG_RATE, + PARAM_STREAM_BARO_RATE, + PARAM_STREAM_AIRSPEED_RATE, + PARAM_STREAM_SONAR_RATE, + + PARAM_STREAM_OUTPUT_RAW_RATE, + PARAM_STREAM_RC_RAW_RATE, + + /********************************/ + /*** CONTROLLER CONFIGURATION ***/ + /********************************/ + PARAM_MAX_COMMAND, + + PARAM_PID_ROLL_RATE_P, + PARAM_PID_ROLL_RATE_I, + PARAM_PID_ROLL_RATE_D, + + PARAM_PID_PITCH_RATE_P, + PARAM_PID_PITCH_RATE_I, + PARAM_PID_PITCH_RATE_D, + + PARAM_PID_YAW_RATE_P, + PARAM_PID_YAW_RATE_I, + PARAM_PID_YAW_RATE_D, + + PARAM_PID_ROLL_ANGLE_P, + PARAM_PID_ROLL_ANGLE_I, + PARAM_PID_ROLL_ANGLE_D, + + PARAM_PID_PITCH_ANGLE_P, + PARAM_PID_PITCH_ANGLE_I, + PARAM_PID_PITCH_ANGLE_D, + + PARAM_X_EQ_TORQUE, + PARAM_Y_EQ_TORQUE, + PARAM_Z_EQ_TORQUE, + + PARAM_PID_TAU, + + /*************************/ + /*** PWM CONFIGURATION ***/ + /*************************/ + PARAM_MOTOR_PWM_SEND_RATE, + PARAM_MOTOR_IDLE_THROTTLE, + PARAM_FAILSAFE_THROTTLE, + PARAM_MOTOR_MAX_PWM, + PARAM_MOTOR_MIN_PWM, + PARAM_SPIN_MOTORS_WHEN_ARMED, + + /*******************************/ + /*** ESTIMATOR CONFIGURATION ***/ + /*******************************/ + PARAM_INIT_TIME, + PARAM_FILTER_KP, + PARAM_FILTER_KI, + + PARAM_FILTER_USE_QUAD_INT, + PARAM_FILTER_USE_MAT_EXP, + PARAM_FILTER_USE_ACC, + + PARAM_CALIBRATE_GYRO_ON_ARM, + + PARAM_GYRO_ALPHA, + PARAM_ACC_ALPHA, + + PARAM_GYRO_X_BIAS, + PARAM_GYRO_Y_BIAS, + PARAM_GYRO_Z_BIAS, + PARAM_ACC_X_BIAS, + PARAM_ACC_Y_BIAS, + PARAM_ACC_Z_BIAS, + PARAM_ACC_X_TEMP_COMP, + PARAM_ACC_Y_TEMP_COMP, + PARAM_ACC_Z_TEMP_COMP, + + PARAM_MAG_A11_COMP, + PARAM_MAG_A12_COMP, + PARAM_MAG_A13_COMP, + PARAM_MAG_A21_COMP, + PARAM_MAG_A22_COMP, + PARAM_MAG_A23_COMP, + PARAM_MAG_A31_COMP, + PARAM_MAG_A32_COMP, + PARAM_MAG_A33_COMP, + PARAM_MAG_X_BIAS, + PARAM_MAG_Y_BIAS, + PARAM_MAG_Z_BIAS, + + PARAM_BARO_BIAS, + PARAM_GROUND_LEVEL, + + PARAM_DIFF_PRESS_BIAS, + + /************************/ + /*** RC CONFIGURATION ***/ + /************************/ + PARAM_RC_TYPE, + PARAM_RC_X_CHANNEL, + PARAM_RC_Y_CHANNEL, + PARAM_RC_Z_CHANNEL, + PARAM_RC_F_CHANNEL, + PARAM_RC_ATTITUDE_OVERRIDE_CHANNEL, + PARAM_RC_THROTTLE_OVERRIDE_CHANNEL, + PARAM_RC_ATT_CONTROL_TYPE_CHANNEL, + PARAM_RC_ARM_CHANNEL, + PARAM_RC_NUM_CHANNELS, + + PARAM_RC_SWITCH_5_DIRECTION, + PARAM_RC_SWITCH_6_DIRECTION, + PARAM_RC_SWITCH_7_DIRECTION, + PARAM_RC_SWITCH_8_DIRECTION, + + PARAM_RC_OVERRIDE_DEVIATION, + PARAM_OVERRIDE_LAG_TIME, + PARAM_RC_OVERRIDE_TAKE_MIN_THROTTLE, + + PARAM_RC_ATTITUDE_MODE, + PARAM_RC_MAX_ROLL, + PARAM_RC_MAX_PITCH, + PARAM_RC_MAX_ROLLRATE, + PARAM_RC_MAX_PITCHRATE, + PARAM_RC_MAX_YAWRATE, + + /***************************/ + /*** FRAME CONFIGURATION ***/ + /***************************/ + PARAM_MIXER, + + PARAM_FIXED_WING, + PARAM_ELEVATOR_REVERSE, + PARAM_AILERON_REVERSE, + PARAM_RUDDER_REVERSE, + + /********************/ + /*** ARMING SETUP ***/ + /********************/ + PARAM_ARM_THRESHOLD, + + // keep track of size of params array + PARAMS_COUNT +}; + +typedef enum +{ + PARAM_TYPE_INT32, + PARAM_TYPE_FLOAT, + PARAM_TYPE_INVALID +} param_type_t; + +class ROSflight; +class Params +{ + +public: + static constexpr uint8_t PARAMS_NAME_LENGTH = 16; + +private: + typedef struct + { + uint32_t version; + uint16_t size; + uint8_t magic_be; // magic number, should be 0xBE + + int32_t values[PARAMS_COUNT]; + char names[PARAMS_COUNT][PARAMS_NAME_LENGTH]; + param_type_t types[PARAMS_COUNT]; + + uint8_t magic_ef; // magic number, should be 0xEF + uint8_t chk; // XOR checksum + } params_t; + + std::function callbacks[PARAMS_COUNT]; // Param change callbacks + + params_t params; + ROSflight& RF_; + + void init_param_int(uint16_t id, const char name[PARAMS_NAME_LENGTH], int32_t value); + void init_param_float(uint16_t id, const char name[PARAMS_NAME_LENGTH], float value); + uint8_t compute_checksum(void); + + +public: + Params(ROSflight& _rf); + + void add_callback(std::function callback, uint16_t param_id); + + + + // function declarations + + /** + * @brief Initialize parameter values + */ + void init(); + + /** + * @brief Set all parameters to default values + */ + void set_defaults(void); + + /** + * @brief Read parameter values from non-volatile memory + * @return True if successful, false otherwise + */ + bool read(void); + + /** + * @brief Write current parameter values to non-volatile memory + * @return True if successful, false otherwise + */ + bool write(void); + + /** + * @brief Callback for executing actions that need to be taken when a parameter value changes + * @param id The ID of the parameter that was changed + */ + void change_callback(uint16_t id); + + /** + * @brief Gets the id of a parameter from its name + * @param name The name of the parameter + * @return The ID of the parameter if the name is valid, PARAMS_COUNT otherwise (invalid ID) + */ + uint16_t lookup_param_id(const char name[PARAMS_NAME_LENGTH]); + + /** + * @brief Get the value of an integer parameter by id + * @param id The ID of the parameter + * @return The value of the parameter + */ + inline const int get_param_int(uint16_t id) const { return params.values[id]; } + + /** + * @brief Get the value of a floating point parameter by id + * @param id The ID of the parameter + * @return The value of the parameter + */ + inline const float get_param_float(uint16_t id) const { return *(float *) ¶ms.values[id]; } + + /** + * @brief Get the name of a parameter + * @param id The ID of the parameter + * @return The name of the parameter + */ + inline const char *get_param_name(uint16_t id) const { return params.names[id]; } + + /** + * @brief Get the type of a parameter + * @param id The ID of the parameter + * @return The type of the parameter + * This returns one of three possible types + * PARAM_TYPE_INT32, PARAM_TYPE_FLOAT, or PARAM_TYPE_INVALID + * See line 165 + */ + inline const param_type_t get_param_type(uint16_t id) const { return params.types[id]; } + + /** + * @brief Sets the value of a parameter by ID and calls the parameter change callback + * @param id The ID of the parameter + * @param value The new value + * @return True if a parameter value was changed, false otherwise + */ + bool set_param_int(uint16_t id, int32_t value); + + /** + * @brief Sets the value of a floating point parameter by ID and calls the parameter callback + * @param id The ID of the parameter + * @param value The new value + * @return True if a parameter was changed, false otherwise + */ + bool set_param_float(uint16_t id, float value); + + /** + * @brief Sets the value of a parameter by name and calls the parameter change callback + * @param name The name of the parameter + * @param value The new value + * @return True if a parameter value was changed, false otherwise + */ + bool set_param_by_name_int(const char name[PARAMS_NAME_LENGTH], int32_t value); + + /** + * @brief Sets the value of a floating point parameter by name and calls the parameter change callback + * @param name The name of the parameter + * @param value The new value + * @return True if a parameter value was changed, false otherwise + */ + bool set_param_by_name_float(const char name[PARAMS_NAME_LENGTH], float value); + +}; + +} // namespace rosflight_firmware + +#endif // ROSFLIGHT_FIRMWARE_PARAM_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/rc.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/rc.h new file mode 100644 index 0000000..e49a3c1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/rc.h @@ -0,0 +1,119 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_FIRMWARE_RC_H +#define ROSFLIGHT_FIRMWARE_RC_H + +#include +#include + +namespace rosflight_firmware +{ + +class ROSflight; + +class RC +{ + +public: + enum Stick + { + STICK_X, + STICK_Y, + STICK_Z, + STICK_F, + STICKS_COUNT + }; + + enum Switch + { + SWITCH_ARM, + SWITCH_ATT_OVERRIDE, + SWITCH_THROTTLE_OVERRIDE, + SWITCH_ATT_TYPE, + SWITCHES_COUNT + }; + + RC(ROSflight& _rf); + + typedef enum + { + PARALLEL_PWM, + CPPM, + } rc_type_t; + + void init(); + float stick(Stick channel); + bool switch_on(Switch channel); + bool switch_mapped(Switch channel); + bool run(); + bool new_command(); + void param_change_callback(uint16_t param_id); + +private: + ROSflight& RF_; + + typedef struct + { + uint8_t channel; + int8_t direction; + bool mapped; + } rc_switch_config_t; + + typedef struct + { + uint8_t channel; + bool one_sided; + } rc_stick_config_t; + + bool new_command_; + + uint32_t time_of_last_stick_deviation = 0; + uint32_t time_sticks_have_been_in_arming_position_ms = 0; + uint32_t prev_time_ms = 0; + uint32_t last_rc_receive_time = 0; + + rc_stick_config_t sticks[STICKS_COUNT]; + rc_switch_config_t switches[SWITCHES_COUNT]; + + bool switch_values[SWITCHES_COUNT]; + float stick_values[STICKS_COUNT]; + + void init_rc(); + void init_switches(); + void init_sticks(); + bool check_rc_lost(); + void look_for_arm_disarm_signal(); +}; + +} // namespace rosflight_firmware + +#endif // ROSLFLIGHT_FIRMWARE_RC_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/rosflight.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/rosflight.h new file mode 100644 index 0000000..e5971ce --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/rosflight.h @@ -0,0 +1,87 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_FIRMWARE_ROSFLIGHT_H +#define ROSFLIGHT_FIRMWARE_ROSFLIGHT_H + +#include "board.h" +#include "param.h" +#include "sensors.h" +#include "estimator.h" +#include "rc.h" +#include "controller.h" +#include "mavlink.h" +#include "mixer.h" +#include "state_manager.h" +#include "command_manager.h" + +namespace rosflight_firmware +{ + +class ROSflight +{ + +private: + + +public: + ROSflight(Board& board); + + Board& board_; + Mavlink mavlink_; + + Params params_; + StateManager state_manager_; + Sensors sensors_; + Estimator estimator_; + CommandManager command_manager_; + Mixer mixer_; + Controller controller_; + RC rc_; + + uint32_t loop_time_us; + + /** + * @brief Main initialization routine for the ROSflight autopilot flight stack + */ + void init(); + + /** + * @brief Main loop for the ROSflight autopilot flight stack + */ + void run(); + + uint32_t get_loop_time_us(); +}; + +} // namespace rosflight_firmware + +#endif // ROSFLIGHT_FIRMWARE_ROSFLIGHT_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/sensors.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/sensors.h new file mode 100644 index 0000000..fe5d48c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/sensors.h @@ -0,0 +1,196 @@ +/* + * Copyright (c) 2017, James Jackson, Daniel Koch, and Craig Bidstrup, + * BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_FIRMWARE_SENSORS_H +#define ROSFLIGHT_FIRMWARE_SENSORS_H + +#include +#include +#include + +namespace rosflight_firmware +{ + +class ROSflight; + +class Sensors +{ +public: + struct Data + { + vector_t accel = {0, 0, 0}; + vector_t gyro = {0, 0, 0}; + float imu_temperature = 0; + uint64_t imu_time = 0; + + float diff_pressure_velocity = 0; + float diff_pressure = 0; + float diff_pressure_temp = 0; + bool diff_pressure_valid = false; + + float baro_altitude = 0; + float baro_pressure = 0; + float baro_temperature = 0; + bool baro_valid = false; + + float sonar_range = 0; + bool sonar_range_valid = false; + + vector_t mag = {0, 0, 0}; + + bool baro_present = false; + bool mag_present = false; + bool sonar_present = false; + bool diff_pressure_present = false; + }; + + Sensors(ROSflight& rosflight); + + inline const Data& data() const { return data_; } + + // function declarations + void init(); + bool run(); + + // Calibration Functions + bool start_imu_calibration(void); + bool start_gyro_calibration(void); + bool start_baro_calibration(void); + bool start_diff_pressure_calibration(void); + bool gyro_calibration_complete(void); + + inline bool should_send_imu_data(void) + { + if (imu_data_sent_) + return false; + else + imu_data_sent_ = true; + return true; + } + +private: + static const float BARO_MAX_CHANGE_RATE; + static const float BARO_SAMPLE_RATE; + static const float DIFF_MAX_CHANGE_RATE; + static const float DIFF_SAMPLE_RATE; + static const float SONAR_MAX_CHANGE_RATE; + static const float SONAR_SAMPLE_RATE; + static const int SENSOR_CAL_DELAY_CYCLES; + static const int SENSOR_CAL_CYCLES; + static const float BARO_MAX_CALIBRATION_VARIANCE; + static const float DIFF_PRESSURE_MAX_CALIBRATION_VARIANCE; + + class OutlierFilter + { + private: + float max_change_; + float center_; + int window_size_; + bool init_ = false; + + public: + OutlierFilter() {}; + void init(float max_change_rate, float update_rate, float center); + bool update(float new_val, float *val); + }; + + enum LowPrioritySensors + { + BAROMETER, + DIFF_PRESSURE, + SONAR, + MAGNETOMETER, + NUM_LOW_PRIORITY_SENSORS + }; + + ROSflight& rf_; + + Data data_; + + float accel_[3] = {0, 0, 0}; + float gyro_[3] = {0, 0, 0}; + + bool calibrating_acc_flag_ = false; + bool calibrating_gyro_flag_ = false; + LowPrioritySensors next_sensor_to_update_ = BAROMETER; + void calibrate_accel(void); + void calibrate_gyro(void); + void calibrate_baro(void); + void calibrate_diff_pressure(void); + void correct_imu(void); + void correct_mag(void); + void correct_baro(void); + void correct_diff_pressure(void); + bool update_imu(void); + void update_other_sensors(void); + void look_for_disabled_sensors(void); + uint32_t last_time_look_for_disarmed_sensors_ = 0; + uint32_t last_imu_update_ms_ = 0; + + bool new_imu_data_; + bool imu_data_sent_; + + // IMU calibration + uint16_t gyro_calibration_count_ = 0; + vector_t gyro_sum_ = {0, 0, 0}; + uint16_t accel_calibration_count_ = 0; + vector_t acc_sum_ = {0, 0, 0}; + const vector_t gravity_ = {0.0f, 0.0f, 9.80665f}; + float acc_temp_sum_ = 0.0f; + vector_t max_ = {-1000.0f, -1000.0f, -1000.0f}; + vector_t min_ = {1000.0f, 1000.0f, 1000.0f}; + + // Baro Calibration + bool baro_calibrated_ = false; + float ground_pressure_ = 0.0f; + uint16_t baro_calibration_count_ = 0; + uint32_t last_baro_cal_iter_ms_ = 0; + float baro_calibration_mean_ = 0.0f; + float baro_calibration_var_ = 0.0f; + + // Diff Pressure Calibration + bool diff_pressure_calibrated_ = false; + uint16_t diff_pressure_calibration_count_ = 0; + uint32_t last_diff_pressure_cal_iter_ms_ = 0; + float diff_pressure_calibration_mean_ = 0.0f; + float diff_pressure_calibration_var_ = 0.0f; + + // Sensor Measurement Outlier Filters + OutlierFilter baro_outlier_filt_; + OutlierFilter diff_outlier_filt_; + OutlierFilter sonar_outlier_filt_; + +}; + +} // namespace rosflight_firmware + +#endif // ROSFLIGHT_FIRMWARE_SENSORS_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/state_manager.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/state_manager.h new file mode 100644 index 0000000..63f46f0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/include/state_manager.h @@ -0,0 +1,112 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_FIRMWARE_STATE_MANAGER_H +#define ROSFLIGHT_FIRMWARE_STATE_MANAGER_H + +#include + +namespace rosflight_firmware +{ + +class ROSflight; + +class StateManager +{ + +public: + struct State + { + bool armed; + bool failsafe; + bool error; + uint16_t error_codes; + }; + + enum Event + { + EVENT_INITIALIZED, + EVENT_REQUEST_ARM, + EVENT_REQUEST_DISARM, + EVENT_RC_LOST, + EVENT_RC_FOUND, + EVENT_ERROR, + EVENT_NO_ERROR, + EVENT_CALIBRATION_COMPLETE, + EVENT_CALIBRATION_FAILED, + }; + + enum + { + ERROR_NONE = 0x0000, + ERROR_INVALID_MIXER = 0x0001, + ERROR_IMU_NOT_RESPONDING = 0x0002, + ERROR_RC_LOST = 0x0004, + ERROR_UNHEALTHY_ESTIMATOR = 0x0008, + ERROR_TIME_GOING_BACKWARDS = 0x0010, + ERROR_UNCALIBRATED_IMU = 0x0020, + }; + + StateManager(ROSflight& parent); + void init(); + void run(); + + inline const State& state() const { return state_; } + + void set_event(Event event); + void set_error(uint16_t error); + void clear_error(uint16_t error); + +private: + ROSflight& RF_; + State state_; + + int next_led_blink_ms_ = 0; + + enum FsmState + { + FSM_STATE_INIT, + FSM_STATE_PREFLIGHT, + FSM_STATE_ARMED, + FSM_STATE_ERROR, + FSM_STATE_FAILSAFE, + FSM_STATE_CALIBRATING + }; + + FsmState fsm_state_; + void process_errors(); + + void update_leds(); +}; + +} // namespace rosflight_firmware + +#endif // ROSFLIGHT_FIRMWARE_STATE_MANAGER_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/checksum.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/checksum.h new file mode 100644 index 0000000..0f30b65 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/checksum.h @@ -0,0 +1,96 @@ +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef _CHECKSUM_H_ +#define _CHECKSUM_H_ + +// Visual Studio versions before 2010 don't have stdint.h, so we just error out. +#if (defined _MSC_VER) && (_MSC_VER < 1600) +#error "The C-MAVLink implementation requires Visual Studio 2010 or greater" +#endif + +#include + +/** + * + * CALCULATE THE CHECKSUM + * + */ + +#define X25_INIT_CRC 0xffff +#define X25_VALIDATE_CRC 0xf0b8 + +#ifndef HAVE_CRC_ACCUMULATE +/** + * @brief Accumulate the X.25 CRC by adding one char at a time. + * + * The checksum function adds the hash of one char at a time to the + * 16 bit checksum (uint16_t). + * + * @param data new char to hash + * @param crcAccum the already accumulated checksum + **/ +static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) +{ + /*Accumulate one byte of data into the CRC*/ + uint8_t tmp; + + tmp = data ^ (uint8_t)(*crcAccum &0xff); + tmp ^= (tmp<<4); + *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); +} +#endif + + +/** + * @brief Initiliaze the buffer for the X.25 CRC + * + * @param crcAccum the 16 bit X.25 CRC + */ +static inline void crc_init(uint16_t* crcAccum) +{ + *crcAccum = X25_INIT_CRC; +} + + +/** + * @brief Calculates the X.25 checksum on a byte buffer + * + * @param pBuffer buffer containing the byte array to hash + * @param length length of the byte array + * @return the checksum over the buffer bytes + **/ +static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length) +{ + uint16_t crcTmp; + crc_init(&crcTmp); + while (length--) { + crc_accumulate(*pBuffer++, &crcTmp); + } + return crcTmp; +} + + +/** + * @brief Accumulate the X.25 CRC by adding an array of bytes + * + * The checksum function adds the hash of one char at a time to the + * 16 bit checksum (uint16_t). + * + * @param data new bytes to hash + * @param crcAccum the already accumulated checksum + **/ +static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length) +{ + const uint8_t *p = (const uint8_t *)pBuffer; + while (length--) { + crc_accumulate(*p++, crcAccum); + } +} + +#endif /* _CHECKSUM_H_ */ + +#ifdef __cplusplus +} +#endif diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/common.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/common.h new file mode 100644 index 0000000..ce06f42 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/common.h @@ -0,0 +1,1007 @@ +/** @file + * @brief MAVLink comm protocol generated from common.xml + * @see http://mavlink.org + */ +#ifndef MAVLINK_COMMON_H +#define MAVLINK_COMMON_H + +#ifndef MAVLINK_H + #error Wrong include order: MAVLINK_COMMON.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call. +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 37, 4, 0, 0, 27, 25, 0, 0, 0, 0, 0, 68, 26, 185, 229, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 53, 51, 53, 51, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 44, 64, 84, 9, 254, 16, 12, 36, 44, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 22, 13, 255, 14, 18, 43, 8, 22, 14, 36, 43, 41, 32, 243, 14, 93, 0, 100, 36, 60, 30, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 32, 52, 53, 6, 2, 38, 0, 254, 36, 30, 18, 18, 51, 9, 0} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 78, 196, 0, 0, 15, 3, 0, 0, 0, 0, 0, 153, 183, 51, 59, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 138, 108, 32, 185, 84, 34, 174, 124, 237, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 46, 29, 223, 85, 6, 229, 203, 1, 195, 109, 168, 181, 47, 72, 131, 127, 0, 103, 154, 178, 200, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 163, 105, 0, 0, 0, 0, 0, 0, 0, 0, 0, 90, 104, 85, 95, 130, 184, 0, 8, 204, 49, 170, 44, 83, 46, 0} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ALTITUDE, MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3, MAVLINK_MESSAGE_INFO_FOLLOW_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_LANDING_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS, MAVLINK_MESSAGE_INFO_WIND_COV, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VIBRATION, MAVLINK_MESSAGE_INFO_HOME_POSITION, MAVLINK_MESSAGE_INFO_SET_HOME_POSITION, MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL, MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE, MAVLINK_MESSAGE_INFO_ADSB_VEHICLE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_COMMON + +// ENUM DEFINITIONS + + +/** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */ +#ifndef HAVE_ENUM_MAV_AUTOPILOT +#define HAVE_ENUM_MAV_AUTOPILOT +typedef enum MAV_AUTOPILOT +{ + MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */ + MAV_AUTOPILOT_RESERVED=1, /* Reserved for future use. | */ + MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */ + MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilotMega / ArduCopter, http://diydrones.com | */ + MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */ + MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */ + MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */ + MAV_AUTOPILOT_GENERIC_MISSION_FULL=7, /* Generic autopilot supporting the full mission command set | */ + MAV_AUTOPILOT_INVALID=8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */ + MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */ + MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */ + MAV_AUTOPILOT_FP=11, /* FlexiPilot | */ + MAV_AUTOPILOT_PX4=12, /* PX4 Autopilot - http://pixhawk.ethz.ch/px4/ | */ + MAV_AUTOPILOT_SMACCMPILOT=13, /* SMACCMPilot - http://smaccmpilot.org | */ + MAV_AUTOPILOT_AUTOQUAD=14, /* AutoQuad -- http://autoquad.org | */ + MAV_AUTOPILOT_ARMAZILA=15, /* Armazila -- http://armazila.com | */ + MAV_AUTOPILOT_AEROB=16, /* Aerob -- http://aerob.ru | */ + MAV_AUTOPILOT_ASLUAV=17, /* ASLUAV autopilot -- http://www.asl.ethz.ch | */ + MAV_AUTOPILOT_ENUM_END=18, /* | */ +} MAV_AUTOPILOT; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_TYPE +#define HAVE_ENUM_MAV_TYPE +typedef enum MAV_TYPE +{ + MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */ + MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */ + MAV_TYPE_QUADROTOR=2, /* Quadrotor | */ + MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */ + MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */ + MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */ + MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */ + MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */ + MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */ + MAV_TYPE_ROCKET=9, /* Rocket | */ + MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */ + MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */ + MAV_TYPE_SUBMARINE=12, /* Submarine | */ + MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */ + MAV_TYPE_OCTOROTOR=14, /* Octorotor | */ + MAV_TYPE_TRICOPTER=15, /* Octorotor | */ + MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */ + MAV_TYPE_KITE=17, /* Flapping wing | */ + MAV_TYPE_ONBOARD_CONTROLLER=18, /* Onboard companion controller | */ + MAV_TYPE_VTOL_DUOROTOR=19, /* Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. | */ + MAV_TYPE_VTOL_QUADROTOR=20, /* Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. | */ + MAV_TYPE_VTOL_TILTROTOR=21, /* Tiltrotor VTOL | */ + MAV_TYPE_VTOL_RESERVED2=22, /* VTOL reserved 2 | */ + MAV_TYPE_VTOL_RESERVED3=23, /* VTOL reserved 3 | */ + MAV_TYPE_VTOL_RESERVED4=24, /* VTOL reserved 4 | */ + MAV_TYPE_VTOL_RESERVED5=25, /* VTOL reserved 5 | */ + MAV_TYPE_GIMBAL=26, /* Onboard gimbal | */ + MAV_TYPE_ADSB=27, /* Onboard ADSB peripheral | */ + MAV_TYPE_ENUM_END=28, /* | */ +} MAV_TYPE; +#endif + +/** @brief These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65. */ +#ifndef HAVE_ENUM_FIRMWARE_VERSION_TYPE +#define HAVE_ENUM_FIRMWARE_VERSION_TYPE +typedef enum FIRMWARE_VERSION_TYPE +{ + FIRMWARE_VERSION_TYPE_DEV=0, /* development release | */ + FIRMWARE_VERSION_TYPE_ALPHA=64, /* alpha release | */ + FIRMWARE_VERSION_TYPE_BETA=128, /* beta release | */ + FIRMWARE_VERSION_TYPE_RC=192, /* release candidate | */ + FIRMWARE_VERSION_TYPE_OFFICIAL=255, /* official stable release | */ + FIRMWARE_VERSION_TYPE_ENUM_END=256, /* | */ +} FIRMWARE_VERSION_TYPE; +#endif + +/** @brief These flags encode the MAV mode. */ +#ifndef HAVE_ENUM_MAV_MODE_FLAG +#define HAVE_ENUM_MAV_MODE_FLAG +typedef enum MAV_MODE_FLAG +{ + MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */ + MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */ + MAV_MODE_FLAG_AUTO_ENABLED=4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */ + MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */ + MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */ + MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */ + MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */ + MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */ + MAV_MODE_FLAG_ENUM_END=129, /* | */ +} MAV_MODE_FLAG; +#endif + +/** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */ +#ifndef HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION +#define HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION +typedef enum MAV_MODE_FLAG_DECODE_POSITION +{ + MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */ + MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */ + MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixt bit: 00000100 | */ + MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit: 00001000 | */ + MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */ + MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit: 00100000 | */ + MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */ + MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit: 10000000 | */ + MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /* | */ +} MAV_MODE_FLAG_DECODE_POSITION; +#endif + +/** @brief Override command, pauses current mission execution and moves immediately to a position */ +#ifndef HAVE_ENUM_MAV_GOTO +#define HAVE_ENUM_MAV_GOTO +typedef enum MAV_GOTO +{ + MAV_GOTO_DO_HOLD=0, /* Hold at the current position. | */ + MAV_GOTO_DO_CONTINUE=1, /* Continue with the next item in mission execution. | */ + MAV_GOTO_HOLD_AT_CURRENT_POSITION=2, /* Hold at the current position of the system | */ + MAV_GOTO_HOLD_AT_SPECIFIED_POSITION=3, /* Hold at the position specified in the parameters of the DO_HOLD action | */ + MAV_GOTO_ENUM_END=4, /* | */ +} MAV_GOTO; +#endif + +/** @brief These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it + simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. */ +#ifndef HAVE_ENUM_MAV_MODE +#define HAVE_ENUM_MAV_MODE +typedef enum MAV_MODE +{ + MAV_MODE_PREFLIGHT=0, /* System is not ready to fly, booting, calibrating, etc. No flag is set. | */ + MAV_MODE_MANUAL_DISARMED=64, /* System is allowed to be active, under manual (RC) control, no stabilization | */ + MAV_MODE_TEST_DISARMED=66, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ + MAV_MODE_STABILIZE_DISARMED=80, /* System is allowed to be active, under assisted RC control. | */ + MAV_MODE_GUIDED_DISARMED=88, /* System is allowed to be active, under autonomous control, manual setpoint | */ + MAV_MODE_AUTO_DISARMED=92, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ + MAV_MODE_MANUAL_ARMED=192, /* System is allowed to be active, under manual (RC) control, no stabilization | */ + MAV_MODE_TEST_ARMED=194, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ + MAV_MODE_STABILIZE_ARMED=208, /* System is allowed to be active, under assisted RC control. | */ + MAV_MODE_GUIDED_ARMED=216, /* System is allowed to be active, under autonomous control, manual setpoint | */ + MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ + MAV_MODE_ENUM_END=221, /* | */ +} MAV_MODE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_STATE +#define HAVE_ENUM_MAV_STATE +typedef enum MAV_STATE +{ + MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */ + MAV_STATE_BOOT=1, /* System is booting up. | */ + MAV_STATE_CALIBRATING=2, /* System is calibrating and not flight-ready. | */ + MAV_STATE_STANDBY=3, /* System is grounded and on standby. It can be launched any time. | */ + MAV_STATE_ACTIVE=4, /* System is active and might be already airborne. Motors are engaged. | */ + MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode. It can however still navigate. | */ + MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */ + MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */ + MAV_STATE_ENUM_END=8, /* | */ +} MAV_STATE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_COMPONENT +#define HAVE_ENUM_MAV_COMPONENT +typedef enum MAV_COMPONENT +{ + MAV_COMP_ID_ALL=0, /* | */ + MAV_COMP_ID_CAMERA=100, /* | */ + MAV_COMP_ID_SERVO1=140, /* | */ + MAV_COMP_ID_SERVO2=141, /* | */ + MAV_COMP_ID_SERVO3=142, /* | */ + MAV_COMP_ID_SERVO4=143, /* | */ + MAV_COMP_ID_SERVO5=144, /* | */ + MAV_COMP_ID_SERVO6=145, /* | */ + MAV_COMP_ID_SERVO7=146, /* | */ + MAV_COMP_ID_SERVO8=147, /* | */ + MAV_COMP_ID_SERVO9=148, /* | */ + MAV_COMP_ID_SERVO10=149, /* | */ + MAV_COMP_ID_SERVO11=150, /* | */ + MAV_COMP_ID_SERVO12=151, /* | */ + MAV_COMP_ID_SERVO13=152, /* | */ + MAV_COMP_ID_SERVO14=153, /* | */ + MAV_COMP_ID_GIMBAL=154, /* | */ + MAV_COMP_ID_LOG=155, /* | */ + MAV_COMP_ID_ADSB=156, /* | */ + MAV_COMP_ID_OSD=157, /* On Screen Display (OSD) devices for video links | */ + MAV_COMP_ID_PERIPHERAL=158, /* Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol | */ + MAV_COMP_ID_MAPPER=180, /* | */ + MAV_COMP_ID_MISSIONPLANNER=190, /* | */ + MAV_COMP_ID_PATHPLANNER=195, /* | */ + MAV_COMP_ID_IMU=200, /* | */ + MAV_COMP_ID_IMU_2=201, /* | */ + MAV_COMP_ID_IMU_3=202, /* | */ + MAV_COMP_ID_GPS=220, /* | */ + MAV_COMP_ID_UDP_BRIDGE=240, /* | */ + MAV_COMP_ID_UART_BRIDGE=241, /* | */ + MAV_COMP_ID_SYSTEM_CONTROL=250, /* | */ + MAV_COMPONENT_ENUM_END=251, /* | */ +} MAV_COMPONENT; +#endif + +/** @brief These encode the sensors whose status is sent as part of the SYS_STATUS message. */ +#ifndef HAVE_ENUM_MAV_SYS_STATUS_SENSOR +#define HAVE_ENUM_MAV_SYS_STATUS_SENSOR +typedef enum MAV_SYS_STATUS_SENSOR +{ + MAV_SYS_STATUS_SENSOR_3D_GYRO=1, /* 0x01 3D gyro | */ + MAV_SYS_STATUS_SENSOR_3D_ACCEL=2, /* 0x02 3D accelerometer | */ + MAV_SYS_STATUS_SENSOR_3D_MAG=4, /* 0x04 3D magnetometer | */ + MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE=8, /* 0x08 absolute pressure | */ + MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE=16, /* 0x10 differential pressure | */ + MAV_SYS_STATUS_SENSOR_GPS=32, /* 0x20 GPS | */ + MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW=64, /* 0x40 optical flow | */ + MAV_SYS_STATUS_SENSOR_VISION_POSITION=128, /* 0x80 computer vision position | */ + MAV_SYS_STATUS_SENSOR_LASER_POSITION=256, /* 0x100 laser based position | */ + MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH=512, /* 0x200 external ground truth (Vicon or Leica) | */ + MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL=1024, /* 0x400 3D angular rate control | */ + MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION=2048, /* 0x800 attitude stabilization | */ + MAV_SYS_STATUS_SENSOR_YAW_POSITION=4096, /* 0x1000 yaw position | */ + MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL=8192, /* 0x2000 z/altitude control | */ + MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL=16384, /* 0x4000 x/y position control | */ + MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS=32768, /* 0x8000 motor outputs / control | */ + MAV_SYS_STATUS_SENSOR_RC_RECEIVER=65536, /* 0x10000 rc receiver | */ + MAV_SYS_STATUS_SENSOR_3D_GYRO2=131072, /* 0x20000 2nd 3D gyro | */ + MAV_SYS_STATUS_SENSOR_3D_ACCEL2=262144, /* 0x40000 2nd 3D accelerometer | */ + MAV_SYS_STATUS_SENSOR_3D_MAG2=524288, /* 0x80000 2nd 3D magnetometer | */ + MAV_SYS_STATUS_GEOFENCE=1048576, /* 0x100000 geofence | */ + MAV_SYS_STATUS_AHRS=2097152, /* 0x200000 AHRS subsystem health | */ + MAV_SYS_STATUS_TERRAIN=4194304, /* 0x400000 Terrain subsystem health | */ + MAV_SYS_STATUS_REVERSE_MOTOR=8388608, /* 0x800000 Motors are reversed | */ + MAV_SYS_STATUS_SENSOR_ENUM_END=8388609, /* | */ +} MAV_SYS_STATUS_SENSOR; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAV_FRAME +#define HAVE_ENUM_MAV_FRAME +typedef enum MAV_FRAME +{ + MAV_FRAME_GLOBAL=0, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | */ + MAV_FRAME_LOCAL_NED=1, /* Local coordinate frame, Z-up (x: north, y: east, z: down). | */ + MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */ + MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */ + MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */ + MAV_FRAME_GLOBAL_INT=5, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL) | */ + MAV_FRAME_GLOBAL_RELATIVE_ALT_INT=6, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. | */ + MAV_FRAME_LOCAL_OFFSET_NED=7, /* Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. | */ + MAV_FRAME_BODY_NED=8, /* Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. | */ + MAV_FRAME_BODY_OFFSET_NED=9, /* Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. | */ + MAV_FRAME_GLOBAL_TERRAIN_ALT=10, /* Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */ + MAV_FRAME_GLOBAL_TERRAIN_ALT_INT=11, /* Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */ + MAV_FRAME_ENUM_END=12, /* | */ +} MAV_FRAME; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE +#define HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE +typedef enum MAVLINK_DATA_STREAM_TYPE +{ + MAVLINK_DATA_STREAM_IMG_JPEG=1, /* | */ + MAVLINK_DATA_STREAM_IMG_BMP=2, /* | */ + MAVLINK_DATA_STREAM_IMG_RAW8U=3, /* | */ + MAVLINK_DATA_STREAM_IMG_RAW32U=4, /* | */ + MAVLINK_DATA_STREAM_IMG_PGM=5, /* | */ + MAVLINK_DATA_STREAM_IMG_PNG=6, /* | */ + MAVLINK_DATA_STREAM_TYPE_ENUM_END=7, /* | */ +} MAVLINK_DATA_STREAM_TYPE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_FENCE_ACTION +#define HAVE_ENUM_FENCE_ACTION +typedef enum FENCE_ACTION +{ + FENCE_ACTION_NONE=0, /* Disable fenced mode | */ + FENCE_ACTION_GUIDED=1, /* Switched to guided mode to return point (fence point 0) | */ + FENCE_ACTION_REPORT=2, /* Report fence breach, but don't take action | */ + FENCE_ACTION_GUIDED_THR_PASS=3, /* Switched to guided mode to return point (fence point 0) with manual throttle control | */ + FENCE_ACTION_ENUM_END=4, /* | */ +} FENCE_ACTION; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_FENCE_BREACH +#define HAVE_ENUM_FENCE_BREACH +typedef enum FENCE_BREACH +{ + FENCE_BREACH_NONE=0, /* No last fence breach | */ + FENCE_BREACH_MINALT=1, /* Breached minimum altitude | */ + FENCE_BREACH_MAXALT=2, /* Breached maximum altitude | */ + FENCE_BREACH_BOUNDARY=3, /* Breached fence boundary | */ + FENCE_BREACH_ENUM_END=4, /* | */ +} FENCE_BREACH; +#endif + +/** @brief Enumeration of possible mount operation modes */ +#ifndef HAVE_ENUM_MAV_MOUNT_MODE +#define HAVE_ENUM_MAV_MOUNT_MODE +typedef enum MAV_MOUNT_MODE +{ + MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization | */ + MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | */ + MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */ + MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */ + MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */ + MAV_MOUNT_MODE_ENUM_END=5, /* | */ +} MAV_MOUNT_MODE; +#endif + +/** @brief Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */ +#ifndef HAVE_ENUM_MAV_CMD +#define HAVE_ENUM_MAV_CMD +typedef enum MAV_CMD +{ + MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_LAND=21, /* Land at location |Abort Alt| Empty| Empty| Desired yaw angle| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LAND_LOCAL=23, /* Land at local position (local frame only) |Landing target number (if available)| Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land| Landing descend rate [ms^-1]| Desired yaw angle [rad]| Y-axis position [m]| X-axis position [m]| Z-axis / ground level position [m]| */ + MAV_CMD_NAV_TAKEOFF_LOCAL=24, /* Takeoff from local position (local frame only) |Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]| Empty| Takeoff ascend rate [ms^-1]| Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these| Y-axis position [m]| X-axis position [m]| Z-axis position [m]| */ + MAV_CMD_NAV_FOLLOW=25, /* Vehicle following, i.e. this waypoint represents the position of a moving vehicle |Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation| Ground speed of vehicle to be followed| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT=30, /* Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. |Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. | Empty| Empty| Empty| Empty| Empty| Desired altitude in meters| */ + MAV_CMD_NAV_LOITER_TO_ALT=31, /* Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. |Heading Required (0 = False)| Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.| Empty| Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location| Latitude| Longitude| Altitude| */ + MAV_CMD_DO_FOLLOW=32, /* Being following a target |System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode| RESERVED| RESERVED| altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home| altitude| RESERVED| TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout| */ + MAV_CMD_DO_FOLLOW_REPOSITION=33, /* Reposition the MAV after a follow target command has been sent |Camera q1 (where 0 is on the ray from the camera to the tracking device)| Camera q2| Camera q3| Camera q4| altitude offset from target (m)| X offset from target (m)| Y offset from target (m)| */ + MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ + MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_VTOL_TAKEOFF=84, /* Takeoff from ground using VTOL mode |Empty| Empty| Empty| Yaw angle in degrees| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_VTOL_LAND=85, /* Land using VTOL mode |Empty| Empty| Empty| Yaw angle in degrees| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_DELAY=93, /* Delay the next navigation command a number of seconds or until a specified time |Delay in seconds (decimal, -1 to enable time-of-day fields)| hour (24h format, UTC, -1 to ignore)| minute (24h format, UTC, -1 to ignore)| second (24h format, UTC)| Empty| Empty| Empty| */ + MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ + MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| absolute or relative [0,1]| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ + MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ + MAV_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_LAND_START=189, /* Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty| */ + MAV_CMD_DO_RALLY_LAND=190, /* Mission command to perform a landing from a rally point. |Break altitude (meters)| Landing speed (m/s)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_GO_AROUND=191, /* Mission command to safely abort an autonmous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPOSITION=192, /* Reposition the vehicle to a specific WGS84 global position. |Ground speed, less than 0 (-1) for default| Bitmask of option flags, see the MAV_DO_REPOSITION_FLAGS enum.| Reserved| Yaw heading, NaN for unchanged. For planes indicates loiter direction (0: clockwise, 1: counter clockwise)| Latitude (deg * 1E7)| Longitude (deg * 1E7)| Altitude (meters)| */ + MAV_CMD_DO_PAUSE_CONTINUE=193, /* If in a GPS controlled position mode, hold the current position or continue. |0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ + MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ + MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */ + MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */ + MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ + MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */ + MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable, 2=disable_floor_only)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| */ + MAV_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_GUIDED_LIMITS=222, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */ + MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */ + MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ + MAV_CMD_PREFLIGHT_UAVCAN=243, /* Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. |1: Trigger actuator ID assignment and direction mapping.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ + MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)| Reserved| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.| Reserved, send 0| Reserved, send 0| Reserved, send 0| Reserved, send 0| Reserved, send 0| */ + MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ + MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ + MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ + MAV_CMD_GET_HOME_POSITION=410, /* Request the home position from the vehicle. |Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ + MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ + MAV_CMD_GET_MESSAGE_INTERVAL=510, /* Request the interval between messages for a particular MAVLink message ID |The MAVLink message ID| */ + MAV_CMD_SET_MESSAGE_INTERVAL=511, /* Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM |The MAVLink message ID| The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.| */ + MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities |1: Request autopilot version| Reserved (all remaining params)| */ + MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence |Duration between two consecutive pictures (in seconds)| Number of images to capture total - 0 for unlimited capture| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */ + MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence |Reserved| Reserved| */ + MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start)| Shutter integration time (in ms)| Reserved| */ + MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture |Camera ID (0 for all cameras), 1 for first, 2 for second, etc.| Frames per second| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */ + MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture |Reserved| Reserved| */ + MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)| Viewing angle vertical of panorama (in degrees)| Speed of the horizontal rotation (in degrees per second)| Speed of the vertical rotation (in degrees per second)| */ + MAV_CMD_DO_VTOL_TRANSITION=3000, /* Request VTOL transition |The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.| */ + MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.| Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Altitude, in meters AMSL| */ + MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ + MAV_CMD_WAYPOINT_USER_1=31000, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_WAYPOINT_USER_2=31001, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_WAYPOINT_USER_3=31002, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_WAYPOINT_USER_4=31003, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_WAYPOINT_USER_5=31004, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_SPATIAL_USER_1=31005, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_SPATIAL_USER_2=31006, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_SPATIAL_USER_3=31007, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_SPATIAL_USER_4=31008, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_SPATIAL_USER_5=31009, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude, in meters AMSL| */ + MAV_CMD_USER_1=31010, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ + MAV_CMD_USER_2=31011, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ + MAV_CMD_USER_3=31012, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ + MAV_CMD_USER_4=31013, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ + MAV_CMD_USER_5=31014, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */ + MAV_CMD_ENUM_END=31015, /* | */ +} MAV_CMD; +#endif + +/** @brief THIS INTERFACE IS DEPRECATED AS OF JULY 2015. Please use MESSAGE_INTERVAL instead. A data stream is not a fixed set of messages, but rather a + recommendation to the autopilot software. Individual autopilots may or may not obey + the recommended messages. */ +#ifndef HAVE_ENUM_MAV_DATA_STREAM +#define HAVE_ENUM_MAV_DATA_STREAM +typedef enum MAV_DATA_STREAM +{ + MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */ + MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */ + MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */ + MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */ + MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */ + MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */ + MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_ENUM_END=13, /* | */ +} MAV_DATA_STREAM; +#endif + +/** @brief The ROI (region of interest) for the vehicle. This can be + be used by the vehicle for camera/vehicle attitude alignment (see + MAV_CMD_NAV_ROI). */ +#ifndef HAVE_ENUM_MAV_ROI +#define HAVE_ENUM_MAV_ROI +typedef enum MAV_ROI +{ + MAV_ROI_NONE=0, /* No region of interest. | */ + MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */ + MAV_ROI_WPINDEX=2, /* Point toward given MISSION. | */ + MAV_ROI_LOCATION=3, /* Point toward fixed location. | */ + MAV_ROI_TARGET=4, /* Point toward of given id. | */ + MAV_ROI_ENUM_END=5, /* | */ +} MAV_ROI; +#endif + +/** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */ +#ifndef HAVE_ENUM_MAV_CMD_ACK +#define HAVE_ENUM_MAV_CMD_ACK +typedef enum MAV_CMD_ACK +{ + MAV_CMD_ACK_OK=1, /* Command / mission item is ok. | */ + MAV_CMD_ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */ + MAV_CMD_ACK_ERR_ACCESS_DENIED=3, /* The system is refusing to accept this command from this source / communication partner. | */ + MAV_CMD_ACK_ERR_NOT_SUPPORTED=4, /* Command or mission item is not supported, other commands would be accepted. | */ + MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, /* The coordinate frame of this command / mission item is not supported. | */ + MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE=6, /* The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | */ + MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE=7, /* The X or latitude value is out of range. | */ + MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */ + MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */ + MAV_CMD_ACK_ENUM_END=10, /* | */ +} MAV_CMD_ACK; +#endif + +/** @brief Specifies the datatype of a MAVLink parameter. */ +#ifndef HAVE_ENUM_MAV_PARAM_TYPE +#define HAVE_ENUM_MAV_PARAM_TYPE +typedef enum MAV_PARAM_TYPE +{ + MAV_PARAM_TYPE_UINT8=1, /* 8-bit unsigned integer | */ + MAV_PARAM_TYPE_INT8=2, /* 8-bit signed integer | */ + MAV_PARAM_TYPE_UINT16=3, /* 16-bit unsigned integer | */ + MAV_PARAM_TYPE_INT16=4, /* 16-bit signed integer | */ + MAV_PARAM_TYPE_UINT32=5, /* 32-bit unsigned integer | */ + MAV_PARAM_TYPE_INT32=6, /* 32-bit signed integer | */ + MAV_PARAM_TYPE_UINT64=7, /* 64-bit unsigned integer | */ + MAV_PARAM_TYPE_INT64=8, /* 64-bit signed integer | */ + MAV_PARAM_TYPE_REAL32=9, /* 32-bit floating-point | */ + MAV_PARAM_TYPE_REAL64=10, /* 64-bit floating-point | */ + MAV_PARAM_TYPE_ENUM_END=11, /* | */ +} MAV_PARAM_TYPE; +#endif + +/** @brief result from a mavlink command */ +#ifndef HAVE_ENUM_MAV_RESULT +#define HAVE_ENUM_MAV_RESULT +typedef enum MAV_RESULT +{ + MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */ + MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */ + MAV_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */ + MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */ + MAV_RESULT_FAILED=4, /* Command executed, but failed | */ + MAV_RESULT_ENUM_END=5, /* | */ +} MAV_RESULT; +#endif + +/** @brief result in a mavlink mission ack */ +#ifndef HAVE_ENUM_MAV_MISSION_RESULT +#define HAVE_ENUM_MAV_MISSION_RESULT +typedef enum MAV_MISSION_RESULT +{ + MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */ + MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */ + MAV_MISSION_UNSUPPORTED_FRAME=2, /* coordinate frame is not supported | */ + MAV_MISSION_UNSUPPORTED=3, /* command is not supported | */ + MAV_MISSION_NO_SPACE=4, /* mission item exceeds storage space | */ + MAV_MISSION_INVALID=5, /* one of the parameters has an invalid value | */ + MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value | */ + MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value | */ + MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value | */ + MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value | */ + MAV_MISSION_INVALID_PARAM5_X=10, /* x/param5 has an invalid value | */ + MAV_MISSION_INVALID_PARAM6_Y=11, /* y/param6 has an invalid value | */ + MAV_MISSION_INVALID_PARAM7=12, /* param7 has an invalid value | */ + MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */ + MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */ + MAV_MISSION_RESULT_ENUM_END=15, /* | */ +} MAV_MISSION_RESULT; +#endif + +/** @brief Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. */ +#ifndef HAVE_ENUM_MAV_SEVERITY +#define HAVE_ENUM_MAV_SEVERITY +typedef enum MAV_SEVERITY +{ + MAV_SEVERITY_EMERGENCY=0, /* System is unusable. This is a "panic" condition. | */ + MAV_SEVERITY_ALERT=1, /* Action should be taken immediately. Indicates error in non-critical systems. | */ + MAV_SEVERITY_CRITICAL=2, /* Action must be taken immediately. Indicates failure in a primary system. | */ + MAV_SEVERITY_ERROR=3, /* Indicates an error in secondary/redundant systems. | */ + MAV_SEVERITY_WARNING=4, /* Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | */ + MAV_SEVERITY_NOTICE=5, /* An unusual event has occured, though not an error condition. This should be investigated for the root cause. | */ + MAV_SEVERITY_INFO=6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */ + MAV_SEVERITY_DEBUG=7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */ + MAV_SEVERITY_ENUM_END=8, /* | */ +} MAV_SEVERITY; +#endif + +/** @brief Power supply status flags (bitmask) */ +#ifndef HAVE_ENUM_MAV_POWER_STATUS +#define HAVE_ENUM_MAV_POWER_STATUS +typedef enum MAV_POWER_STATUS +{ + MAV_POWER_STATUS_BRICK_VALID=1, /* main brick power supply valid | */ + MAV_POWER_STATUS_SERVO_VALID=2, /* main servo power supply valid for FMU | */ + MAV_POWER_STATUS_USB_CONNECTED=4, /* USB power is connected | */ + MAV_POWER_STATUS_PERIPH_OVERCURRENT=8, /* peripheral supply is in over-current state | */ + MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT=16, /* hi-power peripheral supply is in over-current state | */ + MAV_POWER_STATUS_CHANGED=32, /* Power status has changed since boot | */ + MAV_POWER_STATUS_ENUM_END=33, /* | */ +} MAV_POWER_STATUS; +#endif + +/** @brief SERIAL_CONTROL device types */ +#ifndef HAVE_ENUM_SERIAL_CONTROL_DEV +#define HAVE_ENUM_SERIAL_CONTROL_DEV +typedef enum SERIAL_CONTROL_DEV +{ + SERIAL_CONTROL_DEV_TELEM1=0, /* First telemetry port | */ + SERIAL_CONTROL_DEV_TELEM2=1, /* Second telemetry port | */ + SERIAL_CONTROL_DEV_GPS1=2, /* First GPS port | */ + SERIAL_CONTROL_DEV_GPS2=3, /* Second GPS port | */ + SERIAL_CONTROL_DEV_SHELL=10, /* system shell | */ + SERIAL_CONTROL_DEV_ENUM_END=11, /* | */ +} SERIAL_CONTROL_DEV; +#endif + +/** @brief SERIAL_CONTROL flags (bitmask) */ +#ifndef HAVE_ENUM_SERIAL_CONTROL_FLAG +#define HAVE_ENUM_SERIAL_CONTROL_FLAG +typedef enum SERIAL_CONTROL_FLAG +{ + SERIAL_CONTROL_FLAG_REPLY=1, /* Set if this is a reply | */ + SERIAL_CONTROL_FLAG_RESPOND=2, /* Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message | */ + SERIAL_CONTROL_FLAG_EXCLUSIVE=4, /* Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set | */ + SERIAL_CONTROL_FLAG_BLOCKING=8, /* Block on writes to the serial port | */ + SERIAL_CONTROL_FLAG_MULTI=16, /* Send multiple replies until port is drained | */ + SERIAL_CONTROL_FLAG_ENUM_END=17, /* | */ +} SERIAL_CONTROL_FLAG; +#endif + +/** @brief Enumeration of distance sensor types */ +#ifndef HAVE_ENUM_MAV_DISTANCE_SENSOR +#define HAVE_ENUM_MAV_DISTANCE_SENSOR +typedef enum MAV_DISTANCE_SENSOR +{ + MAV_DISTANCE_SENSOR_LASER=0, /* Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units | */ + MAV_DISTANCE_SENSOR_ULTRASOUND=1, /* Ultrasound rangefinder, e.g. MaxBotix units | */ + MAV_DISTANCE_SENSOR_INFRARED=2, /* Infrared rangefinder, e.g. Sharp units | */ + MAV_DISTANCE_SENSOR_ENUM_END=3, /* | */ +} MAV_DISTANCE_SENSOR; +#endif + +/** @brief Enumeration of sensor orientation, according to its rotations */ +#ifndef HAVE_ENUM_MAV_SENSOR_ORIENTATION +#define HAVE_ENUM_MAV_SENSOR_ORIENTATION +typedef enum MAV_SENSOR_ORIENTATION +{ + MAV_SENSOR_ROTATION_NONE=0, /* Roll: 0, Pitch: 0, Yaw: 0 | */ + MAV_SENSOR_ROTATION_YAW_45=1, /* Roll: 0, Pitch: 0, Yaw: 45 | */ + MAV_SENSOR_ROTATION_YAW_90=2, /* Roll: 0, Pitch: 0, Yaw: 90 | */ + MAV_SENSOR_ROTATION_YAW_135=3, /* Roll: 0, Pitch: 0, Yaw: 135 | */ + MAV_SENSOR_ROTATION_YAW_180=4, /* Roll: 0, Pitch: 0, Yaw: 180 | */ + MAV_SENSOR_ROTATION_YAW_225=5, /* Roll: 0, Pitch: 0, Yaw: 225 | */ + MAV_SENSOR_ROTATION_YAW_270=6, /* Roll: 0, Pitch: 0, Yaw: 270 | */ + MAV_SENSOR_ROTATION_YAW_315=7, /* Roll: 0, Pitch: 0, Yaw: 315 | */ + MAV_SENSOR_ROTATION_ROLL_180=8, /* Roll: 180, Pitch: 0, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_180_YAW_45=9, /* Roll: 180, Pitch: 0, Yaw: 45 | */ + MAV_SENSOR_ROTATION_ROLL_180_YAW_90=10, /* Roll: 180, Pitch: 0, Yaw: 90 | */ + MAV_SENSOR_ROTATION_ROLL_180_YAW_135=11, /* Roll: 180, Pitch: 0, Yaw: 135 | */ + MAV_SENSOR_ROTATION_PITCH_180=12, /* Roll: 0, Pitch: 180, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_180_YAW_225=13, /* Roll: 180, Pitch: 0, Yaw: 225 | */ + MAV_SENSOR_ROTATION_ROLL_180_YAW_270=14, /* Roll: 180, Pitch: 0, Yaw: 270 | */ + MAV_SENSOR_ROTATION_ROLL_180_YAW_315=15, /* Roll: 180, Pitch: 0, Yaw: 315 | */ + MAV_SENSOR_ROTATION_ROLL_90=16, /* Roll: 90, Pitch: 0, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_90_YAW_45=17, /* Roll: 90, Pitch: 0, Yaw: 45 | */ + MAV_SENSOR_ROTATION_ROLL_90_YAW_90=18, /* Roll: 90, Pitch: 0, Yaw: 90 | */ + MAV_SENSOR_ROTATION_ROLL_90_YAW_135=19, /* Roll: 90, Pitch: 0, Yaw: 135 | */ + MAV_SENSOR_ROTATION_ROLL_270=20, /* Roll: 270, Pitch: 0, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_270_YAW_45=21, /* Roll: 270, Pitch: 0, Yaw: 45 | */ + MAV_SENSOR_ROTATION_ROLL_270_YAW_90=22, /* Roll: 270, Pitch: 0, Yaw: 90 | */ + MAV_SENSOR_ROTATION_ROLL_270_YAW_135=23, /* Roll: 270, Pitch: 0, Yaw: 135 | */ + MAV_SENSOR_ROTATION_PITCH_90=24, /* Roll: 0, Pitch: 90, Yaw: 0 | */ + MAV_SENSOR_ROTATION_PITCH_270=25, /* Roll: 0, Pitch: 270, Yaw: 0 | */ + MAV_SENSOR_ROTATION_PITCH_180_YAW_90=26, /* Roll: 0, Pitch: 180, Yaw: 90 | */ + MAV_SENSOR_ROTATION_PITCH_180_YAW_270=27, /* Roll: 0, Pitch: 180, Yaw: 270 | */ + MAV_SENSOR_ROTATION_ROLL_90_PITCH_90=28, /* Roll: 90, Pitch: 90, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_180_PITCH_90=29, /* Roll: 180, Pitch: 90, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_270_PITCH_90=30, /* Roll: 270, Pitch: 90, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_90_PITCH_180=31, /* Roll: 90, Pitch: 180, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_270_PITCH_180=32, /* Roll: 270, Pitch: 180, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_90_PITCH_270=33, /* Roll: 90, Pitch: 270, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_180_PITCH_270=34, /* Roll: 180, Pitch: 270, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_270_PITCH_270=35, /* Roll: 270, Pitch: 270, Yaw: 0 | */ + MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90=36, /* Roll: 90, Pitch: 180, Yaw: 90 | */ + MAV_SENSOR_ROTATION_ROLL_90_YAW_270=37, /* Roll: 90, Pitch: 0, Yaw: 270 | */ + MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315=38, /* Roll: 315, Pitch: 315, Yaw: 315 | */ + MAV_SENSOR_ORIENTATION_ENUM_END=39, /* | */ +} MAV_SENSOR_ORIENTATION; +#endif + +/** @brief Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability. */ +#ifndef HAVE_ENUM_MAV_PROTOCOL_CAPABILITY +#define HAVE_ENUM_MAV_PROTOCOL_CAPABILITY +typedef enum MAV_PROTOCOL_CAPABILITY +{ + MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT=1, /* Autopilot supports MISSION float message type. | */ + MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT=2, /* Autopilot supports the new param float message type. | */ + MAV_PROTOCOL_CAPABILITY_MISSION_INT=4, /* Autopilot supports MISSION_INT scaled integer message type. | */ + MAV_PROTOCOL_CAPABILITY_COMMAND_INT=8, /* Autopilot supports COMMAND_INT scaled integer message type. | */ + MAV_PROTOCOL_CAPABILITY_PARAM_UNION=16, /* Autopilot supports the new param union message type. | */ + MAV_PROTOCOL_CAPABILITY_FTP=32, /* Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. | */ + MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET=64, /* Autopilot supports commanding attitude offboard. | */ + MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED=128, /* Autopilot supports commanding position and velocity targets in local NED frame. | */ + MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT=256, /* Autopilot supports commanding position and velocity targets in global scaled integers. | */ + MAV_PROTOCOL_CAPABILITY_TERRAIN=512, /* Autopilot supports terrain protocol / data handling. | */ + MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET=1024, /* Autopilot supports direct actuator control. | */ + MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION=2048, /* Autopilot supports the flight termination command. | */ + MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION=4096, /* Autopilot supports onboard compass calibration. | */ + MAV_PROTOCOL_CAPABILITY_ENUM_END=4097, /* | */ +} MAV_PROTOCOL_CAPABILITY; +#endif + +/** @brief Enumeration of estimator types */ +#ifndef HAVE_ENUM_MAV_ESTIMATOR_TYPE +#define HAVE_ENUM_MAV_ESTIMATOR_TYPE +typedef enum MAV_ESTIMATOR_TYPE +{ + MAV_ESTIMATOR_TYPE_NAIVE=1, /* This is a naive estimator without any real covariance feedback. | */ + MAV_ESTIMATOR_TYPE_VISION=2, /* Computer vision based estimate. Might be up to scale. | */ + MAV_ESTIMATOR_TYPE_VIO=3, /* Visual-inertial estimate. | */ + MAV_ESTIMATOR_TYPE_GPS=4, /* Plain GPS estimate. | */ + MAV_ESTIMATOR_TYPE_GPS_INS=5, /* Estimator integrating GPS and inertial sensing. | */ + MAV_ESTIMATOR_TYPE_ENUM_END=6, /* | */ +} MAV_ESTIMATOR_TYPE; +#endif + +/** @brief Enumeration of battery types */ +#ifndef HAVE_ENUM_MAV_BATTERY_TYPE +#define HAVE_ENUM_MAV_BATTERY_TYPE +typedef enum MAV_BATTERY_TYPE +{ + MAV_BATTERY_TYPE_UNKNOWN=0, /* Not specified. | */ + MAV_BATTERY_TYPE_LIPO=1, /* Lithium polymer battery | */ + MAV_BATTERY_TYPE_LIFE=2, /* Lithium-iron-phosphate battery | */ + MAV_BATTERY_TYPE_LION=3, /* Lithium-ION battery | */ + MAV_BATTERY_TYPE_NIMH=4, /* Nickel metal hydride battery | */ + MAV_BATTERY_TYPE_ENUM_END=5, /* | */ +} MAV_BATTERY_TYPE; +#endif + +/** @brief Enumeration of battery functions */ +#ifndef HAVE_ENUM_MAV_BATTERY_FUNCTION +#define HAVE_ENUM_MAV_BATTERY_FUNCTION +typedef enum MAV_BATTERY_FUNCTION +{ + MAV_BATTERY_FUNCTION_UNKNOWN=0, /* Battery function is unknown | */ + MAV_BATTERY_FUNCTION_ALL=1, /* Battery supports all flight systems | */ + MAV_BATTERY_FUNCTION_PROPULSION=2, /* Battery for the propulsion system | */ + MAV_BATTERY_FUNCTION_AVIONICS=3, /* Avionics battery | */ + MAV_BATTERY_TYPE_PAYLOAD=4, /* Payload battery | */ + MAV_BATTERY_FUNCTION_ENUM_END=5, /* | */ +} MAV_BATTERY_FUNCTION; +#endif + +/** @brief Enumeration of VTOL states */ +#ifndef HAVE_ENUM_MAV_VTOL_STATE +#define HAVE_ENUM_MAV_VTOL_STATE +typedef enum MAV_VTOL_STATE +{ + MAV_VTOL_STATE_UNDEFINED=0, /* MAV is not configured as VTOL | */ + MAV_VTOL_STATE_TRANSITION_TO_FW=1, /* VTOL is in transition from multicopter to fixed-wing | */ + MAV_VTOL_STATE_TRANSITION_TO_MC=2, /* VTOL is in transition from fixed-wing to multicopter | */ + MAV_VTOL_STATE_MC=3, /* VTOL is in multicopter state | */ + MAV_VTOL_STATE_FW=4, /* VTOL is in fixed-wing state | */ + MAV_VTOL_STATE_ENUM_END=5, /* | */ +} MAV_VTOL_STATE; +#endif + +/** @brief Enumeration of landed detector states */ +#ifndef HAVE_ENUM_MAV_LANDED_STATE +#define HAVE_ENUM_MAV_LANDED_STATE +typedef enum MAV_LANDED_STATE +{ + MAV_LANDED_STATE_UNDEFINED=0, /* MAV landed state is unknown | */ + MAV_LANDED_STATE_ON_GROUND=1, /* MAV is landed (on ground) | */ + MAV_LANDED_STATE_IN_AIR=2, /* MAV is in air | */ + MAV_LANDED_STATE_ENUM_END=3, /* | */ +} MAV_LANDED_STATE; +#endif + +/** @brief Enumeration of the ADSB altimeter types */ +#ifndef HAVE_ENUM_ADSB_ALTITUDE_TYPE +#define HAVE_ENUM_ADSB_ALTITUDE_TYPE +typedef enum ADSB_ALTITUDE_TYPE +{ + ADSB_ALTITUDE_TYPE_PRESSURE_QNH=0, /* Altitude reported from a Baro source using QNH reference | */ + ADSB_ALTITUDE_TYPE_GEOMETRIC=1, /* Altitude reported from a GNSS source | */ + ADSB_ALTITUDE_TYPE_ENUM_END=2, /* | */ +} ADSB_ALTITUDE_TYPE; +#endif + +/** @brief ADSB classification for the type of vehicle emitting the transponder signal */ +#ifndef HAVE_ENUM_ADSB_EMITTER_TYPE +#define HAVE_ENUM_ADSB_EMITTER_TYPE +typedef enum ADSB_EMITTER_TYPE +{ + ADSB_EMITTER_TYPE_NO_INFO=0, /* | */ + ADSB_EMITTER_TYPE_LIGHT=1, /* | */ + ADSB_EMITTER_TYPE_SMALL=2, /* | */ + ADSB_EMITTER_TYPE_LARGE=3, /* | */ + ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE=4, /* | */ + ADSB_EMITTER_TYPE_HEAVY=5, /* | */ + ADSB_EMITTER_TYPE_HIGHLY_MANUV=6, /* | */ + ADSB_EMITTER_TYPE_ROTOCRAFT=7, /* | */ + ADSB_EMITTER_TYPE_UNASSIGNED=8, /* | */ + ADSB_EMITTER_TYPE_GLIDER=9, /* | */ + ADSB_EMITTER_TYPE_LIGHTER_AIR=10, /* | */ + ADSB_EMITTER_TYPE_PARACHUTE=11, /* | */ + ADSB_EMITTER_TYPE_ULTRA_LIGHT=12, /* | */ + ADSB_EMITTER_TYPE_UNASSIGNED2=13, /* | */ + ADSB_EMITTER_TYPE_UAV=14, /* | */ + ADSB_EMITTER_TYPE_SPACE=15, /* | */ + ADSB_EMITTER_TYPE_UNASSGINED3=16, /* | */ + ADSB_EMITTER_TYPE_EMERGENCY_SURFACE=17, /* | */ + ADSB_EMITTER_TYPE_SERVICE_SURFACE=18, /* | */ + ADSB_EMITTER_TYPE_POINT_OBSTACLE=19, /* | */ + ADSB_EMITTER_TYPE_ENUM_END=20, /* | */ +} ADSB_EMITTER_TYPE; +#endif + +/** @brief These flags indicate status such as data validity of each data source. Set = data valid */ +#ifndef HAVE_ENUM_ADSB_FLAGS +#define HAVE_ENUM_ADSB_FLAGS +typedef enum ADSB_FLAGS +{ + ADSB_FLAGS_VALID_COORDS=1, /* | */ + ADSB_FLAGS_VALID_ALTITUDE=2, /* | */ + ADSB_FLAGS_VALID_HEADING=4, /* | */ + ADSB_FLAGS_VALID_VELOCITY=8, /* | */ + ADSB_FLAGS_VALID_CALLSIGN=16, /* | */ + ADSB_FLAGS_VALID_SQUAWK=32, /* | */ + ADSB_FLAGS_SIMULATED=64, /* | */ + ADSB_FLAGS_ENUM_END=65, /* | */ +} ADSB_FLAGS; +#endif + +/** @brief Bitmask of options for the MAV_CMD_DO_REPOSITION */ +#ifndef HAVE_ENUM_MAV_DO_REPOSITION_FLAGS +#define HAVE_ENUM_MAV_DO_REPOSITION_FLAGS +typedef enum MAV_DO_REPOSITION_FLAGS +{ + MAV_DO_REPOSITION_FLAGS_CHANGE_MODE=1, /* The aircraft should immediately transition into guided. This should not be set for follow me applications | */ + MAV_DO_REPOSITION_FLAGS_ENUM_END=2, /* | */ +} MAV_DO_REPOSITION_FLAGS; +#endif + +/** @brief Flags in EKF_STATUS message */ +#ifndef HAVE_ENUM_ESTIMATOR_STATUS_FLAGS +#define HAVE_ENUM_ESTIMATOR_STATUS_FLAGS +typedef enum ESTIMATOR_STATUS_FLAGS +{ + ESTIMATOR_ATTITUDE=1, /* True if the attitude estimate is good | */ + ESTIMATOR_VELOCITY_HORIZ=2, /* True if the horizontal velocity estimate is good | */ + ESTIMATOR_VELOCITY_VERT=4, /* True if the vertical velocity estimate is good | */ + ESTIMATOR_POS_HORIZ_REL=8, /* True if the horizontal position (relative) estimate is good | */ + ESTIMATOR_POS_HORIZ_ABS=16, /* True if the horizontal position (absolute) estimate is good | */ + ESTIMATOR_POS_VERT_ABS=32, /* True if the vertical position (absolute) estimate is good | */ + ESTIMATOR_POS_VERT_AGL=64, /* True if the vertical position (above ground) estimate is good | */ + ESTIMATOR_CONST_POS_MODE=128, /* True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) | */ + ESTIMATOR_PRED_POS_HORIZ_REL=256, /* True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate | */ + ESTIMATOR_PRED_POS_HORIZ_ABS=512, /* True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate | */ + ESTIMATOR_GPS_GLITCH=1024, /* True if the EKF has detected a GPS glitch | */ + ESTIMATOR_STATUS_FLAGS_ENUM_END=1025, /* | */ +} ESTIMATOR_STATUS_FLAGS; +#endif + + + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_heartbeat.h" +#include "./mavlink_msg_sys_status.h" +#include "./mavlink_msg_system_time.h" +#include "./mavlink_msg_ping.h" +#include "./mavlink_msg_change_operator_control.h" +#include "./mavlink_msg_change_operator_control_ack.h" +#include "./mavlink_msg_auth_key.h" +#include "./mavlink_msg_set_mode.h" +#include "./mavlink_msg_param_request_read.h" +#include "./mavlink_msg_param_request_list.h" +#include "./mavlink_msg_param_value.h" +#include "./mavlink_msg_param_set.h" +#include "./mavlink_msg_gps_raw_int.h" +#include "./mavlink_msg_gps_status.h" +#include "./mavlink_msg_scaled_imu.h" +#include "./mavlink_msg_raw_imu.h" +#include "./mavlink_msg_raw_pressure.h" +#include "./mavlink_msg_scaled_pressure.h" +#include "./mavlink_msg_attitude.h" +#include "./mavlink_msg_attitude_quaternion.h" +#include "./mavlink_msg_local_position_ned.h" +#include "./mavlink_msg_global_position_int.h" +#include "./mavlink_msg_rc_channels_scaled.h" +#include "./mavlink_msg_rc_channels_raw.h" +#include "./mavlink_msg_servo_output_raw.h" +#include "./mavlink_msg_mission_request_partial_list.h" +#include "./mavlink_msg_mission_write_partial_list.h" +#include "./mavlink_msg_mission_item.h" +#include "./mavlink_msg_mission_request.h" +#include "./mavlink_msg_mission_set_current.h" +#include "./mavlink_msg_mission_current.h" +#include "./mavlink_msg_mission_request_list.h" +#include "./mavlink_msg_mission_count.h" +#include "./mavlink_msg_mission_clear_all.h" +#include "./mavlink_msg_mission_item_reached.h" +#include "./mavlink_msg_mission_ack.h" +#include "./mavlink_msg_set_gps_global_origin.h" +#include "./mavlink_msg_gps_global_origin.h" +#include "./mavlink_msg_param_map_rc.h" +#include "./mavlink_msg_mission_request_int.h" +#include "./mavlink_msg_safety_set_allowed_area.h" +#include "./mavlink_msg_safety_allowed_area.h" +#include "./mavlink_msg_attitude_quaternion_cov.h" +#include "./mavlink_msg_nav_controller_output.h" +#include "./mavlink_msg_global_position_int_cov.h" +#include "./mavlink_msg_local_position_ned_cov.h" +#include "./mavlink_msg_rc_channels.h" +#include "./mavlink_msg_request_data_stream.h" +#include "./mavlink_msg_data_stream.h" +#include "./mavlink_msg_manual_control.h" +#include "./mavlink_msg_rc_channels_override.h" +#include "./mavlink_msg_mission_item_int.h" +#include "./mavlink_msg_vfr_hud.h" +#include "./mavlink_msg_command_int.h" +#include "./mavlink_msg_command_long.h" +#include "./mavlink_msg_command_ack.h" +#include "./mavlink_msg_manual_setpoint.h" +#include "./mavlink_msg_set_attitude_target.h" +#include "./mavlink_msg_attitude_target.h" +#include "./mavlink_msg_set_position_target_local_ned.h" +#include "./mavlink_msg_position_target_local_ned.h" +#include "./mavlink_msg_set_position_target_global_int.h" +#include "./mavlink_msg_position_target_global_int.h" +#include "./mavlink_msg_local_position_ned_system_global_offset.h" +#include "./mavlink_msg_hil_state.h" +#include "./mavlink_msg_hil_controls.h" +#include "./mavlink_msg_hil_rc_inputs_raw.h" +#include "./mavlink_msg_optical_flow.h" +#include "./mavlink_msg_global_vision_position_estimate.h" +#include "./mavlink_msg_vision_position_estimate.h" +#include "./mavlink_msg_vision_speed_estimate.h" +#include "./mavlink_msg_vicon_position_estimate.h" +#include "./mavlink_msg_highres_imu.h" +#include "./mavlink_msg_optical_flow_rad.h" +#include "./mavlink_msg_hil_sensor.h" +#include "./mavlink_msg_sim_state.h" +#include "./mavlink_msg_radio_status.h" +#include "./mavlink_msg_file_transfer_protocol.h" +#include "./mavlink_msg_timesync.h" +#include "./mavlink_msg_camera_trigger.h" +#include "./mavlink_msg_hil_gps.h" +#include "./mavlink_msg_hil_optical_flow.h" +#include "./mavlink_msg_hil_state_quaternion.h" +#include "./mavlink_msg_scaled_imu2.h" +#include "./mavlink_msg_log_request_list.h" +#include "./mavlink_msg_log_entry.h" +#include "./mavlink_msg_log_request_data.h" +#include "./mavlink_msg_log_data.h" +#include "./mavlink_msg_log_erase.h" +#include "./mavlink_msg_log_request_end.h" +#include "./mavlink_msg_gps_inject_data.h" +#include "./mavlink_msg_gps2_raw.h" +#include "./mavlink_msg_power_status.h" +#include "./mavlink_msg_serial_control.h" +#include "./mavlink_msg_gps_rtk.h" +#include "./mavlink_msg_gps2_rtk.h" +#include "./mavlink_msg_scaled_imu3.h" +#include "./mavlink_msg_data_transmission_handshake.h" +#include "./mavlink_msg_encapsulated_data.h" +#include "./mavlink_msg_distance_sensor.h" +#include "./mavlink_msg_terrain_request.h" +#include "./mavlink_msg_terrain_data.h" +#include "./mavlink_msg_terrain_check.h" +#include "./mavlink_msg_terrain_report.h" +#include "./mavlink_msg_scaled_pressure2.h" +#include "./mavlink_msg_att_pos_mocap.h" +#include "./mavlink_msg_set_actuator_control_target.h" +#include "./mavlink_msg_actuator_control_target.h" +#include "./mavlink_msg_altitude.h" +#include "./mavlink_msg_resource_request.h" +#include "./mavlink_msg_scaled_pressure3.h" +#include "./mavlink_msg_follow_target.h" +#include "./mavlink_msg_control_system_state.h" +#include "./mavlink_msg_battery_status.h" +#include "./mavlink_msg_autopilot_version.h" +#include "./mavlink_msg_landing_target.h" +#include "./mavlink_msg_estimator_status.h" +#include "./mavlink_msg_wind_cov.h" +#include "./mavlink_msg_vibration.h" +#include "./mavlink_msg_home_position.h" +#include "./mavlink_msg_set_home_position.h" +#include "./mavlink_msg_message_interval.h" +#include "./mavlink_msg_extended_sys_state.h" +#include "./mavlink_msg_adsb_vehicle.h" +#include "./mavlink_msg_v2_extension.h" +#include "./mavlink_msg_memory_vect.h" +#include "./mavlink_msg_debug_vect.h" +#include "./mavlink_msg_named_value_float.h" +#include "./mavlink_msg_named_value_int.h" +#include "./mavlink_msg_statustext.h" +#include "./mavlink_msg_debug.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // MAVLINK_COMMON_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink.h new file mode 100644 index 0000000..f92b2b2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink.h @@ -0,0 +1,27 @@ +/** @file + * @brief MAVLink comm protocol built from common.xml + * @see http://mavlink.org + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#ifndef MAVLINK_STX +#define MAVLINK_STX 254 +#endif + +#ifndef MAVLINK_ENDIAN +#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN +#endif + +#ifndef MAVLINK_ALIGNED_FIELDS +#define MAVLINK_ALIGNED_FIELDS 1 +#endif + +#ifndef MAVLINK_CRC_EXTRA +#define MAVLINK_CRC_EXTRA 1 +#endif + +#include "version.h" +#include "common.h" + +#endif // MAVLINK_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_actuator_control_target.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_actuator_control_target.h new file mode 100644 index 0000000..6b939bd --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_actuator_control_target.h @@ -0,0 +1,249 @@ +// MESSAGE ACTUATOR_CONTROL_TARGET PACKING + +#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET 140 + +typedef struct __mavlink_actuator_control_target_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/ + uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/ +} mavlink_actuator_control_target_t; + +#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN 41 +#define MAVLINK_MSG_ID_140_LEN 41 + +#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC 181 +#define MAVLINK_MSG_ID_140_CRC 181 + +#define MAVLINK_MSG_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS_LEN 8 + +#define MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET { \ + "ACTUATOR_CONTROL_TARGET", \ + 3, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \ + { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \ + { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \ + } \ +} + + +/** + * @brief Pack a actuator_control_target message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t group_mlx, const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_float_array(buf, 8, controls, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#else + mavlink_actuator_control_target_t packet; + packet.time_usec = time_usec; + packet.group_mlx = group_mlx; + mav_array_memcpy(packet.controls, controls, sizeof(float)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif +} + +/** + * @brief Pack a actuator_control_target message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t group_mlx,const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_float_array(buf, 8, controls, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#else + mavlink_actuator_control_target_t packet; + packet.time_usec = time_usec; + packet.group_mlx = group_mlx; + mav_array_memcpy(packet.controls, controls, sizeof(float)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif +} + +/** + * @brief Encode a actuator_control_target struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param actuator_control_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_actuator_control_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target) +{ + return mavlink_msg_actuator_control_target_pack(system_id, component_id, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); +} + +/** + * @brief Encode a actuator_control_target struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param actuator_control_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_actuator_control_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target) +{ + return mavlink_msg_actuator_control_target_pack_chan(system_id, component_id, chan, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); +} + +/** + * @brief Send a actuator_control_target message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_actuator_control_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_float_array(buf, 8, controls, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#else + mavlink_actuator_control_target_t packet; + packet.time_usec = time_usec; + packet.group_mlx = group_mlx; + mav_array_memcpy(packet.controls, controls, sizeof(float)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_actuator_control_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_float_array(buf, 8, controls, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#else + mavlink_actuator_control_target_t *packet = (mavlink_actuator_control_target_t *)msgbuf; + packet->time_usec = time_usec; + packet->group_mlx = group_mlx; + mav_array_memcpy(packet->controls, controls, sizeof(float)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ACTUATOR_CONTROL_TARGET UNPACKING + + +/** + * @brief Get field time_usec from actuator_control_target message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_actuator_control_target_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field group_mlx from actuator_control_target message + * + * @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + */ +static inline uint8_t mavlink_msg_actuator_control_target_get_group_mlx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 40); +} + +/** + * @brief Get field controls from actuator_control_target message + * + * @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + */ +static inline uint16_t mavlink_msg_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls) +{ + return _MAV_RETURN_float_array(msg, controls, 8, 8); +} + +/** + * @brief Decode a actuator_control_target message into a struct + * + * @param msg The message to decode + * @param actuator_control_target C-struct to decode the message contents into + */ +static inline void mavlink_msg_actuator_control_target_decode(const mavlink_message_t* msg, mavlink_actuator_control_target_t* actuator_control_target) +{ +#if MAVLINK_NEED_BYTE_SWAP + actuator_control_target->time_usec = mavlink_msg_actuator_control_target_get_time_usec(msg); + mavlink_msg_actuator_control_target_get_controls(msg, actuator_control_target->controls); + actuator_control_target->group_mlx = mavlink_msg_actuator_control_target_get_group_mlx(msg); +#else + memcpy(actuator_control_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_adsb_vehicle.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_adsb_vehicle.h new file mode 100644 index 0000000..9d1d40b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_adsb_vehicle.h @@ -0,0 +1,489 @@ +// MESSAGE ADSB_VEHICLE PACKING + +#define MAVLINK_MSG_ID_ADSB_VEHICLE 246 + +typedef struct __mavlink_adsb_vehicle_t +{ + uint32_t ICAO_address; /*< ICAO address*/ + int32_t lat; /*< Latitude, expressed as degrees * 1E7*/ + int32_t lon; /*< Longitude, expressed as degrees * 1E7*/ + int32_t altitude; /*< Altitude(ASL) in millimeters*/ + uint16_t heading; /*< Course over ground in centidegrees*/ + uint16_t hor_velocity; /*< The horizontal velocity in centimeters/second*/ + int16_t ver_velocity; /*< The vertical velocity in centimeters/second, positive is up*/ + uint16_t flags; /*< Flags to indicate various statuses including valid data fields*/ + uint16_t squawk; /*< Squawk code*/ + uint8_t altitude_type; /*< Type from ADSB_ALTITUDE_TYPE enum*/ + char callsign[9]; /*< The callsign, 8+null*/ + uint8_t emitter_type; /*< Type from ADSB_EMITTER_TYPE enum*/ + uint8_t tslc; /*< Time since last communication in seconds*/ +} mavlink_adsb_vehicle_t; + +#define MAVLINK_MSG_ID_ADSB_VEHICLE_LEN 38 +#define MAVLINK_MSG_ID_246_LEN 38 + +#define MAVLINK_MSG_ID_ADSB_VEHICLE_CRC 184 +#define MAVLINK_MSG_ID_246_CRC 184 + +#define MAVLINK_MSG_ADSB_VEHICLE_FIELD_CALLSIGN_LEN 9 + +#define MAVLINK_MESSAGE_INFO_ADSB_VEHICLE { \ + "ADSB_VEHICLE", \ + 13, \ + { { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \ + { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \ + { "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \ + { "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \ + { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \ + { "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \ + { "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \ + { "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \ + { "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \ + } \ +} + + +/** + * @brief Pack a adsb_vehicle message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param ICAO_address ICAO address + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param altitude_type Type from ADSB_ALTITUDE_TYPE enum + * @param altitude Altitude(ASL) in millimeters + * @param heading Course over ground in centidegrees + * @param hor_velocity The horizontal velocity in centimeters/second + * @param ver_velocity The vertical velocity in centimeters/second, positive is up + * @param callsign The callsign, 8+null + * @param emitter_type Type from ADSB_EMITTER_TYPE enum + * @param tslc Time since last communication in seconds + * @param flags Flags to indicate various statuses including valid data fields + * @param squawk Squawk code + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_adsb_vehicle_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN]; + _mav_put_uint32_t(buf, 0, ICAO_address); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, altitude); + _mav_put_uint16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, hor_velocity); + _mav_put_int16_t(buf, 20, ver_velocity); + _mav_put_uint16_t(buf, 22, flags); + _mav_put_uint16_t(buf, 24, squawk); + _mav_put_uint8_t(buf, 26, altitude_type); + _mav_put_uint8_t(buf, 36, emitter_type); + _mav_put_uint8_t(buf, 37, tslc); + _mav_put_char_array(buf, 27, callsign, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#else + mavlink_adsb_vehicle_t packet; + packet.ICAO_address = ICAO_address; + packet.lat = lat; + packet.lon = lon; + packet.altitude = altitude; + packet.heading = heading; + packet.hor_velocity = hor_velocity; + packet.ver_velocity = ver_velocity; + packet.flags = flags; + packet.squawk = squawk; + packet.altitude_type = altitude_type; + packet.emitter_type = emitter_type; + packet.tslc = tslc; + mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ADSB_VEHICLE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif +} + +/** + * @brief Pack a adsb_vehicle message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param ICAO_address ICAO address + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param altitude_type Type from ADSB_ALTITUDE_TYPE enum + * @param altitude Altitude(ASL) in millimeters + * @param heading Course over ground in centidegrees + * @param hor_velocity The horizontal velocity in centimeters/second + * @param ver_velocity The vertical velocity in centimeters/second, positive is up + * @param callsign The callsign, 8+null + * @param emitter_type Type from ADSB_EMITTER_TYPE enum + * @param tslc Time since last communication in seconds + * @param flags Flags to indicate various statuses including valid data fields + * @param squawk Squawk code + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_adsb_vehicle_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t ICAO_address,int32_t lat,int32_t lon,uint8_t altitude_type,int32_t altitude,uint16_t heading,uint16_t hor_velocity,int16_t ver_velocity,const char *callsign,uint8_t emitter_type,uint8_t tslc,uint16_t flags,uint16_t squawk) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN]; + _mav_put_uint32_t(buf, 0, ICAO_address); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, altitude); + _mav_put_uint16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, hor_velocity); + _mav_put_int16_t(buf, 20, ver_velocity); + _mav_put_uint16_t(buf, 22, flags); + _mav_put_uint16_t(buf, 24, squawk); + _mav_put_uint8_t(buf, 26, altitude_type); + _mav_put_uint8_t(buf, 36, emitter_type); + _mav_put_uint8_t(buf, 37, tslc); + _mav_put_char_array(buf, 27, callsign, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#else + mavlink_adsb_vehicle_t packet; + packet.ICAO_address = ICAO_address; + packet.lat = lat; + packet.lon = lon; + packet.altitude = altitude; + packet.heading = heading; + packet.hor_velocity = hor_velocity; + packet.ver_velocity = ver_velocity; + packet.flags = flags; + packet.squawk = squawk; + packet.altitude_type = altitude_type; + packet.emitter_type = emitter_type; + packet.tslc = tslc; + mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ADSB_VEHICLE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif +} + +/** + * @brief Encode a adsb_vehicle struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param adsb_vehicle C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_adsb_vehicle_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adsb_vehicle_t* adsb_vehicle) +{ + return mavlink_msg_adsb_vehicle_pack(system_id, component_id, msg, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk); +} + +/** + * @brief Encode a adsb_vehicle struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param adsb_vehicle C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_adsb_vehicle_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adsb_vehicle_t* adsb_vehicle) +{ + return mavlink_msg_adsb_vehicle_pack_chan(system_id, component_id, chan, msg, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk); +} + +/** + * @brief Send a adsb_vehicle message + * @param chan MAVLink channel to send the message + * + * @param ICAO_address ICAO address + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param altitude_type Type from ADSB_ALTITUDE_TYPE enum + * @param altitude Altitude(ASL) in millimeters + * @param heading Course over ground in centidegrees + * @param hor_velocity The horizontal velocity in centimeters/second + * @param ver_velocity The vertical velocity in centimeters/second, positive is up + * @param callsign The callsign, 8+null + * @param emitter_type Type from ADSB_EMITTER_TYPE enum + * @param tslc Time since last communication in seconds + * @param flags Flags to indicate various statuses including valid data fields + * @param squawk Squawk code + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_adsb_vehicle_send(mavlink_channel_t chan, uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN]; + _mav_put_uint32_t(buf, 0, ICAO_address); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, altitude); + _mav_put_uint16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, hor_velocity); + _mav_put_int16_t(buf, 20, ver_velocity); + _mav_put_uint16_t(buf, 22, flags); + _mav_put_uint16_t(buf, 24, squawk); + _mav_put_uint8_t(buf, 26, altitude_type); + _mav_put_uint8_t(buf, 36, emitter_type); + _mav_put_uint8_t(buf, 37, tslc); + _mav_put_char_array(buf, 27, callsign, 9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif +#else + mavlink_adsb_vehicle_t packet; + packet.ICAO_address = ICAO_address; + packet.lat = lat; + packet.lon = lon; + packet.altitude = altitude; + packet.heading = heading; + packet.hor_velocity = hor_velocity; + packet.ver_velocity = ver_velocity; + packet.flags = flags; + packet.squawk = squawk; + packet.altitude_type = altitude_type; + packet.emitter_type = emitter_type; + packet.tslc = tslc; + mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)&packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)&packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ADSB_VEHICLE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_adsb_vehicle_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, ICAO_address); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, altitude); + _mav_put_uint16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, hor_velocity); + _mav_put_int16_t(buf, 20, ver_velocity); + _mav_put_uint16_t(buf, 22, flags); + _mav_put_uint16_t(buf, 24, squawk); + _mav_put_uint8_t(buf, 26, altitude_type); + _mav_put_uint8_t(buf, 36, emitter_type); + _mav_put_uint8_t(buf, 37, tslc); + _mav_put_char_array(buf, 27, callsign, 9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif +#else + mavlink_adsb_vehicle_t *packet = (mavlink_adsb_vehicle_t *)msgbuf; + packet->ICAO_address = ICAO_address; + packet->lat = lat; + packet->lon = lon; + packet->altitude = altitude; + packet->heading = heading; + packet->hor_velocity = hor_velocity; + packet->ver_velocity = ver_velocity; + packet->flags = flags; + packet->squawk = squawk; + packet->altitude_type = altitude_type; + packet->emitter_type = emitter_type; + packet->tslc = tslc; + mav_array_memcpy(packet->callsign, callsign, sizeof(char)*9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ADSB_VEHICLE UNPACKING + + +/** + * @brief Get field ICAO_address from adsb_vehicle message + * + * @return ICAO address + */ +static inline uint32_t mavlink_msg_adsb_vehicle_get_ICAO_address(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field lat from adsb_vehicle message + * + * @return Latitude, expressed as degrees * 1E7 + */ +static inline int32_t mavlink_msg_adsb_vehicle_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field lon from adsb_vehicle message + * + * @return Longitude, expressed as degrees * 1E7 + */ +static inline int32_t mavlink_msg_adsb_vehicle_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field altitude_type from adsb_vehicle message + * + * @return Type from ADSB_ALTITUDE_TYPE enum + */ +static inline uint8_t mavlink_msg_adsb_vehicle_get_altitude_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 26); +} + +/** + * @brief Get field altitude from adsb_vehicle message + * + * @return Altitude(ASL) in millimeters + */ +static inline int32_t mavlink_msg_adsb_vehicle_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field heading from adsb_vehicle message + * + * @return Course over ground in centidegrees + */ +static inline uint16_t mavlink_msg_adsb_vehicle_get_heading(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field hor_velocity from adsb_vehicle message + * + * @return The horizontal velocity in centimeters/second + */ +static inline uint16_t mavlink_msg_adsb_vehicle_get_hor_velocity(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field ver_velocity from adsb_vehicle message + * + * @return The vertical velocity in centimeters/second, positive is up + */ +static inline int16_t mavlink_msg_adsb_vehicle_get_ver_velocity(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field callsign from adsb_vehicle message + * + * @return The callsign, 8+null + */ +static inline uint16_t mavlink_msg_adsb_vehicle_get_callsign(const mavlink_message_t* msg, char *callsign) +{ + return _MAV_RETURN_char_array(msg, callsign, 9, 27); +} + +/** + * @brief Get field emitter_type from adsb_vehicle message + * + * @return Type from ADSB_EMITTER_TYPE enum + */ +static inline uint8_t mavlink_msg_adsb_vehicle_get_emitter_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Get field tslc from adsb_vehicle message + * + * @return Time since last communication in seconds + */ +static inline uint8_t mavlink_msg_adsb_vehicle_get_tslc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 37); +} + +/** + * @brief Get field flags from adsb_vehicle message + * + * @return Flags to indicate various statuses including valid data fields + */ +static inline uint16_t mavlink_msg_adsb_vehicle_get_flags(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field squawk from adsb_vehicle message + * + * @return Squawk code + */ +static inline uint16_t mavlink_msg_adsb_vehicle_get_squawk(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Decode a adsb_vehicle message into a struct + * + * @param msg The message to decode + * @param adsb_vehicle C-struct to decode the message contents into + */ +static inline void mavlink_msg_adsb_vehicle_decode(const mavlink_message_t* msg, mavlink_adsb_vehicle_t* adsb_vehicle) +{ +#if MAVLINK_NEED_BYTE_SWAP + adsb_vehicle->ICAO_address = mavlink_msg_adsb_vehicle_get_ICAO_address(msg); + adsb_vehicle->lat = mavlink_msg_adsb_vehicle_get_lat(msg); + adsb_vehicle->lon = mavlink_msg_adsb_vehicle_get_lon(msg); + adsb_vehicle->altitude = mavlink_msg_adsb_vehicle_get_altitude(msg); + adsb_vehicle->heading = mavlink_msg_adsb_vehicle_get_heading(msg); + adsb_vehicle->hor_velocity = mavlink_msg_adsb_vehicle_get_hor_velocity(msg); + adsb_vehicle->ver_velocity = mavlink_msg_adsb_vehicle_get_ver_velocity(msg); + adsb_vehicle->flags = mavlink_msg_adsb_vehicle_get_flags(msg); + adsb_vehicle->squawk = mavlink_msg_adsb_vehicle_get_squawk(msg); + adsb_vehicle->altitude_type = mavlink_msg_adsb_vehicle_get_altitude_type(msg); + mavlink_msg_adsb_vehicle_get_callsign(msg, adsb_vehicle->callsign); + adsb_vehicle->emitter_type = mavlink_msg_adsb_vehicle_get_emitter_type(msg); + adsb_vehicle->tslc = mavlink_msg_adsb_vehicle_get_tslc(msg); +#else + memcpy(adsb_vehicle, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_altitude.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_altitude.h new file mode 100644 index 0000000..2ed8cb8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_altitude.h @@ -0,0 +1,353 @@ +// MESSAGE ALTITUDE PACKING + +#define MAVLINK_MSG_ID_ALTITUDE 141 + +typedef struct __mavlink_altitude_t +{ + uint64_t time_usec; /*< Timestamp (milliseconds since system boot)*/ + float altitude_monotonic; /*< This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.*/ + float altitude_amsl; /*< This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.*/ + float altitude_local; /*< This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.*/ + float altitude_relative; /*< This is the altitude above the home position. It resets on each change of the current home position.*/ + float altitude_terrain; /*< This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.*/ + float bottom_clearance; /*< This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.*/ +} mavlink_altitude_t; + +#define MAVLINK_MSG_ID_ALTITUDE_LEN 32 +#define MAVLINK_MSG_ID_141_LEN 32 + +#define MAVLINK_MSG_ID_ALTITUDE_CRC 47 +#define MAVLINK_MSG_ID_141_CRC 47 + + + +#define MAVLINK_MESSAGE_INFO_ALTITUDE { \ + "ALTITUDE", \ + 7, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_altitude_t, time_usec) }, \ + { "altitude_monotonic", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_altitude_t, altitude_monotonic) }, \ + { "altitude_amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_altitude_t, altitude_amsl) }, \ + { "altitude_local", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_altitude_t, altitude_local) }, \ + { "altitude_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_altitude_t, altitude_relative) }, \ + { "altitude_terrain", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_altitude_t, altitude_terrain) }, \ + { "bottom_clearance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_altitude_t, bottom_clearance) }, \ + } \ +} + + +/** + * @brief Pack a altitude message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (milliseconds since system boot) + * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. + * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position. + * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ALTITUDE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, altitude_monotonic); + _mav_put_float(buf, 12, altitude_amsl); + _mav_put_float(buf, 16, altitude_local); + _mav_put_float(buf, 20, altitude_relative); + _mav_put_float(buf, 24, altitude_terrain); + _mav_put_float(buf, 28, bottom_clearance); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN); +#else + mavlink_altitude_t packet; + packet.time_usec = time_usec; + packet.altitude_monotonic = altitude_monotonic; + packet.altitude_amsl = altitude_amsl; + packet.altitude_local = altitude_local; + packet.altitude_relative = altitude_relative; + packet.altitude_terrain = altitude_terrain; + packet.bottom_clearance = bottom_clearance; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ALTITUDE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif +} + +/** + * @brief Pack a altitude message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (milliseconds since system boot) + * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. + * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position. + * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float altitude_monotonic,float altitude_amsl,float altitude_local,float altitude_relative,float altitude_terrain,float bottom_clearance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ALTITUDE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, altitude_monotonic); + _mav_put_float(buf, 12, altitude_amsl); + _mav_put_float(buf, 16, altitude_local); + _mav_put_float(buf, 20, altitude_relative); + _mav_put_float(buf, 24, altitude_terrain); + _mav_put_float(buf, 28, bottom_clearance); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN); +#else + mavlink_altitude_t packet; + packet.time_usec = time_usec; + packet.altitude_monotonic = altitude_monotonic; + packet.altitude_amsl = altitude_amsl; + packet.altitude_local = altitude_local; + packet.altitude_relative = altitude_relative; + packet.altitude_terrain = altitude_terrain; + packet.bottom_clearance = bottom_clearance; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ALTITUDE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif +} + +/** + * @brief Encode a altitude struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param altitude C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_altitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_altitude_t* altitude) +{ + return mavlink_msg_altitude_pack(system_id, component_id, msg, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance); +} + +/** + * @brief Encode a altitude struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param altitude C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_altitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_altitude_t* altitude) +{ + return mavlink_msg_altitude_pack_chan(system_id, component_id, chan, msg, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance); +} + +/** + * @brief Send a altitude message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (milliseconds since system boot) + * @param altitude_monotonic This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + * @param altitude_amsl This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. + * @param altitude_local This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + * @param altitude_relative This is the altitude above the home position. It resets on each change of the current home position. + * @param altitude_terrain This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + * @param bottom_clearance This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_altitude_send(mavlink_channel_t chan, uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ALTITUDE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, altitude_monotonic); + _mav_put_float(buf, 12, altitude_amsl); + _mav_put_float(buf, 16, altitude_local); + _mav_put_float(buf, 20, altitude_relative); + _mav_put_float(buf, 24, altitude_terrain); + _mav_put_float(buf, 28, bottom_clearance); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif +#else + mavlink_altitude_t packet; + packet.time_usec = time_usec; + packet.altitude_monotonic = altitude_monotonic; + packet.altitude_amsl = altitude_amsl; + packet.altitude_local = altitude_local; + packet.altitude_relative = altitude_relative; + packet.altitude_terrain = altitude_terrain; + packet.bottom_clearance = bottom_clearance; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ALTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_altitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, altitude_monotonic); + _mav_put_float(buf, 12, altitude_amsl); + _mav_put_float(buf, 16, altitude_local); + _mav_put_float(buf, 20, altitude_relative); + _mav_put_float(buf, 24, altitude_terrain); + _mav_put_float(buf, 28, bottom_clearance); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif +#else + mavlink_altitude_t *packet = (mavlink_altitude_t *)msgbuf; + packet->time_usec = time_usec; + packet->altitude_monotonic = altitude_monotonic; + packet->altitude_amsl = altitude_amsl; + packet->altitude_local = altitude_local; + packet->altitude_relative = altitude_relative; + packet->altitude_terrain = altitude_terrain; + packet->bottom_clearance = bottom_clearance; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)packet, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)packet, MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ALTITUDE UNPACKING + + +/** + * @brief Get field time_usec from altitude message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint64_t mavlink_msg_altitude_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field altitude_monotonic from altitude message + * + * @return This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + */ +static inline float mavlink_msg_altitude_get_altitude_monotonic(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field altitude_amsl from altitude message + * + * @return This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. + */ +static inline float mavlink_msg_altitude_get_altitude_amsl(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field altitude_local from altitude message + * + * @return This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + */ +static inline float mavlink_msg_altitude_get_altitude_local(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field altitude_relative from altitude message + * + * @return This is the altitude above the home position. It resets on each change of the current home position. + */ +static inline float mavlink_msg_altitude_get_altitude_relative(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field altitude_terrain from altitude message + * + * @return This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + */ +static inline float mavlink_msg_altitude_get_altitude_terrain(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field bottom_clearance from altitude message + * + * @return This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + */ +static inline float mavlink_msg_altitude_get_bottom_clearance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a altitude message into a struct + * + * @param msg The message to decode + * @param altitude C-struct to decode the message contents into + */ +static inline void mavlink_msg_altitude_decode(const mavlink_message_t* msg, mavlink_altitude_t* altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP + altitude->time_usec = mavlink_msg_altitude_get_time_usec(msg); + altitude->altitude_monotonic = mavlink_msg_altitude_get_altitude_monotonic(msg); + altitude->altitude_amsl = mavlink_msg_altitude_get_altitude_amsl(msg); + altitude->altitude_local = mavlink_msg_altitude_get_altitude_local(msg); + altitude->altitude_relative = mavlink_msg_altitude_get_altitude_relative(msg); + altitude->altitude_terrain = mavlink_msg_altitude_get_altitude_terrain(msg); + altitude->bottom_clearance = mavlink_msg_altitude_get_bottom_clearance(msg); +#else + memcpy(altitude, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ALTITUDE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_att_pos_mocap.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_att_pos_mocap.h new file mode 100644 index 0000000..581a243 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_att_pos_mocap.h @@ -0,0 +1,297 @@ +// MESSAGE ATT_POS_MOCAP PACKING + +#define MAVLINK_MSG_ID_ATT_POS_MOCAP 138 + +typedef struct __mavlink_att_pos_mocap_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ + float x; /*< X position in meters (NED)*/ + float y; /*< Y position in meters (NED)*/ + float z; /*< Z position in meters (NED)*/ +} mavlink_att_pos_mocap_t; + +#define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN 36 +#define MAVLINK_MSG_ID_138_LEN 36 + +#define MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC 109 +#define MAVLINK_MSG_ID_138_CRC 109 + +#define MAVLINK_MSG_ATT_POS_MOCAP_FIELD_Q_LEN 4 + +#define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \ + "ATT_POS_MOCAP", \ + 5, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \ + { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \ + } \ +} + + +/** + * @brief Pack a att_pos_mocap message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param x X position in meters (NED) + * @param y Y position in meters (NED) + * @param z Z position in meters (NED) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, const float *q, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, x); + _mav_put_float(buf, 28, y); + _mav_put_float(buf, 32, z); + _mav_put_float_array(buf, 8, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#else + mavlink_att_pos_mocap_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif +} + +/** + * @brief Pack a att_pos_mocap message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param x X position in meters (NED) + * @param y Y position in meters (NED) + * @param z Z position in meters (NED) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_att_pos_mocap_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,const float *q,float x,float y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, x); + _mav_put_float(buf, 28, y); + _mav_put_float(buf, 32, z); + _mav_put_float_array(buf, 8, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#else + mavlink_att_pos_mocap_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif +} + +/** + * @brief Encode a att_pos_mocap struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param att_pos_mocap C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_att_pos_mocap_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap) +{ + return mavlink_msg_att_pos_mocap_pack(system_id, component_id, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z); +} + +/** + * @brief Encode a att_pos_mocap struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param att_pos_mocap C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_att_pos_mocap_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap) +{ + return mavlink_msg_att_pos_mocap_pack_chan(system_id, component_id, chan, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z); +} + +/** + * @brief Send a att_pos_mocap message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param x X position in meters (NED) + * @param y Y position in meters (NED) + * @param z Z position in meters (NED) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_att_pos_mocap_send(mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, x); + _mav_put_float(buf, 28, y); + _mav_put_float(buf, 32, z); + _mav_put_float_array(buf, 8, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif +#else + mavlink_att_pos_mocap_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + mav_array_memcpy(packet.q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)&packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)&packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_att_pos_mocap_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, x); + _mav_put_float(buf, 28, y); + _mav_put_float(buf, 32, z); + _mav_put_float_array(buf, 8, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif +#else + mavlink_att_pos_mocap_t *packet = (mavlink_att_pos_mocap_t *)msgbuf; + packet->time_usec = time_usec; + packet->x = x; + packet->y = y; + packet->z = z; + mav_array_memcpy(packet->q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ATT_POS_MOCAP UNPACKING + + +/** + * @brief Get field time_usec from att_pos_mocap message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_att_pos_mocap_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field q from att_pos_mocap message + * + * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + */ +static inline uint16_t mavlink_msg_att_pos_mocap_get_q(const mavlink_message_t* msg, float *q) +{ + return _MAV_RETURN_float_array(msg, q, 4, 8); +} + +/** + * @brief Get field x from att_pos_mocap message + * + * @return X position in meters (NED) + */ +static inline float mavlink_msg_att_pos_mocap_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field y from att_pos_mocap message + * + * @return Y position in meters (NED) + */ +static inline float mavlink_msg_att_pos_mocap_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field z from att_pos_mocap message + * + * @return Z position in meters (NED) + */ +static inline float mavlink_msg_att_pos_mocap_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Decode a att_pos_mocap message into a struct + * + * @param msg The message to decode + * @param att_pos_mocap C-struct to decode the message contents into + */ +static inline void mavlink_msg_att_pos_mocap_decode(const mavlink_message_t* msg, mavlink_att_pos_mocap_t* att_pos_mocap) +{ +#if MAVLINK_NEED_BYTE_SWAP + att_pos_mocap->time_usec = mavlink_msg_att_pos_mocap_get_time_usec(msg); + mavlink_msg_att_pos_mocap_get_q(msg, att_pos_mocap->q); + att_pos_mocap->x = mavlink_msg_att_pos_mocap_get_x(msg); + att_pos_mocap->y = mavlink_msg_att_pos_mocap_get_y(msg); + att_pos_mocap->z = mavlink_msg_att_pos_mocap_get_z(msg); +#else + memcpy(att_pos_mocap, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_attitude.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_attitude.h new file mode 100644 index 0000000..ca9f5ac --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_attitude.h @@ -0,0 +1,353 @@ +// MESSAGE ATTITUDE PACKING + +#define MAVLINK_MSG_ID_ATTITUDE 30 + +typedef struct __mavlink_attitude_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float roll; /*< Roll angle (rad, -pi..+pi)*/ + float pitch; /*< Pitch angle (rad, -pi..+pi)*/ + float yaw; /*< Yaw angle (rad, -pi..+pi)*/ + float rollspeed; /*< Roll angular speed (rad/s)*/ + float pitchspeed; /*< Pitch angular speed (rad/s)*/ + float yawspeed; /*< Yaw angular speed (rad/s)*/ +} mavlink_attitude_t; + +#define MAVLINK_MSG_ID_ATTITUDE_LEN 28 +#define MAVLINK_MSG_ID_30_LEN 28 + +#define MAVLINK_MSG_ID_ATTITUDE_CRC 39 +#define MAVLINK_MSG_ID_30_CRC 39 + + + +#define MAVLINK_MESSAGE_INFO_ATTITUDE { \ + "ATTITUDE", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \ + } \ +} + + +/** + * @brief Pack a attitude message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param roll Roll angle (rad, -pi..+pi) + * @param pitch Pitch angle (rad, -pi..+pi) + * @param yaw Yaw angle (rad, -pi..+pi) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, rollspeed); + _mav_put_float(buf, 20, pitchspeed); + _mav_put_float(buf, 24, yawspeed); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN); +#else + mavlink_attitude_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif +} + +/** + * @brief Pack a attitude message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param roll Roll angle (rad, -pi..+pi) + * @param pitch Pitch angle (rad, -pi..+pi) + * @param yaw Yaw angle (rad, -pi..+pi) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, rollspeed); + _mav_put_float(buf, 20, pitchspeed); + _mav_put_float(buf, 24, yawspeed); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN); +#else + mavlink_attitude_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif +} + +/** + * @brief Encode a attitude struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param attitude C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude) +{ + return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); +} + +/** + * @brief Encode a attitude struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param attitude C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_t* attitude) +{ + return mavlink_msg_attitude_pack_chan(system_id, component_id, chan, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); +} + +/** + * @brief Send a attitude message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param roll Roll angle (rad, -pi..+pi) + * @param pitch Pitch angle (rad, -pi..+pi) + * @param yaw Yaw angle (rad, -pi..+pi) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, rollspeed); + _mav_put_float(buf, 20, pitchspeed); + _mav_put_float(buf, 24, yawspeed); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif +#else + mavlink_attitude_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_attitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, rollspeed); + _mav_put_float(buf, 20, pitchspeed); + _mav_put_float(buf, 24, yawspeed); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif +#else + mavlink_attitude_t *packet = (mavlink_attitude_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + packet->rollspeed = rollspeed; + packet->pitchspeed = pitchspeed; + packet->yawspeed = yawspeed; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ATTITUDE UNPACKING + + +/** + * @brief Get field time_boot_ms from attitude message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field roll from attitude message + * + * @return Roll angle (rad, -pi..+pi) + */ +static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field pitch from attitude message + * + * @return Pitch angle (rad, -pi..+pi) + */ +static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from attitude message + * + * @return Yaw angle (rad, -pi..+pi) + */ +static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field rollspeed from attitude message + * + * @return Roll angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field pitchspeed from attitude message + * + * @return Pitch angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field yawspeed from attitude message + * + * @return Yaw angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a attitude message into a struct + * + * @param msg The message to decode + * @param attitude C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude) +{ +#if MAVLINK_NEED_BYTE_SWAP + attitude->time_boot_ms = mavlink_msg_attitude_get_time_boot_ms(msg); + attitude->roll = mavlink_msg_attitude_get_roll(msg); + attitude->pitch = mavlink_msg_attitude_get_pitch(msg); + attitude->yaw = mavlink_msg_attitude_get_yaw(msg); + attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg); + attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg); + attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg); +#else + memcpy(attitude, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h new file mode 100644 index 0000000..df362b4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h @@ -0,0 +1,377 @@ +// MESSAGE ATTITUDE_QUATERNION PACKING + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31 + +typedef struct __mavlink_attitude_quaternion_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float q1; /*< Quaternion component 1, w (1 in null-rotation)*/ + float q2; /*< Quaternion component 2, x (0 in null-rotation)*/ + float q3; /*< Quaternion component 3, y (0 in null-rotation)*/ + float q4; /*< Quaternion component 4, z (0 in null-rotation)*/ + float rollspeed; /*< Roll angular speed (rad/s)*/ + float pitchspeed; /*< Pitch angular speed (rad/s)*/ + float yawspeed; /*< Yaw angular speed (rad/s)*/ +} mavlink_attitude_quaternion_t; + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32 +#define MAVLINK_MSG_ID_31_LEN 32 + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246 +#define MAVLINK_MSG_ID_31_CRC 246 + + + +#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \ + "ATTITUDE_QUATERNION", \ + 8, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \ + { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \ + { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \ + { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \ + { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \ + } \ +} + + +/** + * @brief Pack a attitude_quaternion message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q1 Quaternion component 1, w (1 in null-rotation) + * @param q2 Quaternion component 2, x (0 in null-rotation) + * @param q3 Quaternion component 3, y (0 in null-rotation) + * @param q4 Quaternion component 4, z (0 in null-rotation) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, q1); + _mav_put_float(buf, 8, q2); + _mav_put_float(buf, 12, q3); + _mav_put_float(buf, 16, q4); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#else + mavlink_attitude_quaternion_t packet; + packet.time_boot_ms = time_boot_ms; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif +} + +/** + * @brief Pack a attitude_quaternion message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q1 Quaternion component 1, w (1 in null-rotation) + * @param q2 Quaternion component 2, x (0 in null-rotation) + * @param q3 Quaternion component 3, y (0 in null-rotation) + * @param q4 Quaternion component 4, z (0 in null-rotation) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, q1); + _mav_put_float(buf, 8, q2); + _mav_put_float(buf, 12, q3); + _mav_put_float(buf, 16, q4); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#else + mavlink_attitude_quaternion_t packet; + packet.time_boot_ms = time_boot_ms; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif +} + +/** + * @brief Encode a attitude_quaternion struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param attitude_quaternion C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion) +{ + return mavlink_msg_attitude_quaternion_pack(system_id, component_id, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed); +} + +/** + * @brief Encode a attitude_quaternion struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param attitude_quaternion C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion) +{ + return mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, chan, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed); +} + +/** + * @brief Send a attitude_quaternion message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q1 Quaternion component 1, w (1 in null-rotation) + * @param q2 Quaternion component 2, x (0 in null-rotation) + * @param q3 Quaternion component 3, y (0 in null-rotation) + * @param q4 Quaternion component 4, z (0 in null-rotation) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, q1); + _mav_put_float(buf, 8, q2); + _mav_put_float(buf, 12, q3); + _mav_put_float(buf, 16, q4); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif +#else + mavlink_attitude_quaternion_t packet; + packet.time_boot_ms = time_boot_ms; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, q1); + _mav_put_float(buf, 8, q2); + _mav_put_float(buf, 12, q3); + _mav_put_float(buf, 16, q4); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif +#else + mavlink_attitude_quaternion_t *packet = (mavlink_attitude_quaternion_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->q1 = q1; + packet->q2 = q2; + packet->q3 = q3; + packet->q4 = q4; + packet->rollspeed = rollspeed; + packet->pitchspeed = pitchspeed; + packet->yawspeed = yawspeed; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ATTITUDE_QUATERNION UNPACKING + + +/** + * @brief Get field time_boot_ms from attitude_quaternion message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field q1 from attitude_quaternion message + * + * @return Quaternion component 1, w (1 in null-rotation) + */ +static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field q2 from attitude_quaternion message + * + * @return Quaternion component 2, x (0 in null-rotation) + */ +static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field q3 from attitude_quaternion message + * + * @return Quaternion component 3, y (0 in null-rotation) + */ +static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field q4 from attitude_quaternion message + * + * @return Quaternion component 4, z (0 in null-rotation) + */ +static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field rollspeed from attitude_quaternion message + * + * @return Roll angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitchspeed from attitude_quaternion message + * + * @return Pitch angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yawspeed from attitude_quaternion message + * + * @return Yaw angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a attitude_quaternion message into a struct + * + * @param msg The message to decode + * @param attitude_quaternion C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_t* attitude_quaternion) +{ +#if MAVLINK_NEED_BYTE_SWAP + attitude_quaternion->time_boot_ms = mavlink_msg_attitude_quaternion_get_time_boot_ms(msg); + attitude_quaternion->q1 = mavlink_msg_attitude_quaternion_get_q1(msg); + attitude_quaternion->q2 = mavlink_msg_attitude_quaternion_get_q2(msg); + attitude_quaternion->q3 = mavlink_msg_attitude_quaternion_get_q3(msg); + attitude_quaternion->q4 = mavlink_msg_attitude_quaternion_get_q4(msg); + attitude_quaternion->rollspeed = mavlink_msg_attitude_quaternion_get_rollspeed(msg); + attitude_quaternion->pitchspeed = mavlink_msg_attitude_quaternion_get_pitchspeed(msg); + attitude_quaternion->yawspeed = mavlink_msg_attitude_quaternion_get_yawspeed(msg); +#else + memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_attitude_quaternion_cov.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_attitude_quaternion_cov.h new file mode 100644 index 0000000..dc99d9d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_attitude_quaternion_cov.h @@ -0,0 +1,322 @@ +// MESSAGE ATTITUDE_QUATERNION_COV PACKING + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV 61 + +typedef struct __mavlink_attitude_quaternion_cov_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)*/ + float rollspeed; /*< Roll angular speed (rad/s)*/ + float pitchspeed; /*< Pitch angular speed (rad/s)*/ + float yawspeed; /*< Yaw angular speed (rad/s)*/ + float covariance[9]; /*< Attitude covariance*/ +} mavlink_attitude_quaternion_cov_t; + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN 68 +#define MAVLINK_MSG_ID_61_LEN 68 + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC 153 +#define MAVLINK_MSG_ID_61_CRC 153 + +#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_Q_LEN 4 +#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_COVARIANCE_LEN 9 + +#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV { \ + "ATTITUDE_QUATERNION_COV", \ + 6, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_boot_ms) }, \ + { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \ + { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 32, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \ + } \ +} + + +/** + * @brief Pack a attitude_quaternion_cov message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @param covariance Attitude covariance + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_float_array(buf, 4, q, 4); + _mav_put_float_array(buf, 32, covariance, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#else + mavlink_attitude_quaternion_cov_t packet; + packet.time_boot_ms = time_boot_ms; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif +} + +/** + * @brief Pack a attitude_quaternion_cov message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @param covariance Attitude covariance + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,const float *q,float rollspeed,float pitchspeed,float yawspeed,const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_float_array(buf, 4, q, 4); + _mav_put_float_array(buf, 32, covariance, 9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#else + mavlink_attitude_quaternion_cov_t packet; + packet.time_boot_ms = time_boot_ms; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif +} + +/** + * @brief Encode a attitude_quaternion_cov struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param attitude_quaternion_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) +{ + return mavlink_msg_attitude_quaternion_cov_pack(system_id, component_id, msg, attitude_quaternion_cov->time_boot_ms, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance); +} + +/** + * @brief Encode a attitude_quaternion_cov struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param attitude_quaternion_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) +{ + return mavlink_msg_attitude_quaternion_cov_pack_chan(system_id, component_id, chan, msg, attitude_quaternion_cov->time_boot_ms, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance); +} + +/** + * @brief Send a attitude_quaternion_cov message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @param covariance Attitude covariance + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_quaternion_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_float_array(buf, 4, q, 4); + _mav_put_float_array(buf, 32, covariance, 9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif +#else + mavlink_attitude_quaternion_cov_t packet; + packet.time_boot_ms = time_boot_ms; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_attitude_quaternion_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_float_array(buf, 4, q, 4); + _mav_put_float_array(buf, 32, covariance, 9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif +#else + mavlink_attitude_quaternion_cov_t *packet = (mavlink_attitude_quaternion_cov_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->rollspeed = rollspeed; + packet->pitchspeed = pitchspeed; + packet->yawspeed = yawspeed; + mav_array_memcpy(packet->q, q, sizeof(float)*4); + mav_array_memcpy(packet->covariance, covariance, sizeof(float)*9); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ATTITUDE_QUATERNION_COV UNPACKING + + +/** + * @brief Get field time_boot_ms from attitude_quaternion_cov message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_attitude_quaternion_cov_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field q from attitude_quaternion_cov message + * + * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + */ +static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_q(const mavlink_message_t* msg, float *q) +{ + return _MAV_RETURN_float_array(msg, q, 4, 4); +} + +/** + * @brief Get field rollspeed from attitude_quaternion_cov message + * + * @return Roll angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_cov_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitchspeed from attitude_quaternion_cov message + * + * @return Pitch angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_cov_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yawspeed from attitude_quaternion_cov message + * + * @return Yaw angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_cov_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field covariance from attitude_quaternion_cov message + * + * @return Attitude covariance + */ +static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_covariance(const mavlink_message_t* msg, float *covariance) +{ + return _MAV_RETURN_float_array(msg, covariance, 9, 32); +} + +/** + * @brief Decode a attitude_quaternion_cov message into a struct + * + * @param msg The message to decode + * @param attitude_quaternion_cov C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_quaternion_cov_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) +{ +#if MAVLINK_NEED_BYTE_SWAP + attitude_quaternion_cov->time_boot_ms = mavlink_msg_attitude_quaternion_cov_get_time_boot_ms(msg); + mavlink_msg_attitude_quaternion_cov_get_q(msg, attitude_quaternion_cov->q); + attitude_quaternion_cov->rollspeed = mavlink_msg_attitude_quaternion_cov_get_rollspeed(msg); + attitude_quaternion_cov->pitchspeed = mavlink_msg_attitude_quaternion_cov_get_pitchspeed(msg); + attitude_quaternion_cov->yawspeed = mavlink_msg_attitude_quaternion_cov_get_yawspeed(msg); + mavlink_msg_attitude_quaternion_cov_get_covariance(msg, attitude_quaternion_cov->covariance); +#else + memcpy(attitude_quaternion_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_attitude_target.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_attitude_target.h new file mode 100644 index 0000000..5313fb0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_attitude_target.h @@ -0,0 +1,345 @@ +// MESSAGE ATTITUDE_TARGET PACKING + +#define MAVLINK_MSG_ID_ATTITUDE_TARGET 83 + +typedef struct __mavlink_attitude_target_t +{ + uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ + float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ + float body_roll_rate; /*< Body roll rate in radians per second*/ + float body_pitch_rate; /*< Body roll rate in radians per second*/ + float body_yaw_rate; /*< Body roll rate in radians per second*/ + float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/ + uint8_t type_mask; /*< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude*/ +} mavlink_attitude_target_t; + +#define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37 +#define MAVLINK_MSG_ID_83_LEN 37 + +#define MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC 22 +#define MAVLINK_MSG_ID_83_CRC 22 + +#define MAVLINK_MSG_ATTITUDE_TARGET_FIELD_Q_LEN 4 + +#define MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET { \ + "ATTITUDE_TARGET", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \ + { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \ + { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \ + { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \ + { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \ + } \ +} + + +/** + * @brief Pack a attitude_target message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate Body roll rate in radians per second + * @param body_pitch_rate Body roll rate in radians per second + * @param body_yaw_rate Body roll rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, type_mask); + _mav_put_float_array(buf, 4, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#else + mavlink_attitude_target_t packet; + packet.time_boot_ms = time_boot_ms; + packet.body_roll_rate = body_roll_rate; + packet.body_pitch_rate = body_pitch_rate; + packet.body_yaw_rate = body_yaw_rate; + packet.thrust = thrust; + packet.type_mask = type_mask; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif +} + +/** + * @brief Pack a attitude_target message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate Body roll rate in radians per second + * @param body_pitch_rate Body roll rate in radians per second + * @param body_yaw_rate Body roll rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t type_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, type_mask); + _mav_put_float_array(buf, 4, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#else + mavlink_attitude_target_t packet; + packet.time_boot_ms = time_boot_ms; + packet.body_roll_rate = body_roll_rate; + packet.body_pitch_rate = body_pitch_rate; + packet.body_yaw_rate = body_yaw_rate; + packet.thrust = thrust; + packet.type_mask = type_mask; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif +} + +/** + * @brief Encode a attitude_target struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param attitude_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target) +{ + return mavlink_msg_attitude_target_pack(system_id, component_id, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust); +} + +/** + * @brief Encode a attitude_target struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param attitude_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target) +{ + return mavlink_msg_attitude_target_pack_chan(system_id, component_id, chan, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust); +} + +/** + * @brief Send a attitude_target message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate Body roll rate in radians per second + * @param body_pitch_rate Body roll rate in radians per second + * @param body_yaw_rate Body roll rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_target_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, type_mask); + _mav_put_float_array(buf, 4, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif +#else + mavlink_attitude_target_t packet; + packet.time_boot_ms = time_boot_ms; + packet.body_roll_rate = body_roll_rate; + packet.body_pitch_rate = body_pitch_rate; + packet.body_yaw_rate = body_yaw_rate; + packet.thrust = thrust; + packet.type_mask = type_mask; + mav_array_memcpy(packet.q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_attitude_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, type_mask); + _mav_put_float_array(buf, 4, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif +#else + mavlink_attitude_target_t *packet = (mavlink_attitude_target_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->body_roll_rate = body_roll_rate; + packet->body_pitch_rate = body_pitch_rate; + packet->body_yaw_rate = body_yaw_rate; + packet->thrust = thrust; + packet->type_mask = type_mask; + mav_array_memcpy(packet->q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ATTITUDE_TARGET UNPACKING + + +/** + * @brief Get field time_boot_ms from attitude_target message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_attitude_target_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field type_mask from attitude_target message + * + * @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + */ +static inline uint8_t mavlink_msg_attitude_target_get_type_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Get field q from attitude_target message + * + * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + */ +static inline uint16_t mavlink_msg_attitude_target_get_q(const mavlink_message_t* msg, float *q) +{ + return _MAV_RETURN_float_array(msg, q, 4, 4); +} + +/** + * @brief Get field body_roll_rate from attitude_target message + * + * @return Body roll rate in radians per second + */ +static inline float mavlink_msg_attitude_target_get_body_roll_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field body_pitch_rate from attitude_target message + * + * @return Body roll rate in radians per second + */ +static inline float mavlink_msg_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field body_yaw_rate from attitude_target message + * + * @return Body roll rate in radians per second + */ +static inline float mavlink_msg_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field thrust from attitude_target message + * + * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + */ +static inline float mavlink_msg_attitude_target_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Decode a attitude_target message into a struct + * + * @param msg The message to decode + * @param attitude_target C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_target_decode(const mavlink_message_t* msg, mavlink_attitude_target_t* attitude_target) +{ +#if MAVLINK_NEED_BYTE_SWAP + attitude_target->time_boot_ms = mavlink_msg_attitude_target_get_time_boot_ms(msg); + mavlink_msg_attitude_target_get_q(msg, attitude_target->q); + attitude_target->body_roll_rate = mavlink_msg_attitude_target_get_body_roll_rate(msg); + attitude_target->body_pitch_rate = mavlink_msg_attitude_target_get_body_pitch_rate(msg); + attitude_target->body_yaw_rate = mavlink_msg_attitude_target_get_body_yaw_rate(msg); + attitude_target->thrust = mavlink_msg_attitude_target_get_thrust(msg); + attitude_target->type_mask = mavlink_msg_attitude_target_get_type_mask(msg); +#else + memcpy(attitude_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_auth_key.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_auth_key.h new file mode 100644 index 0000000..4c6c114 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_auth_key.h @@ -0,0 +1,209 @@ +// MESSAGE AUTH_KEY PACKING + +#define MAVLINK_MSG_ID_AUTH_KEY 7 + +typedef struct __mavlink_auth_key_t +{ + char key[32]; /*< key*/ +} mavlink_auth_key_t; + +#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32 +#define MAVLINK_MSG_ID_7_LEN 32 + +#define MAVLINK_MSG_ID_AUTH_KEY_CRC 119 +#define MAVLINK_MSG_ID_7_CRC 119 + +#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32 + +#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ + "AUTH_KEY", \ + 1, \ + { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ + } \ +} + + +/** + * @brief Pack a auth_key message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param key key + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *key) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; + + _mav_put_char_array(buf, 0, key, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#else + mavlink_auth_key_t packet; + + mav_array_memcpy(packet.key, key, sizeof(char)*32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif +} + +/** + * @brief Pack a auth_key message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param key key + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *key) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; + + _mav_put_char_array(buf, 0, key, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#else + mavlink_auth_key_t packet; + + mav_array_memcpy(packet.key, key, sizeof(char)*32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif +} + +/** + * @brief Encode a auth_key struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param auth_key C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) +{ + return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key); +} + +/** + * @brief Encode a auth_key struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param auth_key C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_auth_key_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) +{ + return mavlink_msg_auth_key_pack_chan(system_id, component_id, chan, msg, auth_key->key); +} + +/** + * @brief Send a auth_key message + * @param chan MAVLink channel to send the message + * + * @param key key + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; + + _mav_put_char_array(buf, 0, key, 32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif +#else + mavlink_auth_key_t packet; + + mav_array_memcpy(packet.key, key, sizeof(char)*32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_AUTH_KEY_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_auth_key_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *key) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + + _mav_put_char_array(buf, 0, key, 32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif +#else + mavlink_auth_key_t *packet = (mavlink_auth_key_t *)msgbuf; + + mav_array_memcpy(packet->key, key, sizeof(char)*32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE AUTH_KEY UNPACKING + + +/** + * @brief Get field key from auth_key message + * + * @return key + */ +static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key) +{ + return _MAV_RETURN_char_array(msg, key, 32, 0); +} + +/** + * @brief Decode a auth_key message into a struct + * + * @param msg The message to decode + * @param auth_key C-struct to decode the message contents into + */ +static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key) +{ +#if MAVLINK_NEED_BYTE_SWAP + mavlink_msg_auth_key_get_key(msg, auth_key->key); +#else + memcpy(auth_key, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AUTH_KEY_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_autopilot_version.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_autopilot_version.h new file mode 100644 index 0000000..7cef9ea --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_autopilot_version.h @@ -0,0 +1,443 @@ +// MESSAGE AUTOPILOT_VERSION PACKING + +#define MAVLINK_MSG_ID_AUTOPILOT_VERSION 148 + +typedef struct __mavlink_autopilot_version_t +{ + uint64_t capabilities; /*< bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)*/ + uint64_t uid; /*< UID if provided by hardware*/ + uint32_t flight_sw_version; /*< Firmware version number*/ + uint32_t middleware_sw_version; /*< Middleware version number*/ + uint32_t os_sw_version; /*< Operating system version number*/ + uint32_t board_version; /*< HW / board version (last 8 bytes should be silicon ID, if any)*/ + uint16_t vendor_id; /*< ID of the board vendor*/ + uint16_t product_id; /*< ID of the product*/ + uint8_t flight_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ + uint8_t middleware_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ + uint8_t os_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ +} mavlink_autopilot_version_t; + +#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 60 +#define MAVLINK_MSG_ID_148_LEN 60 + +#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC 178 +#define MAVLINK_MSG_ID_148_CRC 178 + +#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION_LEN 8 +#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION_LEN 8 +#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION_LEN 8 + +#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \ + "AUTOPILOT_VERSION", \ + 11, \ + { { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \ + { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \ + { "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \ + { "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \ + { "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \ + { "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \ + { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \ + { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \ + { "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \ + { "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \ + { "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \ + } \ +} + + +/** + * @brief Pack a autopilot_version message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) + * @param flight_sw_version Firmware version number + * @param middleware_sw_version Middleware version number + * @param os_sw_version Operating system version number + * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) + * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param vendor_id ID of the board vendor + * @param product_id ID of the product + * @param uid UID if provided by hardware + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN]; + _mav_put_uint64_t(buf, 0, capabilities); + _mav_put_uint64_t(buf, 8, uid); + _mav_put_uint32_t(buf, 16, flight_sw_version); + _mav_put_uint32_t(buf, 20, middleware_sw_version); + _mav_put_uint32_t(buf, 24, os_sw_version); + _mav_put_uint32_t(buf, 28, board_version); + _mav_put_uint16_t(buf, 32, vendor_id); + _mav_put_uint16_t(buf, 34, product_id); + _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); + _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); + _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#else + mavlink_autopilot_version_t packet; + packet.capabilities = capabilities; + packet.uid = uid; + packet.flight_sw_version = flight_sw_version; + packet.middleware_sw_version = middleware_sw_version; + packet.os_sw_version = os_sw_version; + packet.board_version = board_version; + packet.vendor_id = vendor_id; + packet.product_id = product_id; + mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif +} + +/** + * @brief Pack a autopilot_version message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) + * @param flight_sw_version Firmware version number + * @param middleware_sw_version Middleware version number + * @param os_sw_version Operating system version number + * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) + * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param vendor_id ID of the board vendor + * @param product_id ID of the product + * @param uid UID if provided by hardware + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t capabilities,uint32_t flight_sw_version,uint32_t middleware_sw_version,uint32_t os_sw_version,uint32_t board_version,const uint8_t *flight_custom_version,const uint8_t *middleware_custom_version,const uint8_t *os_custom_version,uint16_t vendor_id,uint16_t product_id,uint64_t uid) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN]; + _mav_put_uint64_t(buf, 0, capabilities); + _mav_put_uint64_t(buf, 8, uid); + _mav_put_uint32_t(buf, 16, flight_sw_version); + _mav_put_uint32_t(buf, 20, middleware_sw_version); + _mav_put_uint32_t(buf, 24, os_sw_version); + _mav_put_uint32_t(buf, 28, board_version); + _mav_put_uint16_t(buf, 32, vendor_id); + _mav_put_uint16_t(buf, 34, product_id); + _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); + _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); + _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#else + mavlink_autopilot_version_t packet; + packet.capabilities = capabilities; + packet.uid = uid; + packet.flight_sw_version = flight_sw_version; + packet.middleware_sw_version = middleware_sw_version; + packet.os_sw_version = os_sw_version; + packet.board_version = board_version; + packet.vendor_id = vendor_id; + packet.product_id = product_id; + mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif +} + +/** + * @brief Encode a autopilot_version struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param autopilot_version C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_autopilot_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version) +{ + return mavlink_msg_autopilot_version_pack(system_id, component_id, msg, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid); +} + +/** + * @brief Encode a autopilot_version struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param autopilot_version C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_autopilot_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version) +{ + return mavlink_msg_autopilot_version_pack_chan(system_id, component_id, chan, msg, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid); +} + +/** + * @brief Send a autopilot_version message + * @param chan MAVLink channel to send the message + * + * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) + * @param flight_sw_version Firmware version number + * @param middleware_sw_version Middleware version number + * @param os_sw_version Operating system version number + * @param board_version HW / board version (last 8 bytes should be silicon ID, if any) + * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + * @param vendor_id ID of the board vendor + * @param product_id ID of the product + * @param uid UID if provided by hardware + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_autopilot_version_send(mavlink_channel_t chan, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN]; + _mav_put_uint64_t(buf, 0, capabilities); + _mav_put_uint64_t(buf, 8, uid); + _mav_put_uint32_t(buf, 16, flight_sw_version); + _mav_put_uint32_t(buf, 20, middleware_sw_version); + _mav_put_uint32_t(buf, 24, os_sw_version); + _mav_put_uint32_t(buf, 28, board_version); + _mav_put_uint16_t(buf, 32, vendor_id); + _mav_put_uint16_t(buf, 34, product_id); + _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); + _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); + _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif +#else + mavlink_autopilot_version_t packet; + packet.capabilities = capabilities; + packet.uid = uid; + packet.flight_sw_version = flight_sw_version; + packet.middleware_sw_version = middleware_sw_version; + packet.os_sw_version = os_sw_version; + packet.board_version = board_version; + packet.vendor_id = vendor_id; + packet.product_id = product_id; + mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_autopilot_version_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, capabilities); + _mav_put_uint64_t(buf, 8, uid); + _mav_put_uint32_t(buf, 16, flight_sw_version); + _mav_put_uint32_t(buf, 20, middleware_sw_version); + _mav_put_uint32_t(buf, 24, os_sw_version); + _mav_put_uint32_t(buf, 28, board_version); + _mav_put_uint16_t(buf, 32, vendor_id); + _mav_put_uint16_t(buf, 34, product_id); + _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); + _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); + _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif +#else + mavlink_autopilot_version_t *packet = (mavlink_autopilot_version_t *)msgbuf; + packet->capabilities = capabilities; + packet->uid = uid; + packet->flight_sw_version = flight_sw_version; + packet->middleware_sw_version = middleware_sw_version; + packet->os_sw_version = os_sw_version; + packet->board_version = board_version; + packet->vendor_id = vendor_id; + packet->product_id = product_id; + mav_array_memcpy(packet->flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet->middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); + mav_array_memcpy(packet->os_custom_version, os_custom_version, sizeof(uint8_t)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE AUTOPILOT_VERSION UNPACKING + + +/** + * @brief Get field capabilities from autopilot_version message + * + * @return bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) + */ +static inline uint64_t mavlink_msg_autopilot_version_get_capabilities(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field flight_sw_version from autopilot_version message + * + * @return Firmware version number + */ +static inline uint32_t mavlink_msg_autopilot_version_get_flight_sw_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 16); +} + +/** + * @brief Get field middleware_sw_version from autopilot_version message + * + * @return Middleware version number + */ +static inline uint32_t mavlink_msg_autopilot_version_get_middleware_sw_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 20); +} + +/** + * @brief Get field os_sw_version from autopilot_version message + * + * @return Operating system version number + */ +static inline uint32_t mavlink_msg_autopilot_version_get_os_sw_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 24); +} + +/** + * @brief Get field board_version from autopilot_version message + * + * @return HW / board version (last 8 bytes should be silicon ID, if any) + */ +static inline uint32_t mavlink_msg_autopilot_version_get_board_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 28); +} + +/** + * @brief Get field flight_custom_version from autopilot_version message + * + * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + */ +static inline uint16_t mavlink_msg_autopilot_version_get_flight_custom_version(const mavlink_message_t* msg, uint8_t *flight_custom_version) +{ + return _MAV_RETURN_uint8_t_array(msg, flight_custom_version, 8, 36); +} + +/** + * @brief Get field middleware_custom_version from autopilot_version message + * + * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + */ +static inline uint16_t mavlink_msg_autopilot_version_get_middleware_custom_version(const mavlink_message_t* msg, uint8_t *middleware_custom_version) +{ + return _MAV_RETURN_uint8_t_array(msg, middleware_custom_version, 8, 44); +} + +/** + * @brief Get field os_custom_version from autopilot_version message + * + * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + */ +static inline uint16_t mavlink_msg_autopilot_version_get_os_custom_version(const mavlink_message_t* msg, uint8_t *os_custom_version) +{ + return _MAV_RETURN_uint8_t_array(msg, os_custom_version, 8, 52); +} + +/** + * @brief Get field vendor_id from autopilot_version message + * + * @return ID of the board vendor + */ +static inline uint16_t mavlink_msg_autopilot_version_get_vendor_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 32); +} + +/** + * @brief Get field product_id from autopilot_version message + * + * @return ID of the product + */ +static inline uint16_t mavlink_msg_autopilot_version_get_product_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 34); +} + +/** + * @brief Get field uid from autopilot_version message + * + * @return UID if provided by hardware + */ +static inline uint64_t mavlink_msg_autopilot_version_get_uid(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 8); +} + +/** + * @brief Decode a autopilot_version message into a struct + * + * @param msg The message to decode + * @param autopilot_version C-struct to decode the message contents into + */ +static inline void mavlink_msg_autopilot_version_decode(const mavlink_message_t* msg, mavlink_autopilot_version_t* autopilot_version) +{ +#if MAVLINK_NEED_BYTE_SWAP + autopilot_version->capabilities = mavlink_msg_autopilot_version_get_capabilities(msg); + autopilot_version->uid = mavlink_msg_autopilot_version_get_uid(msg); + autopilot_version->flight_sw_version = mavlink_msg_autopilot_version_get_flight_sw_version(msg); + autopilot_version->middleware_sw_version = mavlink_msg_autopilot_version_get_middleware_sw_version(msg); + autopilot_version->os_sw_version = mavlink_msg_autopilot_version_get_os_sw_version(msg); + autopilot_version->board_version = mavlink_msg_autopilot_version_get_board_version(msg); + autopilot_version->vendor_id = mavlink_msg_autopilot_version_get_vendor_id(msg); + autopilot_version->product_id = mavlink_msg_autopilot_version_get_product_id(msg); + mavlink_msg_autopilot_version_get_flight_custom_version(msg, autopilot_version->flight_custom_version); + mavlink_msg_autopilot_version_get_middleware_custom_version(msg, autopilot_version->middleware_custom_version); + mavlink_msg_autopilot_version_get_os_custom_version(msg, autopilot_version->os_custom_version); +#else + memcpy(autopilot_version, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_battery_status.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_battery_status.h new file mode 100644 index 0000000..9311a7d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_battery_status.h @@ -0,0 +1,393 @@ +// MESSAGE BATTERY_STATUS PACKING + +#define MAVLINK_MSG_ID_BATTERY_STATUS 147 + +typedef struct __mavlink_battery_status_t +{ + int32_t current_consumed; /*< Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate*/ + int32_t energy_consumed; /*< Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate*/ + int16_t temperature; /*< Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.*/ + uint16_t voltages[10]; /*< Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value.*/ + int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current*/ + uint8_t id; /*< Battery ID*/ + uint8_t battery_function; /*< Function of the battery*/ + uint8_t type; /*< Type (chemistry) of the battery*/ + int8_t battery_remaining; /*< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery*/ +} mavlink_battery_status_t; + +#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36 +#define MAVLINK_MSG_ID_147_LEN 36 + +#define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 154 +#define MAVLINK_MSG_ID_147_CRC 154 + +#define MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN 10 + +#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \ + "BATTERY_STATUS", \ + 9, \ + { { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \ + { "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \ + { "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \ + { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \ + { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \ + { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \ + { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \ + } \ +} + + +/** + * @brief Pack a battery_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param id Battery ID + * @param battery_function Function of the battery + * @param type Type (chemistry) of the battery + * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. + * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + * @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; + _mav_put_int32_t(buf, 0, current_consumed); + _mav_put_int32_t(buf, 4, energy_consumed); + _mav_put_int16_t(buf, 8, temperature); + _mav_put_int16_t(buf, 30, current_battery); + _mav_put_uint8_t(buf, 32, id); + _mav_put_uint8_t(buf, 33, battery_function); + _mav_put_uint8_t(buf, 34, type); + _mav_put_int8_t(buf, 35, battery_remaining); + _mav_put_uint16_t_array(buf, 10, voltages, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#else + mavlink_battery_status_t packet; + packet.current_consumed = current_consumed; + packet.energy_consumed = energy_consumed; + packet.temperature = temperature; + packet.current_battery = current_battery; + packet.id = id; + packet.battery_function = battery_function; + packet.type = type; + packet.battery_remaining = battery_remaining; + mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif +} + +/** + * @brief Pack a battery_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param id Battery ID + * @param battery_function Function of the battery + * @param type Type (chemistry) of the battery + * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. + * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + * @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t id,uint8_t battery_function,uint8_t type,int16_t temperature,const uint16_t *voltages,int16_t current_battery,int32_t current_consumed,int32_t energy_consumed,int8_t battery_remaining) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; + _mav_put_int32_t(buf, 0, current_consumed); + _mav_put_int32_t(buf, 4, energy_consumed); + _mav_put_int16_t(buf, 8, temperature); + _mav_put_int16_t(buf, 30, current_battery); + _mav_put_uint8_t(buf, 32, id); + _mav_put_uint8_t(buf, 33, battery_function); + _mav_put_uint8_t(buf, 34, type); + _mav_put_int8_t(buf, 35, battery_remaining); + _mav_put_uint16_t_array(buf, 10, voltages, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#else + mavlink_battery_status_t packet; + packet.current_consumed = current_consumed; + packet.energy_consumed = energy_consumed; + packet.temperature = temperature; + packet.current_battery = current_battery; + packet.id = id; + packet.battery_function = battery_function; + packet.type = type; + packet.battery_remaining = battery_remaining; + mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif +} + +/** + * @brief Encode a battery_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param battery_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status) +{ + return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining); +} + +/** + * @brief Encode a battery_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param battery_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status) +{ + return mavlink_msg_battery_status_pack_chan(system_id, component_id, chan, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining); +} + +/** + * @brief Send a battery_status message + * @param chan MAVLink channel to send the message + * + * @param id Battery ID + * @param battery_function Function of the battery + * @param type Type (chemistry) of the battery + * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. + * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + * @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; + _mav_put_int32_t(buf, 0, current_consumed); + _mav_put_int32_t(buf, 4, energy_consumed); + _mav_put_int16_t(buf, 8, temperature); + _mav_put_int16_t(buf, 30, current_battery); + _mav_put_uint8_t(buf, 32, id); + _mav_put_uint8_t(buf, 33, battery_function); + _mav_put_uint8_t(buf, 34, type); + _mav_put_int8_t(buf, 35, battery_remaining); + _mav_put_uint16_t_array(buf, 10, voltages, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif +#else + mavlink_battery_status_t packet; + packet.current_consumed = current_consumed; + packet.energy_consumed = energy_consumed; + packet.temperature = temperature; + packet.current_battery = current_battery; + packet.id = id; + packet.battery_function = battery_function; + packet.type = type; + packet.battery_remaining = battery_remaining; + mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_BATTERY_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, current_consumed); + _mav_put_int32_t(buf, 4, energy_consumed); + _mav_put_int16_t(buf, 8, temperature); + _mav_put_int16_t(buf, 30, current_battery); + _mav_put_uint8_t(buf, 32, id); + _mav_put_uint8_t(buf, 33, battery_function); + _mav_put_uint8_t(buf, 34, type); + _mav_put_int8_t(buf, 35, battery_remaining); + _mav_put_uint16_t_array(buf, 10, voltages, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif +#else + mavlink_battery_status_t *packet = (mavlink_battery_status_t *)msgbuf; + packet->current_consumed = current_consumed; + packet->energy_consumed = energy_consumed; + packet->temperature = temperature; + packet->current_battery = current_battery; + packet->id = id; + packet->battery_function = battery_function; + packet->type = type; + packet->battery_remaining = battery_remaining; + mav_array_memcpy(packet->voltages, voltages, sizeof(uint16_t)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE BATTERY_STATUS UNPACKING + + +/** + * @brief Get field id from battery_status message + * + * @return Battery ID + */ +static inline uint8_t mavlink_msg_battery_status_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field battery_function from battery_status message + * + * @return Function of the battery + */ +static inline uint8_t mavlink_msg_battery_status_get_battery_function(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field type from battery_status message + * + * @return Type (chemistry) of the battery + */ +static inline uint8_t mavlink_msg_battery_status_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field temperature from battery_status message + * + * @return Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. + */ +static inline int16_t mavlink_msg_battery_status_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field voltages from battery_status message + * + * @return Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. + */ +static inline uint16_t mavlink_msg_battery_status_get_voltages(const mavlink_message_t* msg, uint16_t *voltages) +{ + return _MAV_RETURN_uint16_t_array(msg, voltages, 10, 10); +} + +/** + * @brief Get field current_battery from battery_status message + * + * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + */ +static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 30); +} + +/** + * @brief Get field current_consumed from battery_status message + * + * @return Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + */ +static inline int32_t mavlink_msg_battery_status_get_current_consumed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field energy_consumed from battery_status message + * + * @return Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate + */ +static inline int32_t mavlink_msg_battery_status_get_energy_consumed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field battery_remaining from battery_status message + * + * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + */ +static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 35); +} + +/** + * @brief Decode a battery_status message into a struct + * + * @param msg The message to decode + * @param battery_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_battery_status_decode(const mavlink_message_t* msg, mavlink_battery_status_t* battery_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + battery_status->current_consumed = mavlink_msg_battery_status_get_current_consumed(msg); + battery_status->energy_consumed = mavlink_msg_battery_status_get_energy_consumed(msg); + battery_status->temperature = mavlink_msg_battery_status_get_temperature(msg); + mavlink_msg_battery_status_get_voltages(msg, battery_status->voltages); + battery_status->current_battery = mavlink_msg_battery_status_get_current_battery(msg); + battery_status->id = mavlink_msg_battery_status_get_id(msg); + battery_status->battery_function = mavlink_msg_battery_status_get_battery_function(msg); + battery_status->type = mavlink_msg_battery_status_get_type(msg); + battery_status->battery_remaining = mavlink_msg_battery_status_get_battery_remaining(msg); +#else + memcpy(battery_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_BATTERY_STATUS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_camera_trigger.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_camera_trigger.h new file mode 100644 index 0000000..d724d9d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_camera_trigger.h @@ -0,0 +1,233 @@ +// MESSAGE CAMERA_TRIGGER PACKING + +#define MAVLINK_MSG_ID_CAMERA_TRIGGER 112 + +typedef struct __mavlink_camera_trigger_t +{ + uint64_t time_usec; /*< Timestamp for the image frame in microseconds*/ + uint32_t seq; /*< Image frame sequence*/ +} mavlink_camera_trigger_t; + +#define MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN 12 +#define MAVLINK_MSG_ID_112_LEN 12 + +#define MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC 174 +#define MAVLINK_MSG_ID_112_CRC 174 + + + +#define MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER { \ + "CAMERA_TRIGGER", \ + 2, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_trigger_t, time_usec) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_trigger_t, seq) }, \ + } \ +} + + +/** + * @brief Pack a camera_trigger message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp for the image frame in microseconds + * @param seq Image frame sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_camera_trigger_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint32_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#else + mavlink_camera_trigger_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CAMERA_TRIGGER; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif +} + +/** + * @brief Pack a camera_trigger message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp for the image frame in microseconds + * @param seq Image frame sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_camera_trigger_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint32_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#else + mavlink_camera_trigger_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CAMERA_TRIGGER; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif +} + +/** + * @brief Encode a camera_trigger struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param camera_trigger C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_camera_trigger_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_trigger_t* camera_trigger) +{ + return mavlink_msg_camera_trigger_pack(system_id, component_id, msg, camera_trigger->time_usec, camera_trigger->seq); +} + +/** + * @brief Encode a camera_trigger struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param camera_trigger C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_camera_trigger_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_trigger_t* camera_trigger) +{ + return mavlink_msg_camera_trigger_pack_chan(system_id, component_id, chan, msg, camera_trigger->time_usec, camera_trigger->seq); +} + +/** + * @brief Send a camera_trigger message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp for the image frame in microseconds + * @param seq Image frame sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_camera_trigger_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif +#else + mavlink_camera_trigger_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_camera_trigger_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif +#else + mavlink_camera_trigger_t *packet = (mavlink_camera_trigger_t *)msgbuf; + packet->time_usec = time_usec; + packet->seq = seq; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE CAMERA_TRIGGER UNPACKING + + +/** + * @brief Get field time_usec from camera_trigger message + * + * @return Timestamp for the image frame in microseconds + */ +static inline uint64_t mavlink_msg_camera_trigger_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field seq from camera_trigger message + * + * @return Image frame sequence + */ +static inline uint32_t mavlink_msg_camera_trigger_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Decode a camera_trigger message into a struct + * + * @param msg The message to decode + * @param camera_trigger C-struct to decode the message contents into + */ +static inline void mavlink_msg_camera_trigger_decode(const mavlink_message_t* msg, mavlink_camera_trigger_t* camera_trigger) +{ +#if MAVLINK_NEED_BYTE_SWAP + camera_trigger->time_usec = mavlink_msg_camera_trigger_get_time_usec(msg); + camera_trigger->seq = mavlink_msg_camera_trigger_get_seq(msg); +#else + memcpy(camera_trigger, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_change_operator_control.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_change_operator_control.h new file mode 100644 index 0000000..7a86a91 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_change_operator_control.h @@ -0,0 +1,273 @@ +// MESSAGE CHANGE_OPERATOR_CONTROL PACKING + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5 + +typedef struct __mavlink_change_operator_control_t +{ + uint8_t target_system; /*< System the GCS requests control for*/ + uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/ + uint8_t version; /*< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.*/ + char passkey[25]; /*< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"*/ +} mavlink_change_operator_control_t; + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28 +#define MAVLINK_MSG_ID_5_LEN 28 + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC 217 +#define MAVLINK_MSG_ID_5_CRC 217 + +#define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25 + +#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \ + "CHANGE_OPERATOR_CONTROL", \ + 4, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \ + { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \ + { "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \ + { "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \ + } \ +} + + +/** + * @brief Pack a change_operator_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, version); + _mav_put_char_array(buf, 3, passkey, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#else + mavlink_change_operator_control_t packet; + packet.target_system = target_system; + packet.control_request = control_request; + packet.version = version; + mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif +} + +/** + * @brief Pack a change_operator_control message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t control_request,uint8_t version,const char *passkey) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, version); + _mav_put_char_array(buf, 3, passkey, 25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#else + mavlink_change_operator_control_t packet; + packet.target_system = target_system; + packet.control_request = control_request; + packet.version = version; + mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif +} + +/** + * @brief Encode a change_operator_control struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param change_operator_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control) +{ + return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); +} + +/** + * @brief Encode a change_operator_control struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param change_operator_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_change_operator_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control) +{ + return mavlink_msg_change_operator_control_pack_chan(system_id, component_id, chan, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); +} + +/** + * @brief Send a change_operator_control message + * @param chan MAVLink channel to send the message + * + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, version); + _mav_put_char_array(buf, 3, passkey, 25); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif +#else + mavlink_change_operator_control_t packet; + packet.target_system = target_system; + packet.control_request = control_request; + packet.version = version; + mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_change_operator_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, version); + _mav_put_char_array(buf, 3, passkey, 25); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif +#else + mavlink_change_operator_control_t *packet = (mavlink_change_operator_control_t *)msgbuf; + packet->target_system = target_system; + packet->control_request = control_request; + packet->version = version; + mav_array_memcpy(packet->passkey, passkey, sizeof(char)*25); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING + + +/** + * @brief Get field target_system from change_operator_control message + * + * @return System the GCS requests control for + */ +static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field control_request from change_operator_control message + * + * @return 0: request control of this MAV, 1: Release control of this MAV + */ +static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field version from change_operator_control message + * + * @return 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + */ +static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field passkey from change_operator_control message + * + * @return Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + */ +static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char *passkey) +{ + return _MAV_RETURN_char_array(msg, passkey, 25, 3); +} + +/** + * @brief Decode a change_operator_control message into a struct + * + * @param msg The message to decode + * @param change_operator_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg); + change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg); + change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg); + mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey); +#else + memcpy(change_operator_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h new file mode 100644 index 0000000..309fa04 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h @@ -0,0 +1,257 @@ +// MESSAGE CHANGE_OPERATOR_CONTROL_ACK PACKING + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6 + +typedef struct __mavlink_change_operator_control_ack_t +{ + uint8_t gcs_system_id; /*< ID of the GCS this message */ + uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/ + uint8_t ack; /*< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control*/ +} mavlink_change_operator_control_ack_t; + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3 +#define MAVLINK_MSG_ID_6_LEN 3 + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC 104 +#define MAVLINK_MSG_ID_6_CRC 104 + + + +#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \ + "CHANGE_OPERATOR_CONTROL_ACK", \ + 3, \ + { { "gcs_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \ + { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \ + { "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \ + } \ +} + + +/** + * @brief Pack a change_operator_control_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN]; + _mav_put_uint8_t(buf, 0, gcs_system_id); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, ack); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#else + mavlink_change_operator_control_ack_t packet; + packet.gcs_system_id = gcs_system_id; + packet.control_request = control_request; + packet.ack = ack; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif +} + +/** + * @brief Pack a change_operator_control_ack message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t gcs_system_id,uint8_t control_request,uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN]; + _mav_put_uint8_t(buf, 0, gcs_system_id); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, ack); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#else + mavlink_change_operator_control_ack_t packet; + packet.gcs_system_id = gcs_system_id; + packet.control_request = control_request; + packet.ack = ack; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif +} + +/** + * @brief Encode a change_operator_control_ack struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param change_operator_control_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack) +{ + return mavlink_msg_change_operator_control_ack_pack(system_id, component_id, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); +} + +/** + * @brief Encode a change_operator_control_ack struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param change_operator_control_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack) +{ + return mavlink_msg_change_operator_control_ack_pack_chan(system_id, component_id, chan, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); +} + +/** + * @brief Send a change_operator_control_ack message + * @param chan MAVLink channel to send the message + * + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN]; + _mav_put_uint8_t(buf, 0, gcs_system_id); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, ack); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif +#else + mavlink_change_operator_control_ack_t packet; + packet.gcs_system_id = gcs_system_id; + packet.control_request = control_request; + packet.ack = ack; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_change_operator_control_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, gcs_system_id); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, ack); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif +#else + mavlink_change_operator_control_ack_t *packet = (mavlink_change_operator_control_ack_t *)msgbuf; + packet->gcs_system_id = gcs_system_id; + packet->control_request = control_request; + packet->ack = ack; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE CHANGE_OPERATOR_CONTROL_ACK UNPACKING + + +/** + * @brief Get field gcs_system_id from change_operator_control_ack message + * + * @return ID of the GCS this message + */ +static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field control_request from change_operator_control_ack message + * + * @return 0: request control of this MAV, 1: Release control of this MAV + */ +static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field ack from change_operator_control_ack message + * + * @return 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + */ +static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a change_operator_control_ack message into a struct + * + * @param msg The message to decode + * @param change_operator_control_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_message_t* msg, mavlink_change_operator_control_ack_t* change_operator_control_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + change_operator_control_ack->gcs_system_id = mavlink_msg_change_operator_control_ack_get_gcs_system_id(msg); + change_operator_control_ack->control_request = mavlink_msg_change_operator_control_ack_get_control_request(msg); + change_operator_control_ack->ack = mavlink_msg_change_operator_control_ack_get_ack(msg); +#else + memcpy(change_operator_control_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_command_ack.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_command_ack.h new file mode 100644 index 0000000..2caebb0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_command_ack.h @@ -0,0 +1,233 @@ +// MESSAGE COMMAND_ACK PACKING + +#define MAVLINK_MSG_ID_COMMAND_ACK 77 + +typedef struct __mavlink_command_ack_t +{ + uint16_t command; /*< Command ID, as defined by MAV_CMD enum.*/ + uint8_t result; /*< See MAV_RESULT enum*/ +} mavlink_command_ack_t; + +#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3 +#define MAVLINK_MSG_ID_77_LEN 3 + +#define MAVLINK_MSG_ID_COMMAND_ACK_CRC 143 +#define MAVLINK_MSG_ID_77_CRC 143 + + + +#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \ + "COMMAND_ACK", \ + 2, \ + { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \ + { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \ + } \ +} + + +/** + * @brief Pack a command_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param command Command ID, as defined by MAV_CMD enum. + * @param result See MAV_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t command, uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN]; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, result); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#else + mavlink_command_ack_t packet; + packet.command = command; + packet.result = result; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif +} + +/** + * @brief Pack a command_ack message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param command Command ID, as defined by MAV_CMD enum. + * @param result See MAV_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t command,uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN]; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, result); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#else + mavlink_command_ack_t packet; + packet.command = command; + packet.result = result; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif +} + +/** + * @brief Encode a command_ack struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param command_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack) +{ + return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result); +} + +/** + * @brief Encode a command_ack struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param command_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack) +{ + return mavlink_msg_command_ack_pack_chan(system_id, component_id, chan, msg, command_ack->command, command_ack->result); +} + +/** + * @brief Send a command_ack message + * @param chan MAVLink channel to send the message + * + * @param command Command ID, as defined by MAV_CMD enum. + * @param result See MAV_RESULT enum + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN]; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, result); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif +#else + mavlink_command_ack_t packet; + packet.command = command; + packet.result = result; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_COMMAND_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t command, uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, result); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif +#else + mavlink_command_ack_t *packet = (mavlink_command_ack_t *)msgbuf; + packet->command = command; + packet->result = result; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE COMMAND_ACK UNPACKING + + +/** + * @brief Get field command from command_ack message + * + * @return Command ID, as defined by MAV_CMD enum. + */ +static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field result from command_ack message + * + * @return See MAV_RESULT enum + */ +static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a command_ack message into a struct + * + * @param msg The message to decode + * @param command_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + command_ack->command = mavlink_msg_command_ack_get_command(msg); + command_ack->result = mavlink_msg_command_ack_get_result(msg); +#else + memcpy(command_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMMAND_ACK_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_command_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_command_int.h new file mode 100644 index 0000000..9f4e6f9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_command_int.h @@ -0,0 +1,497 @@ +// MESSAGE COMMAND_INT PACKING + +#define MAVLINK_MSG_ID_COMMAND_INT 75 + +typedef struct __mavlink_command_int_t +{ + float param1; /*< PARAM1, see MAV_CMD enum*/ + float param2; /*< PARAM2, see MAV_CMD enum*/ + float param3; /*< PARAM3, see MAV_CMD enum*/ + float param4; /*< PARAM4, see MAV_CMD enum*/ + int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/ + int32_t y; /*< PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7*/ + float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/ + uint16_t command; /*< The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t frame; /*< The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h*/ + uint8_t current; /*< false:0, true:1*/ + uint8_t autocontinue; /*< autocontinue to next wp*/ +} mavlink_command_int_t; + +#define MAVLINK_MSG_ID_COMMAND_INT_LEN 35 +#define MAVLINK_MSG_ID_75_LEN 35 + +#define MAVLINK_MSG_ID_COMMAND_INT_CRC 158 +#define MAVLINK_MSG_ID_75_CRC 158 + + + +#define MAVLINK_MESSAGE_INFO_COMMAND_INT { \ + "COMMAND_INT", \ + 13, \ + { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \ + { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \ + } \ +} + + +/** + * @brief Pack a command_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, frame); + _mav_put_uint8_t(buf, 33, current); + _mav_put_uint8_t(buf, 34, autocontinue); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#else + mavlink_command_int_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif +} + +/** + * @brief Pack a command_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,int32_t x,int32_t y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, frame); + _mav_put_uint8_t(buf, 33, current); + _mav_put_uint8_t(buf, 34, autocontinue); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#else + mavlink_command_int_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif +} + +/** + * @brief Encode a command_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param command_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_int_t* command_int) +{ + return mavlink_msg_command_int_pack(system_id, component_id, msg, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z); +} + +/** + * @brief Encode a command_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param command_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_int_t* command_int) +{ + return mavlink_msg_command_int_pack_chan(system_id, component_id, chan, msg, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z); +} + +/** + * @brief Send a command_int message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_command_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, frame); + _mav_put_uint8_t(buf, 33, current); + _mav_put_uint8_t(buf, 34, autocontinue); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif +#else + mavlink_command_int_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_COMMAND_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_command_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, frame); + _mav_put_uint8_t(buf, 33, current); + _mav_put_uint8_t(buf, 34, autocontinue); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif +#else + mavlink_command_int_t *packet = (mavlink_command_int_t *)msgbuf; + packet->param1 = param1; + packet->param2 = param2; + packet->param3 = param3; + packet->param4 = param4; + packet->x = x; + packet->y = y; + packet->z = z; + packet->command = command; + packet->target_system = target_system; + packet->target_component = target_component; + packet->frame = frame; + packet->current = current; + packet->autocontinue = autocontinue; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)packet, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)packet, MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE COMMAND_INT UNPACKING + + +/** + * @brief Get field target_system from command_int message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_command_int_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 30); +} + +/** + * @brief Get field target_component from command_int message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_command_int_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 31); +} + +/** + * @brief Get field frame from command_int message + * + * @return The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h + */ +static inline uint8_t mavlink_msg_command_int_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field command from command_int message + * + * @return The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs + */ +static inline uint16_t mavlink_msg_command_int_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field current from command_int message + * + * @return false:0, true:1 + */ +static inline uint8_t mavlink_msg_command_int_get_current(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field autocontinue from command_int message + * + * @return autocontinue to next wp + */ +static inline uint8_t mavlink_msg_command_int_get_autocontinue(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field param1 from command_int message + * + * @return PARAM1, see MAV_CMD enum + */ +static inline float mavlink_msg_command_int_get_param1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param2 from command_int message + * + * @return PARAM2, see MAV_CMD enum + */ +static inline float mavlink_msg_command_int_get_param2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param3 from command_int message + * + * @return PARAM3, see MAV_CMD enum + */ +static inline float mavlink_msg_command_int_get_param3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param4 from command_int message + * + * @return PARAM4, see MAV_CMD enum + */ +static inline float mavlink_msg_command_int_get_param4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field x from command_int message + * + * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + */ +static inline int32_t mavlink_msg_command_int_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field y from command_int message + * + * @return PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + */ +static inline int32_t mavlink_msg_command_int_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 20); +} + +/** + * @brief Get field z from command_int message + * + * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + */ +static inline float mavlink_msg_command_int_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a command_int message into a struct + * + * @param msg The message to decode + * @param command_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_command_int_decode(const mavlink_message_t* msg, mavlink_command_int_t* command_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + command_int->param1 = mavlink_msg_command_int_get_param1(msg); + command_int->param2 = mavlink_msg_command_int_get_param2(msg); + command_int->param3 = mavlink_msg_command_int_get_param3(msg); + command_int->param4 = mavlink_msg_command_int_get_param4(msg); + command_int->x = mavlink_msg_command_int_get_x(msg); + command_int->y = mavlink_msg_command_int_get_y(msg); + command_int->z = mavlink_msg_command_int_get_z(msg); + command_int->command = mavlink_msg_command_int_get_command(msg); + command_int->target_system = mavlink_msg_command_int_get_target_system(msg); + command_int->target_component = mavlink_msg_command_int_get_target_component(msg); + command_int->frame = mavlink_msg_command_int_get_frame(msg); + command_int->current = mavlink_msg_command_int_get_current(msg); + command_int->autocontinue = mavlink_msg_command_int_get_autocontinue(msg); +#else + memcpy(command_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMMAND_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_command_long.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_command_long.h new file mode 100644 index 0000000..7c7f1c0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_command_long.h @@ -0,0 +1,449 @@ +// MESSAGE COMMAND_LONG PACKING + +#define MAVLINK_MSG_ID_COMMAND_LONG 76 + +typedef struct __mavlink_command_long_t +{ + float param1; /*< Parameter 1, as defined by MAV_CMD enum.*/ + float param2; /*< Parameter 2, as defined by MAV_CMD enum.*/ + float param3; /*< Parameter 3, as defined by MAV_CMD enum.*/ + float param4; /*< Parameter 4, as defined by MAV_CMD enum.*/ + float param5; /*< Parameter 5, as defined by MAV_CMD enum.*/ + float param6; /*< Parameter 6, as defined by MAV_CMD enum.*/ + float param7; /*< Parameter 7, as defined by MAV_CMD enum.*/ + uint16_t command; /*< Command ID, as defined by MAV_CMD enum.*/ + uint8_t target_system; /*< System which should execute the command*/ + uint8_t target_component; /*< Component which should execute the command, 0 for all components*/ + uint8_t confirmation; /*< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)*/ +} mavlink_command_long_t; + +#define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33 +#define MAVLINK_MSG_ID_76_LEN 33 + +#define MAVLINK_MSG_ID_COMMAND_LONG_CRC 152 +#define MAVLINK_MSG_ID_76_CRC 152 + + + +#define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \ + "COMMAND_LONG", \ + 11, \ + { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \ + { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \ + { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \ + { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ + { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ + } \ +} + + +/** + * @brief Pack a command_long message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @param param5 Parameter 5, as defined by MAV_CMD enum. + * @param param6 Parameter 6, as defined by MAV_CMD enum. + * @param param7 Parameter 7, as defined by MAV_CMD enum. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, param5); + _mav_put_float(buf, 20, param6); + _mav_put_float(buf, 24, param7); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, confirmation); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#else + mavlink_command_long_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.param5 = param5; + packet.param6 = param6; + packet.param7 = param7; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.confirmation = confirmation; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif +} + +/** + * @brief Pack a command_long message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @param param5 Parameter 5, as defined by MAV_CMD enum. + * @param param6 Parameter 6, as defined by MAV_CMD enum. + * @param param7 Parameter 7, as defined by MAV_CMD enum. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t command,uint8_t confirmation,float param1,float param2,float param3,float param4,float param5,float param6,float param7) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, param5); + _mav_put_float(buf, 20, param6); + _mav_put_float(buf, 24, param7); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, confirmation); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#else + mavlink_command_long_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.param5 = param5; + packet.param6 = param6; + packet.param7 = param7; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.confirmation = confirmation; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif +} + +/** + * @brief Encode a command_long struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param command_long C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_long_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_long_t* command_long) +{ + return mavlink_msg_command_long_pack(system_id, component_id, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); +} + +/** + * @brief Encode a command_long struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param command_long C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_long_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_long_t* command_long) +{ + return mavlink_msg_command_long_pack_chan(system_id, component_id, chan, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); +} + +/** + * @brief Send a command_long message + * @param chan MAVLink channel to send the message + * + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @param param5 Parameter 5, as defined by MAV_CMD enum. + * @param param6 Parameter 6, as defined by MAV_CMD enum. + * @param param7 Parameter 7, as defined by MAV_CMD enum. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_command_long_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, param5); + _mav_put_float(buf, 20, param6); + _mav_put_float(buf, 24, param7); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, confirmation); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif +#else + mavlink_command_long_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.param5 = param5; + packet.param6 = param6; + packet.param7 = param7; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.confirmation = confirmation; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_COMMAND_LONG_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_command_long_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, param5); + _mav_put_float(buf, 20, param6); + _mav_put_float(buf, 24, param7); + _mav_put_uint16_t(buf, 28, command); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, confirmation); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif +#else + mavlink_command_long_t *packet = (mavlink_command_long_t *)msgbuf; + packet->param1 = param1; + packet->param2 = param2; + packet->param3 = param3; + packet->param4 = param4; + packet->param5 = param5; + packet->param6 = param6; + packet->param7 = param7; + packet->command = command; + packet->target_system = target_system; + packet->target_component = target_component; + packet->confirmation = confirmation; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE COMMAND_LONG UNPACKING + + +/** + * @brief Get field target_system from command_long message + * + * @return System which should execute the command + */ +static inline uint8_t mavlink_msg_command_long_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 30); +} + +/** + * @brief Get field target_component from command_long message + * + * @return Component which should execute the command, 0 for all components + */ +static inline uint8_t mavlink_msg_command_long_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 31); +} + +/** + * @brief Get field command from command_long message + * + * @return Command ID, as defined by MAV_CMD enum. + */ +static inline uint16_t mavlink_msg_command_long_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field confirmation from command_long message + * + * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + */ +static inline uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field param1 from command_long message + * + * @return Parameter 1, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param2 from command_long message + * + * @return Parameter 2, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param3 from command_long message + * + * @return Parameter 3, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param4 from command_long message + * + * @return Parameter 4, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field param5 from command_long message + * + * @return Parameter 5, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field param6 from command_long message + * + * @return Parameter 6, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field param7 from command_long message + * + * @return Parameter 7, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param7(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a command_long message into a struct + * + * @param msg The message to decode + * @param command_long C-struct to decode the message contents into + */ +static inline void mavlink_msg_command_long_decode(const mavlink_message_t* msg, mavlink_command_long_t* command_long) +{ +#if MAVLINK_NEED_BYTE_SWAP + command_long->param1 = mavlink_msg_command_long_get_param1(msg); + command_long->param2 = mavlink_msg_command_long_get_param2(msg); + command_long->param3 = mavlink_msg_command_long_get_param3(msg); + command_long->param4 = mavlink_msg_command_long_get_param4(msg); + command_long->param5 = mavlink_msg_command_long_get_param5(msg); + command_long->param6 = mavlink_msg_command_long_get_param6(msg); + command_long->param7 = mavlink_msg_command_long_get_param7(msg); + command_long->command = mavlink_msg_command_long_get_command(msg); + command_long->target_system = mavlink_msg_command_long_get_target_system(msg); + command_long->target_component = mavlink_msg_command_long_get_target_component(msg); + command_long->confirmation = mavlink_msg_command_long_get_confirmation(msg); +#else + memcpy(command_long, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMMAND_LONG_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_control_system_state.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_control_system_state.h new file mode 100644 index 0000000..e06a68f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_control_system_state.h @@ -0,0 +1,587 @@ +// MESSAGE CONTROL_SYSTEM_STATE PACKING + +#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE 146 + +typedef struct __mavlink_control_system_state_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float x_acc; /*< X acceleration in body frame*/ + float y_acc; /*< Y acceleration in body frame*/ + float z_acc; /*< Z acceleration in body frame*/ + float x_vel; /*< X velocity in body frame*/ + float y_vel; /*< Y velocity in body frame*/ + float z_vel; /*< Z velocity in body frame*/ + float x_pos; /*< X position in local frame*/ + float y_pos; /*< Y position in local frame*/ + float z_pos; /*< Z position in local frame*/ + float airspeed; /*< Airspeed, set to -1 if unknown*/ + float vel_variance[3]; /*< Variance of body velocity estimate*/ + float pos_variance[3]; /*< Variance in local position*/ + float q[4]; /*< The attitude, represented as Quaternion*/ + float roll_rate; /*< Angular rate in roll axis*/ + float pitch_rate; /*< Angular rate in pitch axis*/ + float yaw_rate; /*< Angular rate in yaw axis*/ +} mavlink_control_system_state_t; + +#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN 100 +#define MAVLINK_MSG_ID_146_LEN 100 + +#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC 103 +#define MAVLINK_MSG_ID_146_CRC 103 + +#define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_VEL_VARIANCE_LEN 3 +#define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_POS_VARIANCE_LEN 3 +#define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_Q_LEN 4 + +#define MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE { \ + "CONTROL_SYSTEM_STATE", \ + 17, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_control_system_state_t, time_usec) }, \ + { "x_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_control_system_state_t, x_acc) }, \ + { "y_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_control_system_state_t, y_acc) }, \ + { "z_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_control_system_state_t, z_acc) }, \ + { "x_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_control_system_state_t, x_vel) }, \ + { "y_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_control_system_state_t, y_vel) }, \ + { "z_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_control_system_state_t, z_vel) }, \ + { "x_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_control_system_state_t, x_pos) }, \ + { "y_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_control_system_state_t, y_pos) }, \ + { "z_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_control_system_state_t, z_pos) }, \ + { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_control_system_state_t, airspeed) }, \ + { "vel_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 48, offsetof(mavlink_control_system_state_t, vel_variance) }, \ + { "pos_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 60, offsetof(mavlink_control_system_state_t, pos_variance) }, \ + { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 72, offsetof(mavlink_control_system_state_t, q) }, \ + { "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_control_system_state_t, roll_rate) }, \ + { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_control_system_state_t, pitch_rate) }, \ + { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_control_system_state_t, yaw_rate) }, \ + } \ +} + + +/** + * @brief Pack a control_system_state message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param x_acc X acceleration in body frame + * @param y_acc Y acceleration in body frame + * @param z_acc Z acceleration in body frame + * @param x_vel X velocity in body frame + * @param y_vel Y velocity in body frame + * @param z_vel Z velocity in body frame + * @param x_pos X position in local frame + * @param y_pos Y position in local frame + * @param z_pos Z position in local frame + * @param airspeed Airspeed, set to -1 if unknown + * @param vel_variance Variance of body velocity estimate + * @param pos_variance Variance in local position + * @param q The attitude, represented as Quaternion + * @param roll_rate Angular rate in roll axis + * @param pitch_rate Angular rate in pitch axis + * @param yaw_rate Angular rate in yaw axis + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_control_system_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x_acc); + _mav_put_float(buf, 12, y_acc); + _mav_put_float(buf, 16, z_acc); + _mav_put_float(buf, 20, x_vel); + _mav_put_float(buf, 24, y_vel); + _mav_put_float(buf, 28, z_vel); + _mav_put_float(buf, 32, x_pos); + _mav_put_float(buf, 36, y_pos); + _mav_put_float(buf, 40, z_pos); + _mav_put_float(buf, 44, airspeed); + _mav_put_float(buf, 88, roll_rate); + _mav_put_float(buf, 92, pitch_rate); + _mav_put_float(buf, 96, yaw_rate); + _mav_put_float_array(buf, 48, vel_variance, 3); + _mav_put_float_array(buf, 60, pos_variance, 3); + _mav_put_float_array(buf, 72, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#else + mavlink_control_system_state_t packet; + packet.time_usec = time_usec; + packet.x_acc = x_acc; + packet.y_acc = y_acc; + packet.z_acc = z_acc; + packet.x_vel = x_vel; + packet.y_vel = y_vel; + packet.z_vel = z_vel; + packet.x_pos = x_pos; + packet.y_pos = y_pos; + packet.z_pos = z_pos; + packet.airspeed = airspeed; + packet.roll_rate = roll_rate; + packet.pitch_rate = pitch_rate; + packet.yaw_rate = yaw_rate; + mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3); + mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3); + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif +} + +/** + * @brief Pack a control_system_state message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param x_acc X acceleration in body frame + * @param y_acc Y acceleration in body frame + * @param z_acc Z acceleration in body frame + * @param x_vel X velocity in body frame + * @param y_vel Y velocity in body frame + * @param z_vel Z velocity in body frame + * @param x_pos X position in local frame + * @param y_pos Y position in local frame + * @param z_pos Z position in local frame + * @param airspeed Airspeed, set to -1 if unknown + * @param vel_variance Variance of body velocity estimate + * @param pos_variance Variance in local position + * @param q The attitude, represented as Quaternion + * @param roll_rate Angular rate in roll axis + * @param pitch_rate Angular rate in pitch axis + * @param yaw_rate Angular rate in yaw axis + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_control_system_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float x_acc,float y_acc,float z_acc,float x_vel,float y_vel,float z_vel,float x_pos,float y_pos,float z_pos,float airspeed,const float *vel_variance,const float *pos_variance,const float *q,float roll_rate,float pitch_rate,float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x_acc); + _mav_put_float(buf, 12, y_acc); + _mav_put_float(buf, 16, z_acc); + _mav_put_float(buf, 20, x_vel); + _mav_put_float(buf, 24, y_vel); + _mav_put_float(buf, 28, z_vel); + _mav_put_float(buf, 32, x_pos); + _mav_put_float(buf, 36, y_pos); + _mav_put_float(buf, 40, z_pos); + _mav_put_float(buf, 44, airspeed); + _mav_put_float(buf, 88, roll_rate); + _mav_put_float(buf, 92, pitch_rate); + _mav_put_float(buf, 96, yaw_rate); + _mav_put_float_array(buf, 48, vel_variance, 3); + _mav_put_float_array(buf, 60, pos_variance, 3); + _mav_put_float_array(buf, 72, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#else + mavlink_control_system_state_t packet; + packet.time_usec = time_usec; + packet.x_acc = x_acc; + packet.y_acc = y_acc; + packet.z_acc = z_acc; + packet.x_vel = x_vel; + packet.y_vel = y_vel; + packet.z_vel = z_vel; + packet.x_pos = x_pos; + packet.y_pos = y_pos; + packet.z_pos = z_pos; + packet.airspeed = airspeed; + packet.roll_rate = roll_rate; + packet.pitch_rate = pitch_rate; + packet.yaw_rate = yaw_rate; + mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3); + mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3); + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif +} + +/** + * @brief Encode a control_system_state struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param control_system_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_control_system_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_control_system_state_t* control_system_state) +{ + return mavlink_msg_control_system_state_pack(system_id, component_id, msg, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate); +} + +/** + * @brief Encode a control_system_state struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param control_system_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_control_system_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_control_system_state_t* control_system_state) +{ + return mavlink_msg_control_system_state_pack_chan(system_id, component_id, chan, msg, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate); +} + +/** + * @brief Send a control_system_state message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param x_acc X acceleration in body frame + * @param y_acc Y acceleration in body frame + * @param z_acc Z acceleration in body frame + * @param x_vel X velocity in body frame + * @param y_vel Y velocity in body frame + * @param z_vel Z velocity in body frame + * @param x_pos X position in local frame + * @param y_pos Y position in local frame + * @param z_pos Z position in local frame + * @param airspeed Airspeed, set to -1 if unknown + * @param vel_variance Variance of body velocity estimate + * @param pos_variance Variance in local position + * @param q The attitude, represented as Quaternion + * @param roll_rate Angular rate in roll axis + * @param pitch_rate Angular rate in pitch axis + * @param yaw_rate Angular rate in yaw axis + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_control_system_state_send(mavlink_channel_t chan, uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x_acc); + _mav_put_float(buf, 12, y_acc); + _mav_put_float(buf, 16, z_acc); + _mav_put_float(buf, 20, x_vel); + _mav_put_float(buf, 24, y_vel); + _mav_put_float(buf, 28, z_vel); + _mav_put_float(buf, 32, x_pos); + _mav_put_float(buf, 36, y_pos); + _mav_put_float(buf, 40, z_pos); + _mav_put_float(buf, 44, airspeed); + _mav_put_float(buf, 88, roll_rate); + _mav_put_float(buf, 92, pitch_rate); + _mav_put_float(buf, 96, yaw_rate); + _mav_put_float_array(buf, 48, vel_variance, 3); + _mav_put_float_array(buf, 60, pos_variance, 3); + _mav_put_float_array(buf, 72, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif +#else + mavlink_control_system_state_t packet; + packet.time_usec = time_usec; + packet.x_acc = x_acc; + packet.y_acc = y_acc; + packet.z_acc = z_acc; + packet.x_vel = x_vel; + packet.y_vel = y_vel; + packet.z_vel = z_vel; + packet.x_pos = x_pos; + packet.y_pos = y_pos; + packet.z_pos = z_pos; + packet.airspeed = airspeed; + packet.roll_rate = roll_rate; + packet.pitch_rate = pitch_rate; + packet.yaw_rate = yaw_rate; + mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3); + mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3); + mav_array_memcpy(packet.q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)&packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)&packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_control_system_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x_acc); + _mav_put_float(buf, 12, y_acc); + _mav_put_float(buf, 16, z_acc); + _mav_put_float(buf, 20, x_vel); + _mav_put_float(buf, 24, y_vel); + _mav_put_float(buf, 28, z_vel); + _mav_put_float(buf, 32, x_pos); + _mav_put_float(buf, 36, y_pos); + _mav_put_float(buf, 40, z_pos); + _mav_put_float(buf, 44, airspeed); + _mav_put_float(buf, 88, roll_rate); + _mav_put_float(buf, 92, pitch_rate); + _mav_put_float(buf, 96, yaw_rate); + _mav_put_float_array(buf, 48, vel_variance, 3); + _mav_put_float_array(buf, 60, pos_variance, 3); + _mav_put_float_array(buf, 72, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif +#else + mavlink_control_system_state_t *packet = (mavlink_control_system_state_t *)msgbuf; + packet->time_usec = time_usec; + packet->x_acc = x_acc; + packet->y_acc = y_acc; + packet->z_acc = z_acc; + packet->x_vel = x_vel; + packet->y_vel = y_vel; + packet->z_vel = z_vel; + packet->x_pos = x_pos; + packet->y_pos = y_pos; + packet->z_pos = z_pos; + packet->airspeed = airspeed; + packet->roll_rate = roll_rate; + packet->pitch_rate = pitch_rate; + packet->yaw_rate = yaw_rate; + mav_array_memcpy(packet->vel_variance, vel_variance, sizeof(float)*3); + mav_array_memcpy(packet->pos_variance, pos_variance, sizeof(float)*3); + mav_array_memcpy(packet->q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE CONTROL_SYSTEM_STATE UNPACKING + + +/** + * @brief Get field time_usec from control_system_state message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_control_system_state_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x_acc from control_system_state message + * + * @return X acceleration in body frame + */ +static inline float mavlink_msg_control_system_state_get_x_acc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y_acc from control_system_state message + * + * @return Y acceleration in body frame + */ +static inline float mavlink_msg_control_system_state_get_y_acc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z_acc from control_system_state message + * + * @return Z acceleration in body frame + */ +static inline float mavlink_msg_control_system_state_get_z_acc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field x_vel from control_system_state message + * + * @return X velocity in body frame + */ +static inline float mavlink_msg_control_system_state_get_x_vel(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field y_vel from control_system_state message + * + * @return Y velocity in body frame + */ +static inline float mavlink_msg_control_system_state_get_y_vel(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field z_vel from control_system_state message + * + * @return Z velocity in body frame + */ +static inline float mavlink_msg_control_system_state_get_z_vel(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field x_pos from control_system_state message + * + * @return X position in local frame + */ +static inline float mavlink_msg_control_system_state_get_x_pos(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field y_pos from control_system_state message + * + * @return Y position in local frame + */ +static inline float mavlink_msg_control_system_state_get_y_pos(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field z_pos from control_system_state message + * + * @return Z position in local frame + */ +static inline float mavlink_msg_control_system_state_get_z_pos(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field airspeed from control_system_state message + * + * @return Airspeed, set to -1 if unknown + */ +static inline float mavlink_msg_control_system_state_get_airspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field vel_variance from control_system_state message + * + * @return Variance of body velocity estimate + */ +static inline uint16_t mavlink_msg_control_system_state_get_vel_variance(const mavlink_message_t* msg, float *vel_variance) +{ + return _MAV_RETURN_float_array(msg, vel_variance, 3, 48); +} + +/** + * @brief Get field pos_variance from control_system_state message + * + * @return Variance in local position + */ +static inline uint16_t mavlink_msg_control_system_state_get_pos_variance(const mavlink_message_t* msg, float *pos_variance) +{ + return _MAV_RETURN_float_array(msg, pos_variance, 3, 60); +} + +/** + * @brief Get field q from control_system_state message + * + * @return The attitude, represented as Quaternion + */ +static inline uint16_t mavlink_msg_control_system_state_get_q(const mavlink_message_t* msg, float *q) +{ + return _MAV_RETURN_float_array(msg, q, 4, 72); +} + +/** + * @brief Get field roll_rate from control_system_state message + * + * @return Angular rate in roll axis + */ +static inline float mavlink_msg_control_system_state_get_roll_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 88); +} + +/** + * @brief Get field pitch_rate from control_system_state message + * + * @return Angular rate in pitch axis + */ +static inline float mavlink_msg_control_system_state_get_pitch_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 92); +} + +/** + * @brief Get field yaw_rate from control_system_state message + * + * @return Angular rate in yaw axis + */ +static inline float mavlink_msg_control_system_state_get_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 96); +} + +/** + * @brief Decode a control_system_state message into a struct + * + * @param msg The message to decode + * @param control_system_state C-struct to decode the message contents into + */ +static inline void mavlink_msg_control_system_state_decode(const mavlink_message_t* msg, mavlink_control_system_state_t* control_system_state) +{ +#if MAVLINK_NEED_BYTE_SWAP + control_system_state->time_usec = mavlink_msg_control_system_state_get_time_usec(msg); + control_system_state->x_acc = mavlink_msg_control_system_state_get_x_acc(msg); + control_system_state->y_acc = mavlink_msg_control_system_state_get_y_acc(msg); + control_system_state->z_acc = mavlink_msg_control_system_state_get_z_acc(msg); + control_system_state->x_vel = mavlink_msg_control_system_state_get_x_vel(msg); + control_system_state->y_vel = mavlink_msg_control_system_state_get_y_vel(msg); + control_system_state->z_vel = mavlink_msg_control_system_state_get_z_vel(msg); + control_system_state->x_pos = mavlink_msg_control_system_state_get_x_pos(msg); + control_system_state->y_pos = mavlink_msg_control_system_state_get_y_pos(msg); + control_system_state->z_pos = mavlink_msg_control_system_state_get_z_pos(msg); + control_system_state->airspeed = mavlink_msg_control_system_state_get_airspeed(msg); + mavlink_msg_control_system_state_get_vel_variance(msg, control_system_state->vel_variance); + mavlink_msg_control_system_state_get_pos_variance(msg, control_system_state->pos_variance); + mavlink_msg_control_system_state_get_q(msg, control_system_state->q); + control_system_state->roll_rate = mavlink_msg_control_system_state_get_roll_rate(msg); + control_system_state->pitch_rate = mavlink_msg_control_system_state_get_pitch_rate(msg); + control_system_state->yaw_rate = mavlink_msg_control_system_state_get_yaw_rate(msg); +#else + memcpy(control_system_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_data_stream.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_data_stream.h new file mode 100644 index 0000000..0e12a60 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_data_stream.h @@ -0,0 +1,257 @@ +// MESSAGE DATA_STREAM PACKING + +#define MAVLINK_MSG_ID_DATA_STREAM 67 + +typedef struct __mavlink_data_stream_t +{ + uint16_t message_rate; /*< The message rate*/ + uint8_t stream_id; /*< The ID of the requested data stream*/ + uint8_t on_off; /*< 1 stream is enabled, 0 stream is stopped.*/ +} mavlink_data_stream_t; + +#define MAVLINK_MSG_ID_DATA_STREAM_LEN 4 +#define MAVLINK_MSG_ID_67_LEN 4 + +#define MAVLINK_MSG_ID_DATA_STREAM_CRC 21 +#define MAVLINK_MSG_ID_67_CRC 21 + + + +#define MAVLINK_MESSAGE_INFO_DATA_STREAM { \ + "DATA_STREAM", \ + 3, \ + { { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ + { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ + { "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \ + } \ +} + + +/** + * @brief Pack a data_stream message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param stream_id The ID of the requested data stream + * @param message_rate The message rate + * @param on_off 1 stream is enabled, 0 stream is stopped. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t stream_id, uint16_t message_rate, uint8_t on_off) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DATA_STREAM_LEN]; + _mav_put_uint16_t(buf, 0, message_rate); + _mav_put_uint8_t(buf, 2, stream_id); + _mav_put_uint8_t(buf, 3, on_off); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#else + mavlink_data_stream_t packet; + packet.message_rate = message_rate; + packet.stream_id = stream_id; + packet.on_off = on_off; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif +} + +/** + * @brief Pack a data_stream message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param stream_id The ID of the requested data stream + * @param message_rate The message rate + * @param on_off 1 stream is enabled, 0 stream is stopped. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t stream_id,uint16_t message_rate,uint8_t on_off) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DATA_STREAM_LEN]; + _mav_put_uint16_t(buf, 0, message_rate); + _mav_put_uint8_t(buf, 2, stream_id); + _mav_put_uint8_t(buf, 3, on_off); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#else + mavlink_data_stream_t packet; + packet.message_rate = message_rate; + packet.stream_id = stream_id; + packet.on_off = on_off; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif +} + +/** + * @brief Encode a data_stream struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param data_stream C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream) +{ + return mavlink_msg_data_stream_pack(system_id, component_id, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); +} + +/** + * @brief Encode a data_stream struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param data_stream C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream) +{ + return mavlink_msg_data_stream_pack_chan(system_id, component_id, chan, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); +} + +/** + * @brief Send a data_stream message + * @param chan MAVLink channel to send the message + * + * @param stream_id The ID of the requested data stream + * @param message_rate The message rate + * @param on_off 1 stream is enabled, 0 stream is stopped. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_data_stream_send(mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DATA_STREAM_LEN]; + _mav_put_uint16_t(buf, 0, message_rate); + _mav_put_uint8_t(buf, 2, stream_id); + _mav_put_uint8_t(buf, 3, on_off); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif +#else + mavlink_data_stream_t packet; + packet.message_rate = message_rate; + packet.stream_id = stream_id; + packet.on_off = on_off; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_data_stream_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, message_rate); + _mav_put_uint8_t(buf, 2, stream_id); + _mav_put_uint8_t(buf, 3, on_off); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif +#else + mavlink_data_stream_t *packet = (mavlink_data_stream_t *)msgbuf; + packet->message_rate = message_rate; + packet->stream_id = stream_id; + packet->on_off = on_off; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE DATA_STREAM UNPACKING + + +/** + * @brief Get field stream_id from data_stream message + * + * @return The ID of the requested data stream + */ +static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field message_rate from data_stream message + * + * @return The message rate + */ +static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field on_off from data_stream message + * + * @return 1 stream is enabled, 0 stream is stopped. + */ +static inline uint8_t mavlink_msg_data_stream_get_on_off(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Decode a data_stream message into a struct + * + * @param msg The message to decode + * @param data_stream C-struct to decode the message contents into + */ +static inline void mavlink_msg_data_stream_decode(const mavlink_message_t* msg, mavlink_data_stream_t* data_stream) +{ +#if MAVLINK_NEED_BYTE_SWAP + data_stream->message_rate = mavlink_msg_data_stream_get_message_rate(msg); + data_stream->stream_id = mavlink_msg_data_stream_get_stream_id(msg); + data_stream->on_off = mavlink_msg_data_stream_get_on_off(msg); +#else + memcpy(data_stream, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA_STREAM_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h new file mode 100644 index 0000000..c6b037a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h @@ -0,0 +1,353 @@ +// MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING + +#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 130 + +typedef struct __mavlink_data_transmission_handshake_t +{ + uint32_t size; /*< total data size in bytes (set on ACK only)*/ + uint16_t width; /*< Width of a matrix or image*/ + uint16_t height; /*< Height of a matrix or image*/ + uint16_t packets; /*< number of packets beeing sent (set on ACK only)*/ + uint8_t type; /*< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)*/ + uint8_t payload; /*< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)*/ + uint8_t jpg_quality; /*< JPEG quality out of [1,100]*/ +} mavlink_data_transmission_handshake_t; + +#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 13 +#define MAVLINK_MSG_ID_130_LEN 13 + +#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC 29 +#define MAVLINK_MSG_ID_130_CRC 29 + + + +#define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \ + "DATA_TRANSMISSION_HANDSHAKE", \ + 7, \ + { { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \ + { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \ + { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \ + { "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \ + { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \ + { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \ + } \ +} + + +/** + * @brief Pack a data_transmission_handshake message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + * @param size total data size in bytes (set on ACK only) + * @param width Width of a matrix or image + * @param height Height of a matrix or image + * @param packets number of packets beeing sent (set on ACK only) + * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + * @param jpg_quality JPEG quality out of [1,100] + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN]; + _mav_put_uint32_t(buf, 0, size); + _mav_put_uint16_t(buf, 4, width); + _mav_put_uint16_t(buf, 6, height); + _mav_put_uint16_t(buf, 8, packets); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, payload); + _mav_put_uint8_t(buf, 12, jpg_quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#else + mavlink_data_transmission_handshake_t packet; + packet.size = size; + packet.width = width; + packet.height = height; + packet.packets = packets; + packet.type = type; + packet.payload = payload; + packet.jpg_quality = jpg_quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif +} + +/** + * @brief Pack a data_transmission_handshake message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + * @param size total data size in bytes (set on ACK only) + * @param width Width of a matrix or image + * @param height Height of a matrix or image + * @param packets number of packets beeing sent (set on ACK only) + * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + * @param jpg_quality JPEG quality out of [1,100] + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t type,uint32_t size,uint16_t width,uint16_t height,uint16_t packets,uint8_t payload,uint8_t jpg_quality) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN]; + _mav_put_uint32_t(buf, 0, size); + _mav_put_uint16_t(buf, 4, width); + _mav_put_uint16_t(buf, 6, height); + _mav_put_uint16_t(buf, 8, packets); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, payload); + _mav_put_uint8_t(buf, 12, jpg_quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#else + mavlink_data_transmission_handshake_t packet; + packet.size = size; + packet.width = width; + packet.height = height; + packet.packets = packets; + packet.type = type; + packet.payload = payload; + packet.jpg_quality = jpg_quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif +} + +/** + * @brief Encode a data_transmission_handshake struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param data_transmission_handshake C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake) +{ + return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); +} + +/** + * @brief Encode a data_transmission_handshake struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param data_transmission_handshake C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake) +{ + return mavlink_msg_data_transmission_handshake_pack_chan(system_id, component_id, chan, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); +} + +/** + * @brief Send a data_transmission_handshake message + * @param chan MAVLink channel to send the message + * + * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + * @param size total data size in bytes (set on ACK only) + * @param width Width of a matrix or image + * @param height Height of a matrix or image + * @param packets number of packets beeing sent (set on ACK only) + * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + * @param jpg_quality JPEG quality out of [1,100] + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN]; + _mav_put_uint32_t(buf, 0, size); + _mav_put_uint16_t(buf, 4, width); + _mav_put_uint16_t(buf, 6, height); + _mav_put_uint16_t(buf, 8, packets); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, payload); + _mav_put_uint8_t(buf, 12, jpg_quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif +#else + mavlink_data_transmission_handshake_t packet; + packet.size = size; + packet.width = width; + packet.height = height; + packet.packets = packets; + packet.type = type; + packet.payload = payload; + packet.jpg_quality = jpg_quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_data_transmission_handshake_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, size); + _mav_put_uint16_t(buf, 4, width); + _mav_put_uint16_t(buf, 6, height); + _mav_put_uint16_t(buf, 8, packets); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, payload); + _mav_put_uint8_t(buf, 12, jpg_quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif +#else + mavlink_data_transmission_handshake_t *packet = (mavlink_data_transmission_handshake_t *)msgbuf; + packet->size = size; + packet->width = width; + packet->height = height; + packet->packets = packets; + packet->type = type; + packet->payload = payload; + packet->jpg_quality = jpg_quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE DATA_TRANSMISSION_HANDSHAKE UNPACKING + + +/** + * @brief Get field type from data_transmission_handshake message + * + * @return type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + */ +static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 10); +} + +/** + * @brief Get field size from data_transmission_handshake message + * + * @return total data size in bytes (set on ACK only) + */ +static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field width from data_transmission_handshake message + * + * @return Width of a matrix or image + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_get_width(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field height from data_transmission_handshake message + * + * @return Height of a matrix or image + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_get_height(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field packets from data_transmission_handshake message + * + * @return number of packets beeing sent (set on ACK only) + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field payload from data_transmission_handshake message + * + * @return payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + */ +static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 11); +} + +/** + * @brief Get field jpg_quality from data_transmission_handshake message + * + * @return JPEG quality out of [1,100] + */ +static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Decode a data_transmission_handshake message into a struct + * + * @param msg The message to decode + * @param data_transmission_handshake C-struct to decode the message contents into + */ +static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_message_t* msg, mavlink_data_transmission_handshake_t* data_transmission_handshake) +{ +#if MAVLINK_NEED_BYTE_SWAP + data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg); + data_transmission_handshake->width = mavlink_msg_data_transmission_handshake_get_width(msg); + data_transmission_handshake->height = mavlink_msg_data_transmission_handshake_get_height(msg); + data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg); + data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg); + data_transmission_handshake->payload = mavlink_msg_data_transmission_handshake_get_payload(msg); + data_transmission_handshake->jpg_quality = mavlink_msg_data_transmission_handshake_get_jpg_quality(msg); +#else + memcpy(data_transmission_handshake, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_debug.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_debug.h new file mode 100644 index 0000000..56928ab --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_debug.h @@ -0,0 +1,257 @@ +// MESSAGE DEBUG PACKING + +#define MAVLINK_MSG_ID_DEBUG 254 + +typedef struct __mavlink_debug_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float value; /*< DEBUG value*/ + uint8_t ind; /*< index of debug variable*/ +} mavlink_debug_t; + +#define MAVLINK_MSG_ID_DEBUG_LEN 9 +#define MAVLINK_MSG_ID_254_LEN 9 + +#define MAVLINK_MSG_ID_DEBUG_CRC 46 +#define MAVLINK_MSG_ID_254_CRC 46 + + + +#define MAVLINK_MESSAGE_INFO_DEBUG { \ + "DEBUG", \ + 3, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \ + { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \ + { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \ + } \ +} + + +/** + * @brief Pack a debug message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param ind index of debug variable + * @param value DEBUG value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t ind, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DEBUG_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_uint8_t(buf, 8, ind); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_LEN); +#else + mavlink_debug_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + packet.ind = ind; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_LEN); +#endif +} + +/** + * @brief Pack a debug message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param ind index of debug variable + * @param value DEBUG value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t ind,float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DEBUG_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_uint8_t(buf, 8, ind); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_LEN); +#else + mavlink_debug_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + packet.ind = ind; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_LEN); +#endif +} + +/** + * @brief Encode a debug struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param debug C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug) +{ + return mavlink_msg_debug_pack(system_id, component_id, msg, debug->time_boot_ms, debug->ind, debug->value); +} + +/** + * @brief Encode a debug struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param debug C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_debug_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_t* debug) +{ + return mavlink_msg_debug_pack_chan(system_id, component_id, chan, msg, debug->time_boot_ms, debug->ind, debug->value); +} + +/** + * @brief Send a debug message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param ind index of debug variable + * @param value DEBUG value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DEBUG_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_uint8_t(buf, 8, ind); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN); +#endif +#else + mavlink_debug_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + packet.ind = ind; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_DEBUG_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_debug_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_uint8_t(buf, 8, ind); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN); +#endif +#else + mavlink_debug_t *packet = (mavlink_debug_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->value = value; + packet->ind = ind; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)packet, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)packet, MAVLINK_MSG_ID_DEBUG_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE DEBUG UNPACKING + + +/** + * @brief Get field time_boot_ms from debug message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field ind from debug message + * + * @return index of debug variable + */ +static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field value from debug message + * + * @return DEBUG value + */ +static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Decode a debug message into a struct + * + * @param msg The message to decode + * @param debug C-struct to decode the message contents into + */ +static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug) +{ +#if MAVLINK_NEED_BYTE_SWAP + debug->time_boot_ms = mavlink_msg_debug_get_time_boot_ms(msg); + debug->value = mavlink_msg_debug_get_value(msg); + debug->ind = mavlink_msg_debug_get_ind(msg); +#else + memcpy(debug, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DEBUG_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_debug_vect.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_debug_vect.h new file mode 100644 index 0000000..96ac477 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_debug_vect.h @@ -0,0 +1,297 @@ +// MESSAGE DEBUG_VECT PACKING + +#define MAVLINK_MSG_ID_DEBUG_VECT 250 + +typedef struct __mavlink_debug_vect_t +{ + uint64_t time_usec; /*< Timestamp*/ + float x; /*< x*/ + float y; /*< y*/ + float z; /*< z*/ + char name[10]; /*< Name*/ +} mavlink_debug_vect_t; + +#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30 +#define MAVLINK_MSG_ID_250_LEN 30 + +#define MAVLINK_MSG_ID_DEBUG_VECT_CRC 49 +#define MAVLINK_MSG_ID_250_CRC 49 + +#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10 + +#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \ + "DEBUG_VECT", \ + 5, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \ + } \ +} + + +/** + * @brief Pack a debug_vect message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param name Name + * @param time_usec Timestamp + * @param x x + * @param y y + * @param z z + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *name, uint64_t time_usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_char_array(buf, 20, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#else + mavlink_debug_vect_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif +} + +/** + * @brief Pack a debug_vect message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param name Name + * @param time_usec Timestamp + * @param x x + * @param y y + * @param z z + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *name,uint64_t time_usec,float x,float y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_char_array(buf, 20, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#else + mavlink_debug_vect_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif +} + +/** + * @brief Encode a debug_vect struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param debug_vect C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) +{ + return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); +} + +/** + * @brief Encode a debug_vect struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param debug_vect C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_debug_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) +{ + return mavlink_msg_debug_vect_pack_chan(system_id, component_id, chan, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); +} + +/** + * @brief Send a debug_vect message + * @param chan MAVLink channel to send the message + * + * @param name Name + * @param time_usec Timestamp + * @param x x + * @param y y + * @param z z + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_char_array(buf, 20, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif +#else + mavlink_debug_vect_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + mav_array_memcpy(packet.name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_DEBUG_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_debug_vect_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_char_array(buf, 20, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif +#else + mavlink_debug_vect_t *packet = (mavlink_debug_vect_t *)msgbuf; + packet->time_usec = time_usec; + packet->x = x; + packet->y = y; + packet->z = z; + mav_array_memcpy(packet->name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE DEBUG_VECT UNPACKING + + +/** + * @brief Get field name from debug_vect message + * + * @return Name + */ +static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 10, 20); +} + +/** + * @brief Get field time_usec from debug_vect message + * + * @return Timestamp + */ +static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from debug_vect message + * + * @return x + */ +static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from debug_vect message + * + * @return y + */ +static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from debug_vect message + * + * @return z + */ +static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a debug_vect message into a struct + * + * @param msg The message to decode + * @param debug_vect C-struct to decode the message contents into + */ +static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect) +{ +#if MAVLINK_NEED_BYTE_SWAP + debug_vect->time_usec = mavlink_msg_debug_vect_get_time_usec(msg); + debug_vect->x = mavlink_msg_debug_vect_get_x(msg); + debug_vect->y = mavlink_msg_debug_vect_get_y(msg); + debug_vect->z = mavlink_msg_debug_vect_get_z(msg); + mavlink_msg_debug_vect_get_name(msg, debug_vect->name); +#else + memcpy(debug_vect, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DEBUG_VECT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_distance_sensor.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_distance_sensor.h new file mode 100644 index 0000000..dc91ce2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_distance_sensor.h @@ -0,0 +1,377 @@ +// MESSAGE DISTANCE_SENSOR PACKING + +#define MAVLINK_MSG_ID_DISTANCE_SENSOR 132 + +typedef struct __mavlink_distance_sensor_t +{ + uint32_t time_boot_ms; /*< Time since system boot*/ + uint16_t min_distance; /*< Minimum distance the sensor can measure in centimeters*/ + uint16_t max_distance; /*< Maximum distance the sensor can measure in centimeters*/ + uint16_t current_distance; /*< Current distance reading*/ + uint8_t type; /*< Type from MAV_DISTANCE_SENSOR enum.*/ + uint8_t id; /*< Onboard ID of the sensor*/ + uint8_t orientation; /*< Direction the sensor faces from MAV_SENSOR_ORIENTATION enum.*/ + uint8_t covariance; /*< Measurement covariance in centimeters, 0 for unknown / invalid readings*/ +} mavlink_distance_sensor_t; + +#define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14 +#define MAVLINK_MSG_ID_132_LEN 14 + +#define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85 +#define MAVLINK_MSG_ID_132_CRC 85 + + + +#define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \ + "DISTANCE_SENSOR", \ + 8, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \ + { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \ + { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \ + { "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \ + { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \ + { "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \ + { "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \ + } \ +} + + +/** + * @brief Pack a distance_sensor message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Time since system boot + * @param min_distance Minimum distance the sensor can measure in centimeters + * @param max_distance Maximum distance the sensor can measure in centimeters + * @param current_distance Current distance reading + * @param type Type from MAV_DISTANCE_SENSOR enum. + * @param id Onboard ID of the sensor + * @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. + * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, min_distance); + _mav_put_uint16_t(buf, 6, max_distance); + _mav_put_uint16_t(buf, 8, current_distance); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, id); + _mav_put_uint8_t(buf, 12, orientation); + _mav_put_uint8_t(buf, 13, covariance); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#else + mavlink_distance_sensor_t packet; + packet.time_boot_ms = time_boot_ms; + packet.min_distance = min_distance; + packet.max_distance = max_distance; + packet.current_distance = current_distance; + packet.type = type; + packet.id = id; + packet.orientation = orientation; + packet.covariance = covariance; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif +} + +/** + * @brief Pack a distance_sensor message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Time since system boot + * @param min_distance Minimum distance the sensor can measure in centimeters + * @param max_distance Maximum distance the sensor can measure in centimeters + * @param current_distance Current distance reading + * @param type Type from MAV_DISTANCE_SENSOR enum. + * @param id Onboard ID of the sensor + * @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. + * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint16_t min_distance,uint16_t max_distance,uint16_t current_distance,uint8_t type,uint8_t id,uint8_t orientation,uint8_t covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, min_distance); + _mav_put_uint16_t(buf, 6, max_distance); + _mav_put_uint16_t(buf, 8, current_distance); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, id); + _mav_put_uint8_t(buf, 12, orientation); + _mav_put_uint8_t(buf, 13, covariance); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#else + mavlink_distance_sensor_t packet; + packet.time_boot_ms = time_boot_ms; + packet.min_distance = min_distance; + packet.max_distance = max_distance; + packet.current_distance = current_distance; + packet.type = type; + packet.id = id; + packet.orientation = orientation; + packet.covariance = covariance; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif +} + +/** + * @brief Encode a distance_sensor struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param distance_sensor C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_distance_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor) +{ + return mavlink_msg_distance_sensor_pack(system_id, component_id, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance); +} + +/** + * @brief Encode a distance_sensor struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param distance_sensor C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor) +{ + return mavlink_msg_distance_sensor_pack_chan(system_id, component_id, chan, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance); +} + +/** + * @brief Send a distance_sensor message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Time since system boot + * @param min_distance Minimum distance the sensor can measure in centimeters + * @param max_distance Maximum distance the sensor can measure in centimeters + * @param current_distance Current distance reading + * @param type Type from MAV_DISTANCE_SENSOR enum. + * @param id Onboard ID of the sensor + * @param orientation Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. + * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, min_distance); + _mav_put_uint16_t(buf, 6, max_distance); + _mav_put_uint16_t(buf, 8, current_distance); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, id); + _mav_put_uint8_t(buf, 12, orientation); + _mav_put_uint8_t(buf, 13, covariance); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif +#else + mavlink_distance_sensor_t packet; + packet.time_boot_ms = time_boot_ms; + packet.min_distance = min_distance; + packet.max_distance = max_distance; + packet.current_distance = current_distance; + packet.type = type; + packet.id = id; + packet.orientation = orientation; + packet.covariance = covariance; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, min_distance); + _mav_put_uint16_t(buf, 6, max_distance); + _mav_put_uint16_t(buf, 8, current_distance); + _mav_put_uint8_t(buf, 10, type); + _mav_put_uint8_t(buf, 11, id); + _mav_put_uint8_t(buf, 12, orientation); + _mav_put_uint8_t(buf, 13, covariance); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif +#else + mavlink_distance_sensor_t *packet = (mavlink_distance_sensor_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->min_distance = min_distance; + packet->max_distance = max_distance; + packet->current_distance = current_distance; + packet->type = type; + packet->id = id; + packet->orientation = orientation; + packet->covariance = covariance; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE DISTANCE_SENSOR UNPACKING + + +/** + * @brief Get field time_boot_ms from distance_sensor message + * + * @return Time since system boot + */ +static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field min_distance from distance_sensor message + * + * @return Minimum distance the sensor can measure in centimeters + */ +static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field max_distance from distance_sensor message + * + * @return Maximum distance the sensor can measure in centimeters + */ +static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field current_distance from distance_sensor message + * + * @return Current distance reading + */ +static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field type from distance_sensor message + * + * @return Type from MAV_DISTANCE_SENSOR enum. + */ +static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 10); +} + +/** + * @brief Get field id from distance_sensor message + * + * @return Onboard ID of the sensor + */ +static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 11); +} + +/** + * @brief Get field orientation from distance_sensor message + * + * @return Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. + */ +static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field covariance from distance_sensor message + * + * @return Measurement covariance in centimeters, 0 for unknown / invalid readings + */ +static inline uint8_t mavlink_msg_distance_sensor_get_covariance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 13); +} + +/** + * @brief Decode a distance_sensor message into a struct + * + * @param msg The message to decode + * @param distance_sensor C-struct to decode the message contents into + */ +static inline void mavlink_msg_distance_sensor_decode(const mavlink_message_t* msg, mavlink_distance_sensor_t* distance_sensor) +{ +#if MAVLINK_NEED_BYTE_SWAP + distance_sensor->time_boot_ms = mavlink_msg_distance_sensor_get_time_boot_ms(msg); + distance_sensor->min_distance = mavlink_msg_distance_sensor_get_min_distance(msg); + distance_sensor->max_distance = mavlink_msg_distance_sensor_get_max_distance(msg); + distance_sensor->current_distance = mavlink_msg_distance_sensor_get_current_distance(msg); + distance_sensor->type = mavlink_msg_distance_sensor_get_type(msg); + distance_sensor->id = mavlink_msg_distance_sensor_get_id(msg); + distance_sensor->orientation = mavlink_msg_distance_sensor_get_orientation(msg); + distance_sensor->covariance = mavlink_msg_distance_sensor_get_covariance(msg); +#else + memcpy(distance_sensor, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h new file mode 100644 index 0000000..216738b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h @@ -0,0 +1,225 @@ +// MESSAGE ENCAPSULATED_DATA PACKING + +#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 131 + +typedef struct __mavlink_encapsulated_data_t +{ + uint16_t seqnr; /*< sequence number (starting with 0 on every transmission)*/ + uint8_t data[253]; /*< image data bytes*/ +} mavlink_encapsulated_data_t; + +#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255 +#define MAVLINK_MSG_ID_131_LEN 255 + +#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC 223 +#define MAVLINK_MSG_ID_131_CRC 223 + +#define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253 + +#define MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA { \ + "ENCAPSULATED_DATA", \ + 2, \ + { { "seqnr", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_encapsulated_data_t, seqnr) }, \ + { "data", NULL, MAVLINK_TYPE_UINT8_T, 253, 2, offsetof(mavlink_encapsulated_data_t, data) }, \ + } \ +} + + +/** + * @brief Pack a encapsulated_data message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param seqnr sequence number (starting with 0 on every transmission) + * @param data image data bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t seqnr, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN]; + _mav_put_uint16_t(buf, 0, seqnr); + _mav_put_uint8_t_array(buf, 2, data, 253); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#else + mavlink_encapsulated_data_t packet; + packet.seqnr = seqnr; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif +} + +/** + * @brief Pack a encapsulated_data message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param seqnr sequence number (starting with 0 on every transmission) + * @param data image data bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t seqnr,const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN]; + _mav_put_uint16_t(buf, 0, seqnr); + _mav_put_uint8_t_array(buf, 2, data, 253); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#else + mavlink_encapsulated_data_t packet; + packet.seqnr = seqnr; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif +} + +/** + * @brief Encode a encapsulated_data struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param encapsulated_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data) +{ + return mavlink_msg_encapsulated_data_pack(system_id, component_id, msg, encapsulated_data->seqnr, encapsulated_data->data); +} + +/** + * @brief Encode a encapsulated_data struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param encapsulated_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_encapsulated_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data) +{ + return mavlink_msg_encapsulated_data_pack_chan(system_id, component_id, chan, msg, encapsulated_data->seqnr, encapsulated_data->data); +} + +/** + * @brief Send a encapsulated_data message + * @param chan MAVLink channel to send the message + * + * @param seqnr sequence number (starting with 0 on every transmission) + * @param data image data bytes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_encapsulated_data_send(mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN]; + _mav_put_uint16_t(buf, 0, seqnr); + _mav_put_uint8_t_array(buf, 2, data, 253); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif +#else + mavlink_encapsulated_data_t packet; + packet.seqnr = seqnr; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_encapsulated_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, seqnr); + _mav_put_uint8_t_array(buf, 2, data, 253); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif +#else + mavlink_encapsulated_data_t *packet = (mavlink_encapsulated_data_t *)msgbuf; + packet->seqnr = seqnr; + mav_array_memcpy(packet->data, data, sizeof(uint8_t)*253); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ENCAPSULATED_DATA UNPACKING + + +/** + * @brief Get field seqnr from encapsulated_data message + * + * @return sequence number (starting with 0 on every transmission) + */ +static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field data from encapsulated_data message + * + * @return image data bytes + */ +static inline uint16_t mavlink_msg_encapsulated_data_get_data(const mavlink_message_t* msg, uint8_t *data) +{ + return _MAV_RETURN_uint8_t_array(msg, data, 253, 2); +} + +/** + * @brief Decode a encapsulated_data message into a struct + * + * @param msg The message to decode + * @param encapsulated_data C-struct to decode the message contents into + */ +static inline void mavlink_msg_encapsulated_data_decode(const mavlink_message_t* msg, mavlink_encapsulated_data_t* encapsulated_data) +{ +#if MAVLINK_NEED_BYTE_SWAP + encapsulated_data->seqnr = mavlink_msg_encapsulated_data_get_seqnr(msg); + mavlink_msg_encapsulated_data_get_data(msg, encapsulated_data->data); +#else + memcpy(encapsulated_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_estimator_status.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_estimator_status.h new file mode 100644 index 0000000..f06d609 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_estimator_status.h @@ -0,0 +1,425 @@ +// MESSAGE ESTIMATOR_STATUS PACKING + +#define MAVLINK_MSG_ID_ESTIMATOR_STATUS 230 + +typedef struct __mavlink_estimator_status_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float vel_ratio; /*< Velocity innovation test ratio*/ + float pos_horiz_ratio; /*< Horizontal position innovation test ratio*/ + float pos_vert_ratio; /*< Vertical position innovation test ratio*/ + float mag_ratio; /*< Magnetometer innovation test ratio*/ + float hagl_ratio; /*< Height above terrain innovation test ratio*/ + float tas_ratio; /*< True airspeed innovation test ratio*/ + float pos_horiz_accuracy; /*< Horizontal position 1-STD accuracy relative to the EKF local origin (m)*/ + float pos_vert_accuracy; /*< Vertical position 1-STD accuracy relative to the EKF local origin (m)*/ + uint16_t flags; /*< Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.*/ +} mavlink_estimator_status_t; + +#define MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN 42 +#define MAVLINK_MSG_ID_230_LEN 42 + +#define MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC 163 +#define MAVLINK_MSG_ID_230_CRC 163 + + + +#define MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS { \ + "ESTIMATOR_STATUS", \ + 10, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_estimator_status_t, time_usec) }, \ + { "vel_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_estimator_status_t, vel_ratio) }, \ + { "pos_horiz_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_estimator_status_t, pos_horiz_ratio) }, \ + { "pos_vert_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_estimator_status_t, pos_vert_ratio) }, \ + { "mag_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_estimator_status_t, mag_ratio) }, \ + { "hagl_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_estimator_status_t, hagl_ratio) }, \ + { "tas_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_estimator_status_t, tas_ratio) }, \ + { "pos_horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_estimator_status_t, pos_horiz_accuracy) }, \ + { "pos_vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_estimator_status_t, pos_vert_accuracy) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \ + } \ +} + + +/** + * @brief Pack a estimator_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. + * @param vel_ratio Velocity innovation test ratio + * @param pos_horiz_ratio Horizontal position innovation test ratio + * @param pos_vert_ratio Vertical position innovation test ratio + * @param mag_ratio Magnetometer innovation test ratio + * @param hagl_ratio Height above terrain innovation test ratio + * @param tas_ratio True airspeed innovation test ratio + * @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m) + * @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_estimator_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint16_t flags, float vel_ratio, float pos_horiz_ratio, float pos_vert_ratio, float mag_ratio, float hagl_ratio, float tas_ratio, float pos_horiz_accuracy, float pos_vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vel_ratio); + _mav_put_float(buf, 12, pos_horiz_ratio); + _mav_put_float(buf, 16, pos_vert_ratio); + _mav_put_float(buf, 20, mag_ratio); + _mav_put_float(buf, 24, hagl_ratio); + _mav_put_float(buf, 28, tas_ratio); + _mav_put_float(buf, 32, pos_horiz_accuracy); + _mav_put_float(buf, 36, pos_vert_accuracy); + _mav_put_uint16_t(buf, 40, flags); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#else + mavlink_estimator_status_t packet; + packet.time_usec = time_usec; + packet.vel_ratio = vel_ratio; + packet.pos_horiz_ratio = pos_horiz_ratio; + packet.pos_vert_ratio = pos_vert_ratio; + packet.mag_ratio = mag_ratio; + packet.hagl_ratio = hagl_ratio; + packet.tas_ratio = tas_ratio; + packet.pos_horiz_accuracy = pos_horiz_accuracy; + packet.pos_vert_accuracy = pos_vert_accuracy; + packet.flags = flags; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ESTIMATOR_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif +} + +/** + * @brief Pack a estimator_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. + * @param vel_ratio Velocity innovation test ratio + * @param pos_horiz_ratio Horizontal position innovation test ratio + * @param pos_vert_ratio Vertical position innovation test ratio + * @param mag_ratio Magnetometer innovation test ratio + * @param hagl_ratio Height above terrain innovation test ratio + * @param tas_ratio True airspeed innovation test ratio + * @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m) + * @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_estimator_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint16_t flags,float vel_ratio,float pos_horiz_ratio,float pos_vert_ratio,float mag_ratio,float hagl_ratio,float tas_ratio,float pos_horiz_accuracy,float pos_vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vel_ratio); + _mav_put_float(buf, 12, pos_horiz_ratio); + _mav_put_float(buf, 16, pos_vert_ratio); + _mav_put_float(buf, 20, mag_ratio); + _mav_put_float(buf, 24, hagl_ratio); + _mav_put_float(buf, 28, tas_ratio); + _mav_put_float(buf, 32, pos_horiz_accuracy); + _mav_put_float(buf, 36, pos_vert_accuracy); + _mav_put_uint16_t(buf, 40, flags); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#else + mavlink_estimator_status_t packet; + packet.time_usec = time_usec; + packet.vel_ratio = vel_ratio; + packet.pos_horiz_ratio = pos_horiz_ratio; + packet.pos_vert_ratio = pos_vert_ratio; + packet.mag_ratio = mag_ratio; + packet.hagl_ratio = hagl_ratio; + packet.tas_ratio = tas_ratio; + packet.pos_horiz_accuracy = pos_horiz_accuracy; + packet.pos_vert_accuracy = pos_vert_accuracy; + packet.flags = flags; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ESTIMATOR_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif +} + +/** + * @brief Encode a estimator_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param estimator_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_estimator_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_estimator_status_t* estimator_status) +{ + return mavlink_msg_estimator_status_pack(system_id, component_id, msg, estimator_status->time_usec, estimator_status->flags, estimator_status->vel_ratio, estimator_status->pos_horiz_ratio, estimator_status->pos_vert_ratio, estimator_status->mag_ratio, estimator_status->hagl_ratio, estimator_status->tas_ratio, estimator_status->pos_horiz_accuracy, estimator_status->pos_vert_accuracy); +} + +/** + * @brief Encode a estimator_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param estimator_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_estimator_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_estimator_status_t* estimator_status) +{ + return mavlink_msg_estimator_status_pack_chan(system_id, component_id, chan, msg, estimator_status->time_usec, estimator_status->flags, estimator_status->vel_ratio, estimator_status->pos_horiz_ratio, estimator_status->pos_vert_ratio, estimator_status->mag_ratio, estimator_status->hagl_ratio, estimator_status->tas_ratio, estimator_status->pos_horiz_accuracy, estimator_status->pos_vert_accuracy); +} + +/** + * @brief Send a estimator_status message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param flags Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. + * @param vel_ratio Velocity innovation test ratio + * @param pos_horiz_ratio Horizontal position innovation test ratio + * @param pos_vert_ratio Vertical position innovation test ratio + * @param mag_ratio Magnetometer innovation test ratio + * @param hagl_ratio Height above terrain innovation test ratio + * @param tas_ratio True airspeed innovation test ratio + * @param pos_horiz_accuracy Horizontal position 1-STD accuracy relative to the EKF local origin (m) + * @param pos_vert_accuracy Vertical position 1-STD accuracy relative to the EKF local origin (m) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_estimator_status_send(mavlink_channel_t chan, uint64_t time_usec, uint16_t flags, float vel_ratio, float pos_horiz_ratio, float pos_vert_ratio, float mag_ratio, float hagl_ratio, float tas_ratio, float pos_horiz_accuracy, float pos_vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vel_ratio); + _mav_put_float(buf, 12, pos_horiz_ratio); + _mav_put_float(buf, 16, pos_vert_ratio); + _mav_put_float(buf, 20, mag_ratio); + _mav_put_float(buf, 24, hagl_ratio); + _mav_put_float(buf, 28, tas_ratio); + _mav_put_float(buf, 32, pos_horiz_accuracy); + _mav_put_float(buf, 36, pos_vert_accuracy); + _mav_put_uint16_t(buf, 40, flags); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif +#else + mavlink_estimator_status_t packet; + packet.time_usec = time_usec; + packet.vel_ratio = vel_ratio; + packet.pos_horiz_ratio = pos_horiz_ratio; + packet.pos_vert_ratio = pos_vert_ratio; + packet.mag_ratio = mag_ratio; + packet.hagl_ratio = hagl_ratio; + packet.tas_ratio = tas_ratio; + packet.pos_horiz_accuracy = pos_horiz_accuracy; + packet.pos_vert_accuracy = pos_vert_accuracy; + packet.flags = flags; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_estimator_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint16_t flags, float vel_ratio, float pos_horiz_ratio, float pos_vert_ratio, float mag_ratio, float hagl_ratio, float tas_ratio, float pos_horiz_accuracy, float pos_vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vel_ratio); + _mav_put_float(buf, 12, pos_horiz_ratio); + _mav_put_float(buf, 16, pos_vert_ratio); + _mav_put_float(buf, 20, mag_ratio); + _mav_put_float(buf, 24, hagl_ratio); + _mav_put_float(buf, 28, tas_ratio); + _mav_put_float(buf, 32, pos_horiz_accuracy); + _mav_put_float(buf, 36, pos_vert_accuracy); + _mav_put_uint16_t(buf, 40, flags); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif +#else + mavlink_estimator_status_t *packet = (mavlink_estimator_status_t *)msgbuf; + packet->time_usec = time_usec; + packet->vel_ratio = vel_ratio; + packet->pos_horiz_ratio = pos_horiz_ratio; + packet->pos_vert_ratio = pos_vert_ratio; + packet->mag_ratio = mag_ratio; + packet->hagl_ratio = hagl_ratio; + packet->tas_ratio = tas_ratio; + packet->pos_horiz_accuracy = pos_horiz_accuracy; + packet->pos_vert_accuracy = pos_vert_accuracy; + packet->flags = flags; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ESTIMATOR_STATUS UNPACKING + + +/** + * @brief Get field time_usec from estimator_status message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_estimator_status_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field flags from estimator_status message + * + * @return Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. + */ +static inline uint16_t mavlink_msg_estimator_status_get_flags(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 40); +} + +/** + * @brief Get field vel_ratio from estimator_status message + * + * @return Velocity innovation test ratio + */ +static inline float mavlink_msg_estimator_status_get_vel_ratio(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field pos_horiz_ratio from estimator_status message + * + * @return Horizontal position innovation test ratio + */ +static inline float mavlink_msg_estimator_status_get_pos_horiz_ratio(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field pos_vert_ratio from estimator_status message + * + * @return Vertical position innovation test ratio + */ +static inline float mavlink_msg_estimator_status_get_pos_vert_ratio(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field mag_ratio from estimator_status message + * + * @return Magnetometer innovation test ratio + */ +static inline float mavlink_msg_estimator_status_get_mag_ratio(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field hagl_ratio from estimator_status message + * + * @return Height above terrain innovation test ratio + */ +static inline float mavlink_msg_estimator_status_get_hagl_ratio(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field tas_ratio from estimator_status message + * + * @return True airspeed innovation test ratio + */ +static inline float mavlink_msg_estimator_status_get_tas_ratio(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field pos_horiz_accuracy from estimator_status message + * + * @return Horizontal position 1-STD accuracy relative to the EKF local origin (m) + */ +static inline float mavlink_msg_estimator_status_get_pos_horiz_accuracy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field pos_vert_accuracy from estimator_status message + * + * @return Vertical position 1-STD accuracy relative to the EKF local origin (m) + */ +static inline float mavlink_msg_estimator_status_get_pos_vert_accuracy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Decode a estimator_status message into a struct + * + * @param msg The message to decode + * @param estimator_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_estimator_status_decode(const mavlink_message_t* msg, mavlink_estimator_status_t* estimator_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + estimator_status->time_usec = mavlink_msg_estimator_status_get_time_usec(msg); + estimator_status->vel_ratio = mavlink_msg_estimator_status_get_vel_ratio(msg); + estimator_status->pos_horiz_ratio = mavlink_msg_estimator_status_get_pos_horiz_ratio(msg); + estimator_status->pos_vert_ratio = mavlink_msg_estimator_status_get_pos_vert_ratio(msg); + estimator_status->mag_ratio = mavlink_msg_estimator_status_get_mag_ratio(msg); + estimator_status->hagl_ratio = mavlink_msg_estimator_status_get_hagl_ratio(msg); + estimator_status->tas_ratio = mavlink_msg_estimator_status_get_tas_ratio(msg); + estimator_status->pos_horiz_accuracy = mavlink_msg_estimator_status_get_pos_horiz_accuracy(msg); + estimator_status->pos_vert_accuracy = mavlink_msg_estimator_status_get_pos_vert_accuracy(msg); + estimator_status->flags = mavlink_msg_estimator_status_get_flags(msg); +#else + memcpy(estimator_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_extended_sys_state.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_extended_sys_state.h new file mode 100644 index 0000000..b3c4886 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_extended_sys_state.h @@ -0,0 +1,233 @@ +// MESSAGE EXTENDED_SYS_STATE PACKING + +#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE 245 + +typedef struct __mavlink_extended_sys_state_t +{ + uint8_t vtol_state; /*< The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.*/ + uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/ +} mavlink_extended_sys_state_t; + +#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN 2 +#define MAVLINK_MSG_ID_245_LEN 2 + +#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC 130 +#define MAVLINK_MSG_ID_245_CRC 130 + + + +#define MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE { \ + "EXTENDED_SYS_STATE", \ + 2, \ + { { "vtol_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_extended_sys_state_t, vtol_state) }, \ + { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_extended_sys_state_t, landed_state) }, \ + } \ +} + + +/** + * @brief Pack a extended_sys_state message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_extended_sys_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t vtol_state, uint8_t landed_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN]; + _mav_put_uint8_t(buf, 0, vtol_state); + _mav_put_uint8_t(buf, 1, landed_state); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#else + mavlink_extended_sys_state_t packet; + packet.vtol_state = vtol_state; + packet.landed_state = landed_state; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_EXTENDED_SYS_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif +} + +/** + * @brief Pack a extended_sys_state message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_extended_sys_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t vtol_state,uint8_t landed_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN]; + _mav_put_uint8_t(buf, 0, vtol_state); + _mav_put_uint8_t(buf, 1, landed_state); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#else + mavlink_extended_sys_state_t packet; + packet.vtol_state = vtol_state; + packet.landed_state = landed_state; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_EXTENDED_SYS_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif +} + +/** + * @brief Encode a extended_sys_state struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param extended_sys_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_extended_sys_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_extended_sys_state_t* extended_sys_state) +{ + return mavlink_msg_extended_sys_state_pack(system_id, component_id, msg, extended_sys_state->vtol_state, extended_sys_state->landed_state); +} + +/** + * @brief Encode a extended_sys_state struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param extended_sys_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_extended_sys_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_extended_sys_state_t* extended_sys_state) +{ + return mavlink_msg_extended_sys_state_pack_chan(system_id, component_id, chan, msg, extended_sys_state->vtol_state, extended_sys_state->landed_state); +} + +/** + * @brief Send a extended_sys_state message + * @param chan MAVLink channel to send the message + * + * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_extended_sys_state_send(mavlink_channel_t chan, uint8_t vtol_state, uint8_t landed_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN]; + _mav_put_uint8_t(buf, 0, vtol_state); + _mav_put_uint8_t(buf, 1, landed_state); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif +#else + mavlink_extended_sys_state_t packet; + packet.vtol_state = vtol_state; + packet.landed_state = landed_state; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)&packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)&packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_extended_sys_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t vtol_state, uint8_t landed_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, vtol_state); + _mav_put_uint8_t(buf, 1, landed_state); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif +#else + mavlink_extended_sys_state_t *packet = (mavlink_extended_sys_state_t *)msgbuf; + packet->vtol_state = vtol_state; + packet->landed_state = landed_state; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE EXTENDED_SYS_STATE UNPACKING + + +/** + * @brief Get field vtol_state from extended_sys_state message + * + * @return The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + */ +static inline uint8_t mavlink_msg_extended_sys_state_get_vtol_state(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field landed_state from extended_sys_state message + * + * @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + */ +static inline uint8_t mavlink_msg_extended_sys_state_get_landed_state(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a extended_sys_state message into a struct + * + * @param msg The message to decode + * @param extended_sys_state C-struct to decode the message contents into + */ +static inline void mavlink_msg_extended_sys_state_decode(const mavlink_message_t* msg, mavlink_extended_sys_state_t* extended_sys_state) +{ +#if MAVLINK_NEED_BYTE_SWAP + extended_sys_state->vtol_state = mavlink_msg_extended_sys_state_get_vtol_state(msg); + extended_sys_state->landed_state = mavlink_msg_extended_sys_state_get_landed_state(msg); +#else + memcpy(extended_sys_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_file_transfer_protocol.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_file_transfer_protocol.h new file mode 100644 index 0000000..72865a9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_file_transfer_protocol.h @@ -0,0 +1,273 @@ +// MESSAGE FILE_TRANSFER_PROTOCOL PACKING + +#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL 110 + +typedef struct __mavlink_file_transfer_protocol_t +{ + uint8_t target_network; /*< Network ID (0 for broadcast)*/ + uint8_t target_system; /*< System ID (0 for broadcast)*/ + uint8_t target_component; /*< Component ID (0 for broadcast)*/ + uint8_t payload[251]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.*/ +} mavlink_file_transfer_protocol_t; + +#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN 254 +#define MAVLINK_MSG_ID_110_LEN 254 + +#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC 84 +#define MAVLINK_MSG_ID_110_CRC 84 + +#define MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN 251 + +#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL { \ + "FILE_TRANSFER_PROTOCOL", \ + 4, \ + { { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_file_transfer_protocol_t, target_network) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_file_transfer_protocol_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_file_transfer_protocol_t, target_component) }, \ + { "payload", NULL, MAVLINK_TYPE_UINT8_T, 251, 3, offsetof(mavlink_file_transfer_protocol_t, payload) }, \ + } \ +} + + +/** + * @brief Pack a file_transfer_protocol message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_file_transfer_protocol_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN]; + _mav_put_uint8_t(buf, 0, target_network); + _mav_put_uint8_t(buf, 1, target_system); + _mav_put_uint8_t(buf, 2, target_component); + _mav_put_uint8_t_array(buf, 3, payload, 251); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#else + mavlink_file_transfer_protocol_t packet; + packet.target_network = target_network; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif +} + +/** + * @brief Pack a file_transfer_protocol message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_file_transfer_protocol_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_network,uint8_t target_system,uint8_t target_component,const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN]; + _mav_put_uint8_t(buf, 0, target_network); + _mav_put_uint8_t(buf, 1, target_system); + _mav_put_uint8_t(buf, 2, target_component); + _mav_put_uint8_t_array(buf, 3, payload, 251); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#else + mavlink_file_transfer_protocol_t packet; + packet.target_network = target_network; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif +} + +/** + * @brief Encode a file_transfer_protocol struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param file_transfer_protocol C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_file_transfer_protocol_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol) +{ + return mavlink_msg_file_transfer_protocol_pack(system_id, component_id, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload); +} + +/** + * @brief Encode a file_transfer_protocol struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param file_transfer_protocol C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_file_transfer_protocol_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol) +{ + return mavlink_msg_file_transfer_protocol_pack_chan(system_id, component_id, chan, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload); +} + +/** + * @brief Send a file_transfer_protocol message + * @param chan MAVLink channel to send the message + * + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_file_transfer_protocol_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN]; + _mav_put_uint8_t(buf, 0, target_network); + _mav_put_uint8_t(buf, 1, target_system); + _mav_put_uint8_t(buf, 2, target_component); + _mav_put_uint8_t_array(buf, 3, payload, 251); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif +#else + mavlink_file_transfer_protocol_t packet; + packet.target_network = target_network; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_file_transfer_protocol_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_network); + _mav_put_uint8_t(buf, 1, target_system); + _mav_put_uint8_t(buf, 2, target_component); + _mav_put_uint8_t_array(buf, 3, payload, 251); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif +#else + mavlink_file_transfer_protocol_t *packet = (mavlink_file_transfer_protocol_t *)msgbuf; + packet->target_network = target_network; + packet->target_system = target_system; + packet->target_component = target_component; + mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*251); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE FILE_TRANSFER_PROTOCOL UNPACKING + + +/** + * @brief Get field target_network from file_transfer_protocol message + * + * @return Network ID (0 for broadcast) + */ +static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_network(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_system from file_transfer_protocol message + * + * @return System ID (0 for broadcast) + */ +static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field target_component from file_transfer_protocol message + * + * @return Component ID (0 for broadcast) + */ +static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field payload from file_transfer_protocol message + * + * @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + */ +static inline uint16_t mavlink_msg_file_transfer_protocol_get_payload(const mavlink_message_t* msg, uint8_t *payload) +{ + return _MAV_RETURN_uint8_t_array(msg, payload, 251, 3); +} + +/** + * @brief Decode a file_transfer_protocol message into a struct + * + * @param msg The message to decode + * @param file_transfer_protocol C-struct to decode the message contents into + */ +static inline void mavlink_msg_file_transfer_protocol_decode(const mavlink_message_t* msg, mavlink_file_transfer_protocol_t* file_transfer_protocol) +{ +#if MAVLINK_NEED_BYTE_SWAP + file_transfer_protocol->target_network = mavlink_msg_file_transfer_protocol_get_target_network(msg); + file_transfer_protocol->target_system = mavlink_msg_file_transfer_protocol_get_target_system(msg); + file_transfer_protocol->target_component = mavlink_msg_file_transfer_protocol_get_target_component(msg); + mavlink_msg_file_transfer_protocol_get_payload(msg, file_transfer_protocol->payload); +#else + memcpy(file_transfer_protocol, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_follow_target.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_follow_target.h new file mode 100644 index 0000000..24c9ffa --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_follow_target.h @@ -0,0 +1,445 @@ +// MESSAGE FOLLOW_TARGET PACKING + +#define MAVLINK_MSG_ID_FOLLOW_TARGET 144 + +typedef struct __mavlink_follow_target_t +{ + uint64_t timestamp; /*< Timestamp in milliseconds since system boot*/ + uint64_t custom_state; /*< button states or switches of a tracker device*/ + int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ + float alt; /*< AMSL, in meters*/ + float vel[3]; /*< target velocity (0,0,0) for unknown*/ + float acc[3]; /*< linear target acceleration (0,0,0) for unknown*/ + float attitude_q[4]; /*< (1 0 0 0 for unknown)*/ + float rates[3]; /*< (0 0 0 for unknown)*/ + float position_cov[3]; /*< eph epv*/ + uint8_t est_capabilities; /*< bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)*/ +} mavlink_follow_target_t; + +#define MAVLINK_MSG_ID_FOLLOW_TARGET_LEN 93 +#define MAVLINK_MSG_ID_144_LEN 93 + +#define MAVLINK_MSG_ID_FOLLOW_TARGET_CRC 127 +#define MAVLINK_MSG_ID_144_CRC 127 + +#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_VEL_LEN 3 +#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ACC_LEN 3 +#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ATTITUDE_Q_LEN 4 +#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_RATES_LEN 3 +#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_POSITION_COV_LEN 3 + +#define MAVLINK_MESSAGE_INFO_FOLLOW_TARGET { \ + "FOLLOW_TARGET", \ + 11, \ + { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_follow_target_t, timestamp) }, \ + { "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_follow_target_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_follow_target_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_follow_target_t, alt) }, \ + { "vel", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_follow_target_t, vel) }, \ + { "acc", NULL, MAVLINK_TYPE_FLOAT, 3, 40, offsetof(mavlink_follow_target_t, acc) }, \ + { "attitude_q", NULL, MAVLINK_TYPE_FLOAT, 4, 52, offsetof(mavlink_follow_target_t, attitude_q) }, \ + { "rates", NULL, MAVLINK_TYPE_FLOAT, 3, 68, offsetof(mavlink_follow_target_t, rates) }, \ + { "position_cov", NULL, MAVLINK_TYPE_FLOAT, 3, 80, offsetof(mavlink_follow_target_t, position_cov) }, \ + { "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \ + } \ +} + + +/** + * @brief Pack a follow_target message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param timestamp Timestamp in milliseconds since system boot + * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt AMSL, in meters + * @param vel target velocity (0,0,0) for unknown + * @param acc linear target acceleration (0,0,0) for unknown + * @param attitude_q (1 0 0 0 for unknown) + * @param rates (0 0 0 for unknown) + * @param position_cov eph epv + * @param custom_state button states or switches of a tracker device + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_follow_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_FOLLOW_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_uint64_t(buf, 8, custom_state); + _mav_put_int32_t(buf, 16, lat); + _mav_put_int32_t(buf, 20, lon); + _mav_put_float(buf, 24, alt); + _mav_put_uint8_t(buf, 92, est_capabilities); + _mav_put_float_array(buf, 28, vel, 3); + _mav_put_float_array(buf, 40, acc, 3); + _mav_put_float_array(buf, 52, attitude_q, 4); + _mav_put_float_array(buf, 68, rates, 3); + _mav_put_float_array(buf, 80, position_cov, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#else + mavlink_follow_target_t packet; + packet.timestamp = timestamp; + packet.custom_state = custom_state; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.est_capabilities = est_capabilities; + mav_array_memcpy(packet.vel, vel, sizeof(float)*3); + mav_array_memcpy(packet.acc, acc, sizeof(float)*3); + mav_array_memcpy(packet.attitude_q, attitude_q, sizeof(float)*4); + mav_array_memcpy(packet.rates, rates, sizeof(float)*3); + mav_array_memcpy(packet.position_cov, position_cov, sizeof(float)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_FOLLOW_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif +} + +/** + * @brief Pack a follow_target message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param timestamp Timestamp in milliseconds since system boot + * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt AMSL, in meters + * @param vel target velocity (0,0,0) for unknown + * @param acc linear target acceleration (0,0,0) for unknown + * @param attitude_q (1 0 0 0 for unknown) + * @param rates (0 0 0 for unknown) + * @param position_cov eph epv + * @param custom_state button states or switches of a tracker device + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_follow_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t timestamp,uint8_t est_capabilities,int32_t lat,int32_t lon,float alt,const float *vel,const float *acc,const float *attitude_q,const float *rates,const float *position_cov,uint64_t custom_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_FOLLOW_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_uint64_t(buf, 8, custom_state); + _mav_put_int32_t(buf, 16, lat); + _mav_put_int32_t(buf, 20, lon); + _mav_put_float(buf, 24, alt); + _mav_put_uint8_t(buf, 92, est_capabilities); + _mav_put_float_array(buf, 28, vel, 3); + _mav_put_float_array(buf, 40, acc, 3); + _mav_put_float_array(buf, 52, attitude_q, 4); + _mav_put_float_array(buf, 68, rates, 3); + _mav_put_float_array(buf, 80, position_cov, 3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#else + mavlink_follow_target_t packet; + packet.timestamp = timestamp; + packet.custom_state = custom_state; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.est_capabilities = est_capabilities; + mav_array_memcpy(packet.vel, vel, sizeof(float)*3); + mav_array_memcpy(packet.acc, acc, sizeof(float)*3); + mav_array_memcpy(packet.attitude_q, attitude_q, sizeof(float)*4); + mav_array_memcpy(packet.rates, rates, sizeof(float)*3); + mav_array_memcpy(packet.position_cov, position_cov, sizeof(float)*3); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_FOLLOW_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif +} + +/** + * @brief Encode a follow_target struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param follow_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_follow_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_follow_target_t* follow_target) +{ + return mavlink_msg_follow_target_pack(system_id, component_id, msg, follow_target->timestamp, follow_target->est_capabilities, follow_target->lat, follow_target->lon, follow_target->alt, follow_target->vel, follow_target->acc, follow_target->attitude_q, follow_target->rates, follow_target->position_cov, follow_target->custom_state); +} + +/** + * @brief Encode a follow_target struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param follow_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_follow_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_follow_target_t* follow_target) +{ + return mavlink_msg_follow_target_pack_chan(system_id, component_id, chan, msg, follow_target->timestamp, follow_target->est_capabilities, follow_target->lat, follow_target->lon, follow_target->alt, follow_target->vel, follow_target->acc, follow_target->attitude_q, follow_target->rates, follow_target->position_cov, follow_target->custom_state); +} + +/** + * @brief Send a follow_target message + * @param chan MAVLink channel to send the message + * + * @param timestamp Timestamp in milliseconds since system boot + * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt AMSL, in meters + * @param vel target velocity (0,0,0) for unknown + * @param acc linear target acceleration (0,0,0) for unknown + * @param attitude_q (1 0 0 0 for unknown) + * @param rates (0 0 0 for unknown) + * @param position_cov eph epv + * @param custom_state button states or switches of a tracker device + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_follow_target_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_FOLLOW_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_uint64_t(buf, 8, custom_state); + _mav_put_int32_t(buf, 16, lat); + _mav_put_int32_t(buf, 20, lon); + _mav_put_float(buf, 24, alt); + _mav_put_uint8_t(buf, 92, est_capabilities); + _mav_put_float_array(buf, 28, vel, 3); + _mav_put_float_array(buf, 40, acc, 3); + _mav_put_float_array(buf, 52, attitude_q, 4); + _mav_put_float_array(buf, 68, rates, 3); + _mav_put_float_array(buf, 80, position_cov, 3); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif +#else + mavlink_follow_target_t packet; + packet.timestamp = timestamp; + packet.custom_state = custom_state; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.est_capabilities = est_capabilities; + mav_array_memcpy(packet.vel, vel, sizeof(float)*3); + mav_array_memcpy(packet.acc, acc, sizeof(float)*3); + mav_array_memcpy(packet.attitude_q, attitude_q, sizeof(float)*4); + mav_array_memcpy(packet.rates, rates, sizeof(float)*3); + mav_array_memcpy(packet.position_cov, position_cov, sizeof(float)*3); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)&packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)&packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_FOLLOW_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_follow_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_uint64_t(buf, 8, custom_state); + _mav_put_int32_t(buf, 16, lat); + _mav_put_int32_t(buf, 20, lon); + _mav_put_float(buf, 24, alt); + _mav_put_uint8_t(buf, 92, est_capabilities); + _mav_put_float_array(buf, 28, vel, 3); + _mav_put_float_array(buf, 40, acc, 3); + _mav_put_float_array(buf, 52, attitude_q, 4); + _mav_put_float_array(buf, 68, rates, 3); + _mav_put_float_array(buf, 80, position_cov, 3); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif +#else + mavlink_follow_target_t *packet = (mavlink_follow_target_t *)msgbuf; + packet->timestamp = timestamp; + packet->custom_state = custom_state; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->est_capabilities = est_capabilities; + mav_array_memcpy(packet->vel, vel, sizeof(float)*3); + mav_array_memcpy(packet->acc, acc, sizeof(float)*3); + mav_array_memcpy(packet->attitude_q, attitude_q, sizeof(float)*4); + mav_array_memcpy(packet->rates, rates, sizeof(float)*3); + mav_array_memcpy(packet->position_cov, position_cov, sizeof(float)*3); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE FOLLOW_TARGET UNPACKING + + +/** + * @brief Get field timestamp from follow_target message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint64_t mavlink_msg_follow_target_get_timestamp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field est_capabilities from follow_target message + * + * @return bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + */ +static inline uint8_t mavlink_msg_follow_target_get_est_capabilities(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 92); +} + +/** + * @brief Get field lat from follow_target message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_follow_target_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field lon from follow_target message + * + * @return Longitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_follow_target_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 20); +} + +/** + * @brief Get field alt from follow_target message + * + * @return AMSL, in meters + */ +static inline float mavlink_msg_follow_target_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field vel from follow_target message + * + * @return target velocity (0,0,0) for unknown + */ +static inline uint16_t mavlink_msg_follow_target_get_vel(const mavlink_message_t* msg, float *vel) +{ + return _MAV_RETURN_float_array(msg, vel, 3, 28); +} + +/** + * @brief Get field acc from follow_target message + * + * @return linear target acceleration (0,0,0) for unknown + */ +static inline uint16_t mavlink_msg_follow_target_get_acc(const mavlink_message_t* msg, float *acc) +{ + return _MAV_RETURN_float_array(msg, acc, 3, 40); +} + +/** + * @brief Get field attitude_q from follow_target message + * + * @return (1 0 0 0 for unknown) + */ +static inline uint16_t mavlink_msg_follow_target_get_attitude_q(const mavlink_message_t* msg, float *attitude_q) +{ + return _MAV_RETURN_float_array(msg, attitude_q, 4, 52); +} + +/** + * @brief Get field rates from follow_target message + * + * @return (0 0 0 for unknown) + */ +static inline uint16_t mavlink_msg_follow_target_get_rates(const mavlink_message_t* msg, float *rates) +{ + return _MAV_RETURN_float_array(msg, rates, 3, 68); +} + +/** + * @brief Get field position_cov from follow_target message + * + * @return eph epv + */ +static inline uint16_t mavlink_msg_follow_target_get_position_cov(const mavlink_message_t* msg, float *position_cov) +{ + return _MAV_RETURN_float_array(msg, position_cov, 3, 80); +} + +/** + * @brief Get field custom_state from follow_target message + * + * @return button states or switches of a tracker device + */ +static inline uint64_t mavlink_msg_follow_target_get_custom_state(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 8); +} + +/** + * @brief Decode a follow_target message into a struct + * + * @param msg The message to decode + * @param follow_target C-struct to decode the message contents into + */ +static inline void mavlink_msg_follow_target_decode(const mavlink_message_t* msg, mavlink_follow_target_t* follow_target) +{ +#if MAVLINK_NEED_BYTE_SWAP + follow_target->timestamp = mavlink_msg_follow_target_get_timestamp(msg); + follow_target->custom_state = mavlink_msg_follow_target_get_custom_state(msg); + follow_target->lat = mavlink_msg_follow_target_get_lat(msg); + follow_target->lon = mavlink_msg_follow_target_get_lon(msg); + follow_target->alt = mavlink_msg_follow_target_get_alt(msg); + mavlink_msg_follow_target_get_vel(msg, follow_target->vel); + mavlink_msg_follow_target_get_acc(msg, follow_target->acc); + mavlink_msg_follow_target_get_attitude_q(msg, follow_target->attitude_q); + mavlink_msg_follow_target_get_rates(msg, follow_target->rates); + mavlink_msg_follow_target_get_position_cov(msg, follow_target->position_cov); + follow_target->est_capabilities = mavlink_msg_follow_target_get_est_capabilities(msg); +#else + memcpy(follow_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_global_position_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_global_position_int.h new file mode 100644 index 0000000..35255a2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_global_position_int.h @@ -0,0 +1,401 @@ +// MESSAGE GLOBAL_POSITION_INT PACKING + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33 + +typedef struct __mavlink_global_position_int_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + int32_t lat; /*< Latitude, expressed as degrees * 1E7*/ + int32_t lon; /*< Longitude, expressed as degrees * 1E7*/ + int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)*/ + int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/ + int16_t vx; /*< Ground X Speed (Latitude, positive north), expressed as m/s * 100*/ + int16_t vy; /*< Ground Y Speed (Longitude, positive east), expressed as m/s * 100*/ + int16_t vz; /*< Ground Z Speed (Altitude, positive down), expressed as m/s * 100*/ + uint16_t hdg; /*< Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ +} mavlink_global_position_int_t; + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28 +#define MAVLINK_MSG_ID_33_LEN 28 + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104 +#define MAVLINK_MSG_ID_33_CRC 104 + + + +#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \ + "GLOBAL_POSITION_INT", \ + 9, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \ + { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \ + { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \ + { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \ + } \ +} + + +/** + * @brief Pack a global_position_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100 + * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, alt); + _mav_put_int32_t(buf, 16, relative_alt); + _mav_put_int16_t(buf, 20, vx); + _mav_put_int16_t(buf, 22, vy); + _mav_put_int16_t(buf, 24, vz); + _mav_put_uint16_t(buf, 26, hdg); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#else + mavlink_global_position_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.hdg = hdg; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif +} + +/** + * @brief Pack a global_position_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100 + * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,int16_t vx,int16_t vy,int16_t vz,uint16_t hdg) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, alt); + _mav_put_int32_t(buf, 16, relative_alt); + _mav_put_int16_t(buf, 20, vx); + _mav_put_int16_t(buf, 22, vy); + _mav_put_int16_t(buf, 24, vz); + _mav_put_uint16_t(buf, 26, hdg); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#else + mavlink_global_position_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.hdg = hdg; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif +} + +/** + * @brief Encode a global_position_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param global_position_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int) +{ + return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); +} + +/** + * @brief Encode a global_position_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param global_position_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int) +{ + return mavlink_msg_global_position_int_pack_chan(system_id, component_id, chan, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); +} + +/** + * @brief Send a global_position_int message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100 + * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, alt); + _mav_put_int32_t(buf, 16, relative_alt); + _mav_put_int16_t(buf, 20, vx); + _mav_put_int16_t(buf, 22, vy); + _mav_put_int16_t(buf, 24, vz); + _mav_put_uint16_t(buf, 26, hdg); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif +#else + mavlink_global_position_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.hdg = hdg; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_global_position_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, alt); + _mav_put_int32_t(buf, 16, relative_alt); + _mav_put_int16_t(buf, 20, vx); + _mav_put_int16_t(buf, 22, vy); + _mav_put_int16_t(buf, 24, vz); + _mav_put_uint16_t(buf, 26, hdg); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif +#else + mavlink_global_position_int_t *packet = (mavlink_global_position_int_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->relative_alt = relative_alt; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->hdg = hdg; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GLOBAL_POSITION_INT UNPACKING + + +/** + * @brief Get field time_boot_ms from global_position_int message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field lat from global_position_int message + * + * @return Latitude, expressed as degrees * 1E7 + */ +static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field lon from global_position_int message + * + * @return Longitude, expressed as degrees * 1E7 + */ +static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field alt from global_position_int message + * + * @return Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) + */ +static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field relative_alt from global_position_int message + * + * @return Altitude above ground in meters, expressed as * 1000 (millimeters) + */ +static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field vx from global_position_int message + * + * @return Ground X Speed (Latitude, positive north), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field vy from global_position_int message + * + * @return Ground Y Speed (Longitude, positive east), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field vz from global_position_int message + * + * @return Ground Z Speed (Altitude, positive down), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 24); +} + +/** + * @brief Get field hdg from global_position_int message + * + * @return Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Decode a global_position_int message into a struct + * + * @param msg The message to decode + * @param global_position_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + global_position_int->time_boot_ms = mavlink_msg_global_position_int_get_time_boot_ms(msg); + global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg); + global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg); + global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg); + global_position_int->relative_alt = mavlink_msg_global_position_int_get_relative_alt(msg); + global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg); + global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg); + global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg); + global_position_int->hdg = mavlink_msg_global_position_int_get_hdg(msg); +#else + memcpy(global_position_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_global_position_int_cov.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_global_position_int_cov.h new file mode 100644 index 0000000..49c43c9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_global_position_int_cov.h @@ -0,0 +1,441 @@ +// MESSAGE GLOBAL_POSITION_INT_COV PACKING + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV 63 + +typedef struct __mavlink_global_position_int_cov_t +{ + uint64_t time_utc; /*< Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.*/ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + int32_t lat; /*< Latitude, expressed as degrees * 1E7*/ + int32_t lon; /*< Longitude, expressed as degrees * 1E7*/ + int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), above MSL*/ + int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/ + float vx; /*< Ground X Speed (Latitude), expressed as m/s*/ + float vy; /*< Ground Y Speed (Longitude), expressed as m/s*/ + float vz; /*< Ground Z Speed (Altitude), expressed as m/s*/ + float covariance[36]; /*< Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)*/ + uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/ +} mavlink_global_position_int_cov_t; + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN 185 +#define MAVLINK_MSG_ID_63_LEN 185 + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC 51 +#define MAVLINK_MSG_ID_63_CRC 51 + +#define MAVLINK_MSG_GLOBAL_POSITION_INT_COV_FIELD_COVARIANCE_LEN 36 + +#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \ + "GLOBAL_POSITION_INT_COV", \ + 11, \ + { { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_utc) }, \ + { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, time_boot_ms) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, alt) }, \ + { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_global_position_int_cov_t, vz) }, \ + { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 40, offsetof(mavlink_global_position_int_cov_t, covariance) }, \ + { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 184, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \ + } \ +} + + +/** + * @brief Pack a global_position_int_cov message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s + * @param vy Ground Y Speed (Longitude), expressed as m/s + * @param vz Ground Z Speed (Altitude), expressed as m/s + * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_int_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_int32_t(buf, 12, lat); + _mav_put_int32_t(buf, 16, lon); + _mav_put_int32_t(buf, 20, alt); + _mav_put_int32_t(buf, 24, relative_alt); + _mav_put_float(buf, 28, vx); + _mav_put_float(buf, 32, vy); + _mav_put_float(buf, 36, vz); + _mav_put_uint8_t(buf, 184, estimator_type); + _mav_put_float_array(buf, 40, covariance, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#else + mavlink_global_position_int_cov_t packet; + packet.time_utc = time_utc; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.estimator_type = estimator_type; + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif +} + +/** + * @brief Pack a global_position_int_cov message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s + * @param vy Ground Y Speed (Longitude), expressed as m/s + * @param vz Ground Z Speed (Altitude), expressed as m/s + * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_int_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint64_t time_utc,uint8_t estimator_type,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,float vx,float vy,float vz,const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_int32_t(buf, 12, lat); + _mav_put_int32_t(buf, 16, lon); + _mav_put_int32_t(buf, 20, alt); + _mav_put_int32_t(buf, 24, relative_alt); + _mav_put_float(buf, 28, vx); + _mav_put_float(buf, 32, vy); + _mav_put_float(buf, 36, vz); + _mav_put_uint8_t(buf, 184, estimator_type); + _mav_put_float_array(buf, 40, covariance, 36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#else + mavlink_global_position_int_cov_t packet; + packet.time_utc = time_utc; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.estimator_type = estimator_type; + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif +} + +/** + * @brief Encode a global_position_int_cov struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param global_position_int_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_int_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov) +{ + return mavlink_msg_global_position_int_cov_pack(system_id, component_id, msg, global_position_int_cov->time_boot_ms, global_position_int_cov->time_utc, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance); +} + +/** + * @brief Encode a global_position_int_cov struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param global_position_int_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_int_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov) +{ + return mavlink_msg_global_position_int_cov_pack_chan(system_id, component_id, chan, msg, global_position_int_cov->time_boot_ms, global_position_int_cov->time_utc, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance); +} + +/** + * @brief Send a global_position_int_cov message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param lat Latitude, expressed as degrees * 1E7 + * @param lon Longitude, expressed as degrees * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s + * @param vy Ground Y Speed (Longitude), expressed as m/s + * @param vz Ground Z Speed (Altitude), expressed as m/s + * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_position_int_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_int32_t(buf, 12, lat); + _mav_put_int32_t(buf, 16, lon); + _mav_put_int32_t(buf, 20, alt); + _mav_put_int32_t(buf, 24, relative_alt); + _mav_put_float(buf, 28, vx); + _mav_put_float(buf, 32, vy); + _mav_put_float(buf, 36, vz); + _mav_put_uint8_t(buf, 184, estimator_type); + _mav_put_float_array(buf, 40, covariance, 36); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif +#else + mavlink_global_position_int_cov_t packet; + packet.time_utc = time_utc; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.estimator_type = estimator_type; + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_global_position_int_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_int32_t(buf, 12, lat); + _mav_put_int32_t(buf, 16, lon); + _mav_put_int32_t(buf, 20, alt); + _mav_put_int32_t(buf, 24, relative_alt); + _mav_put_float(buf, 28, vx); + _mav_put_float(buf, 32, vy); + _mav_put_float(buf, 36, vz); + _mav_put_uint8_t(buf, 184, estimator_type); + _mav_put_float_array(buf, 40, covariance, 36); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif +#else + mavlink_global_position_int_cov_t *packet = (mavlink_global_position_int_cov_t *)msgbuf; + packet->time_utc = time_utc; + packet->time_boot_ms = time_boot_ms; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->relative_alt = relative_alt; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->estimator_type = estimator_type; + mav_array_memcpy(packet->covariance, covariance, sizeof(float)*36); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GLOBAL_POSITION_INT_COV UNPACKING + + +/** + * @brief Get field time_boot_ms from global_position_int_cov message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_global_position_int_cov_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field time_utc from global_position_int_cov message + * + * @return Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + */ +static inline uint64_t mavlink_msg_global_position_int_cov_get_time_utc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field estimator_type from global_position_int_cov message + * + * @return Class id of the estimator this estimate originated from. + */ +static inline uint8_t mavlink_msg_global_position_int_cov_get_estimator_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 184); +} + +/** + * @brief Get field lat from global_position_int_cov message + * + * @return Latitude, expressed as degrees * 1E7 + */ +static inline int32_t mavlink_msg_global_position_int_cov_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field lon from global_position_int_cov message + * + * @return Longitude, expressed as degrees * 1E7 + */ +static inline int32_t mavlink_msg_global_position_int_cov_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field alt from global_position_int_cov message + * + * @return Altitude in meters, expressed as * 1000 (millimeters), above MSL + */ +static inline int32_t mavlink_msg_global_position_int_cov_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 20); +} + +/** + * @brief Get field relative_alt from global_position_int_cov message + * + * @return Altitude above ground in meters, expressed as * 1000 (millimeters) + */ +static inline int32_t mavlink_msg_global_position_int_cov_get_relative_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 24); +} + +/** + * @brief Get field vx from global_position_int_cov message + * + * @return Ground X Speed (Latitude), expressed as m/s + */ +static inline float mavlink_msg_global_position_int_cov_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field vy from global_position_int_cov message + * + * @return Ground Y Speed (Longitude), expressed as m/s + */ +static inline float mavlink_msg_global_position_int_cov_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field vz from global_position_int_cov message + * + * @return Ground Z Speed (Altitude), expressed as m/s + */ +static inline float mavlink_msg_global_position_int_cov_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field covariance from global_position_int_cov message + * + * @return Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + */ +static inline uint16_t mavlink_msg_global_position_int_cov_get_covariance(const mavlink_message_t* msg, float *covariance) +{ + return _MAV_RETURN_float_array(msg, covariance, 36, 40); +} + +/** + * @brief Decode a global_position_int_cov message into a struct + * + * @param msg The message to decode + * @param global_position_int_cov C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_position_int_cov_decode(const mavlink_message_t* msg, mavlink_global_position_int_cov_t* global_position_int_cov) +{ +#if MAVLINK_NEED_BYTE_SWAP + global_position_int_cov->time_utc = mavlink_msg_global_position_int_cov_get_time_utc(msg); + global_position_int_cov->time_boot_ms = mavlink_msg_global_position_int_cov_get_time_boot_ms(msg); + global_position_int_cov->lat = mavlink_msg_global_position_int_cov_get_lat(msg); + global_position_int_cov->lon = mavlink_msg_global_position_int_cov_get_lon(msg); + global_position_int_cov->alt = mavlink_msg_global_position_int_cov_get_alt(msg); + global_position_int_cov->relative_alt = mavlink_msg_global_position_int_cov_get_relative_alt(msg); + global_position_int_cov->vx = mavlink_msg_global_position_int_cov_get_vx(msg); + global_position_int_cov->vy = mavlink_msg_global_position_int_cov_get_vy(msg); + global_position_int_cov->vz = mavlink_msg_global_position_int_cov_get_vz(msg); + mavlink_msg_global_position_int_cov_get_covariance(msg, global_position_int_cov->covariance); + global_position_int_cov->estimator_type = mavlink_msg_global_position_int_cov_get_estimator_type(msg); +#else + memcpy(global_position_int_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h new file mode 100644 index 0000000..1a1e92c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h @@ -0,0 +1,353 @@ +// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101 + +typedef struct __mavlink_global_vision_position_estimate_t +{ + uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + float x; /*< Global X position*/ + float y; /*< Global Y position*/ + float z; /*< Global Z position*/ + float roll; /*< Roll angle in rad*/ + float pitch; /*< Pitch angle in rad*/ + float yaw; /*< Yaw angle in rad*/ +} mavlink_global_vision_position_estimate_t; + +#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32 +#define MAVLINK_MSG_ID_101_LEN 32 + +#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC 102 +#define MAVLINK_MSG_ID_101_CRC 102 + + + +#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \ + "GLOBAL_VISION_POSITION_ESTIMATE", \ + 7, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_vision_position_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_vision_position_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_vision_position_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_vision_position_estimate_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_vision_position_estimate_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_vision_position_estimate_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_vision_position_estimate_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a global_vision_position_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#else + mavlink_global_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif +} + +/** + * @brief Pack a global_vision_position_estimate message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#else + mavlink_global_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif +} + +/** + * @brief Encode a global_vision_position_estimate struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param global_vision_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) +{ + return mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw); +} + +/** + * @brief Encode a global_vision_position_estimate struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param global_vision_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_vision_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) +{ + return mavlink_msg_global_vision_position_estimate_pack_chan(system_id, component_id, chan, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw); +} + +/** + * @brief Send a global_vision_position_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif +#else + mavlink_global_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_global_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif +#else + mavlink_global_vision_position_estimate_t *packet = (mavlink_global_vision_position_estimate_t *)msgbuf; + packet->usec = usec; + packet->x = x; + packet->y = y; + packet->z = z; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from global_vision_position_estimate message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_global_vision_position_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from global_vision_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_global_vision_position_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from global_vision_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_global_vision_position_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from global_vision_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_global_vision_position_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field roll from global_vision_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_global_vision_position_estimate_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitch from global_vision_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_global_vision_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yaw from global_vision_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_global_vision_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a global_vision_position_estimate message into a struct + * + * @param msg The message to decode + * @param global_vision_position_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_global_vision_position_estimate_t* global_vision_position_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + global_vision_position_estimate->usec = mavlink_msg_global_vision_position_estimate_get_usec(msg); + global_vision_position_estimate->x = mavlink_msg_global_vision_position_estimate_get_x(msg); + global_vision_position_estimate->y = mavlink_msg_global_vision_position_estimate_get_y(msg); + global_vision_position_estimate->z = mavlink_msg_global_vision_position_estimate_get_z(msg); + global_vision_position_estimate->roll = mavlink_msg_global_vision_position_estimate_get_roll(msg); + global_vision_position_estimate->pitch = mavlink_msg_global_vision_position_estimate_get_pitch(msg); + global_vision_position_estimate->yaw = mavlink_msg_global_vision_position_estimate_get_yaw(msg); +#else + memcpy(global_vision_position_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps2_raw.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps2_raw.h new file mode 100644 index 0000000..f068d49 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps2_raw.h @@ -0,0 +1,473 @@ +// MESSAGE GPS2_RAW PACKING + +#define MAVLINK_MSG_ID_GPS2_RAW 124 + +typedef struct __mavlink_gps2_raw_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ + int32_t alt; /*< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)*/ + uint32_t dgps_age; /*< Age of DGPS info*/ + uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/ + uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/ + uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX*/ + uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ + uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.*/ + uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ + uint8_t dgps_numch; /*< Number of DGPS satellites*/ +} mavlink_gps2_raw_t; + +#define MAVLINK_MSG_ID_GPS2_RAW_LEN 35 +#define MAVLINK_MSG_ID_124_LEN 35 + +#define MAVLINK_MSG_ID_GPS2_RAW_CRC 87 +#define MAVLINK_MSG_ID_124_CRC 87 + + + +#define MAVLINK_MESSAGE_INFO_GPS2_RAW { \ + "GPS2_RAW", \ + 12, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \ + { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \ + { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \ + { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \ + { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \ + { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \ + { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \ + { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \ + } \ +} + + +/** + * @brief Pack a gps2_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @param dgps_numch Number of DGPS satellites + * @param dgps_age Age of DGPS info + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint32_t(buf, 20, dgps_age); + _mav_put_uint16_t(buf, 24, eph); + _mav_put_uint16_t(buf, 26, epv); + _mav_put_uint16_t(buf, 28, vel); + _mav_put_uint16_t(buf, 30, cog); + _mav_put_uint8_t(buf, 32, fix_type); + _mav_put_uint8_t(buf, 33, satellites_visible); + _mav_put_uint8_t(buf, 34, dgps_numch); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#else + mavlink_gps2_raw_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.dgps_age = dgps_age; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + packet.dgps_numch = dgps_numch; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS2_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif +} + +/** + * @brief Pack a gps2_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @param dgps_numch Number of DGPS satellites + * @param dgps_age Age of DGPS info + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible,uint8_t dgps_numch,uint32_t dgps_age) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint32_t(buf, 20, dgps_age); + _mav_put_uint16_t(buf, 24, eph); + _mav_put_uint16_t(buf, 26, epv); + _mav_put_uint16_t(buf, 28, vel); + _mav_put_uint16_t(buf, 30, cog); + _mav_put_uint8_t(buf, 32, fix_type); + _mav_put_uint8_t(buf, 33, satellites_visible); + _mav_put_uint8_t(buf, 34, dgps_numch); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#else + mavlink_gps2_raw_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.dgps_age = dgps_age; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + packet.dgps_numch = dgps_numch; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS2_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif +} + +/** + * @brief Encode a gps2_raw struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps2_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps2_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw) +{ + return mavlink_msg_gps2_raw_pack(system_id, component_id, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age); +} + +/** + * @brief Encode a gps2_raw struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps2_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw) +{ + return mavlink_msg_gps2_raw_pack_chan(system_id, component_id, chan, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age); +} + +/** + * @brief Send a gps2_raw message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @param dgps_numch Number of DGPS satellites + * @param dgps_age Age of DGPS info + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps2_raw_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint32_t(buf, 20, dgps_age); + _mav_put_uint16_t(buf, 24, eph); + _mav_put_uint16_t(buf, 26, epv); + _mav_put_uint16_t(buf, 28, vel); + _mav_put_uint16_t(buf, 30, cog); + _mav_put_uint8_t(buf, 32, fix_type); + _mav_put_uint8_t(buf, 33, satellites_visible); + _mav_put_uint8_t(buf, 34, dgps_numch); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif +#else + mavlink_gps2_raw_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.dgps_age = dgps_age; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + packet.dgps_numch = dgps_numch; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS2_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps2_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint32_t(buf, 20, dgps_age); + _mav_put_uint16_t(buf, 24, eph); + _mav_put_uint16_t(buf, 26, epv); + _mav_put_uint16_t(buf, 28, vel); + _mav_put_uint16_t(buf, 30, cog); + _mav_put_uint8_t(buf, 32, fix_type); + _mav_put_uint8_t(buf, 33, satellites_visible); + _mav_put_uint8_t(buf, 34, dgps_numch); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif +#else + mavlink_gps2_raw_t *packet = (mavlink_gps2_raw_t *)msgbuf; + packet->time_usec = time_usec; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->dgps_age = dgps_age; + packet->eph = eph; + packet->epv = epv; + packet->vel = vel; + packet->cog = cog; + packet->fix_type = fix_type; + packet->satellites_visible = satellites_visible; + packet->dgps_numch = dgps_numch; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS2_RAW UNPACKING + + +/** + * @brief Get field time_usec from gps2_raw message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field fix_type from gps2_raw message + * + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + */ +static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field lat from gps2_raw message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field lon from gps2_raw message + * + * @return Longitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field alt from gps2_raw message + * + * @return Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field eph from gps2_raw message + * + * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field epv from gps2_raw message + * + * @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field vel from gps2_raw message + * + * @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field cog from gps2_raw message + * + * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps2_raw_get_cog(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 30); +} + +/** + * @brief Get field satellites_visible from gps2_raw message + * + * @return Number of satellites visible. If unknown, set to 255 + */ +static inline uint8_t mavlink_msg_gps2_raw_get_satellites_visible(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field dgps_numch from gps2_raw message + * + * @return Number of DGPS satellites + */ +static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field dgps_age from gps2_raw message + * + * @return Age of DGPS info + */ +static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 20); +} + +/** + * @brief Decode a gps2_raw message into a struct + * + * @param msg The message to decode + * @param gps2_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps2_raw_decode(const mavlink_message_t* msg, mavlink_gps2_raw_t* gps2_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps2_raw->time_usec = mavlink_msg_gps2_raw_get_time_usec(msg); + gps2_raw->lat = mavlink_msg_gps2_raw_get_lat(msg); + gps2_raw->lon = mavlink_msg_gps2_raw_get_lon(msg); + gps2_raw->alt = mavlink_msg_gps2_raw_get_alt(msg); + gps2_raw->dgps_age = mavlink_msg_gps2_raw_get_dgps_age(msg); + gps2_raw->eph = mavlink_msg_gps2_raw_get_eph(msg); + gps2_raw->epv = mavlink_msg_gps2_raw_get_epv(msg); + gps2_raw->vel = mavlink_msg_gps2_raw_get_vel(msg); + gps2_raw->cog = mavlink_msg_gps2_raw_get_cog(msg); + gps2_raw->fix_type = mavlink_msg_gps2_raw_get_fix_type(msg); + gps2_raw->satellites_visible = mavlink_msg_gps2_raw_get_satellites_visible(msg); + gps2_raw->dgps_numch = mavlink_msg_gps2_raw_get_dgps_numch(msg); +#else + memcpy(gps2_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS2_RAW_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps2_rtk.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps2_rtk.h new file mode 100644 index 0000000..66ce52f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps2_rtk.h @@ -0,0 +1,497 @@ +// MESSAGE GPS2_RTK PACKING + +#define MAVLINK_MSG_ID_GPS2_RTK 128 + +typedef struct __mavlink_gps2_rtk_t +{ + uint32_t time_last_baseline_ms; /*< Time since boot of last baseline message received in ms.*/ + uint32_t tow; /*< GPS Time of Week of last baseline*/ + int32_t baseline_a_mm; /*< Current baseline in ECEF x or NED north component in mm.*/ + int32_t baseline_b_mm; /*< Current baseline in ECEF y or NED east component in mm.*/ + int32_t baseline_c_mm; /*< Current baseline in ECEF z or NED down component in mm.*/ + uint32_t accuracy; /*< Current estimate of baseline accuracy.*/ + int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/ + uint16_t wn; /*< GPS Week Number of last baseline*/ + uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/ + uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/ + uint8_t rtk_rate; /*< Rate of baseline messages being received by GPS, in HZ*/ + uint8_t nsats; /*< Current number of sats used for RTK calculation.*/ + uint8_t baseline_coords_type; /*< Coordinate system of baseline. 0 == ECEF, 1 == NED*/ +} mavlink_gps2_rtk_t; + +#define MAVLINK_MSG_ID_GPS2_RTK_LEN 35 +#define MAVLINK_MSG_ID_128_LEN 35 + +#define MAVLINK_MSG_ID_GPS2_RTK_CRC 226 +#define MAVLINK_MSG_ID_128_CRC 226 + + + +#define MAVLINK_MESSAGE_INFO_GPS2_RTK { \ + "GPS2_RTK", \ + 13, \ + { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \ + { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \ + { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \ + { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \ + { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \ + { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \ + { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \ + { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \ + { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \ + { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \ + { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \ + { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \ + { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \ + } \ +} + + +/** + * @brief Pack a gps2_rtk message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps2_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#else + mavlink_gps2_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS2_RTK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +} + +/** + * @brief Pack a gps2_rtk message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps2_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_last_baseline_ms,uint8_t rtk_receiver_id,uint16_t wn,uint32_t tow,uint8_t rtk_health,uint8_t rtk_rate,uint8_t nsats,uint8_t baseline_coords_type,int32_t baseline_a_mm,int32_t baseline_b_mm,int32_t baseline_c_mm,uint32_t accuracy,int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#else + mavlink_gps2_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS2_RTK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +} + +/** + * @brief Encode a gps2_rtk struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps2_rtk C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps2_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk) +{ + return mavlink_msg_gps2_rtk_pack(system_id, component_id, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses); +} + +/** + * @brief Encode a gps2_rtk struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps2_rtk C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps2_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk) +{ + return mavlink_msg_gps2_rtk_pack_chan(system_id, component_id, chan, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses); +} + +/** + * @brief Send a gps2_rtk message + * @param chan MAVLink channel to send the message + * + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps2_rtk_send(mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +#else + mavlink_gps2_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS2_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps2_rtk_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +#else + mavlink_gps2_rtk_t *packet = (mavlink_gps2_rtk_t *)msgbuf; + packet->time_last_baseline_ms = time_last_baseline_ms; + packet->tow = tow; + packet->baseline_a_mm = baseline_a_mm; + packet->baseline_b_mm = baseline_b_mm; + packet->baseline_c_mm = baseline_c_mm; + packet->accuracy = accuracy; + packet->iar_num_hypotheses = iar_num_hypotheses; + packet->wn = wn; + packet->rtk_receiver_id = rtk_receiver_id; + packet->rtk_health = rtk_health; + packet->rtk_rate = rtk_rate; + packet->nsats = nsats; + packet->baseline_coords_type = baseline_coords_type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS2_RTK UNPACKING + + +/** + * @brief Get field time_last_baseline_ms from gps2_rtk message + * + * @return Time since boot of last baseline message received in ms. + */ +static inline uint32_t mavlink_msg_gps2_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field rtk_receiver_id from gps2_rtk message + * + * @return Identification of connected RTK receiver. + */ +static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_receiver_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 30); +} + +/** + * @brief Get field wn from gps2_rtk message + * + * @return GPS Week Number of last baseline + */ +static inline uint16_t mavlink_msg_gps2_rtk_get_wn(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field tow from gps2_rtk message + * + * @return GPS Time of Week of last baseline + */ +static inline uint32_t mavlink_msg_gps2_rtk_get_tow(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Get field rtk_health from gps2_rtk message + * + * @return GPS-specific health report for RTK data. + */ +static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_health(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 31); +} + +/** + * @brief Get field rtk_rate from gps2_rtk message + * + * @return Rate of baseline messages being received by GPS, in HZ + */ +static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field nsats from gps2_rtk message + * + * @return Current number of sats used for RTK calculation. + */ +static inline uint8_t mavlink_msg_gps2_rtk_get_nsats(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field baseline_coords_type from gps2_rtk message + * + * @return Coordinate system of baseline. 0 == ECEF, 1 == NED + */ +static inline uint8_t mavlink_msg_gps2_rtk_get_baseline_coords_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field baseline_a_mm from gps2_rtk message + * + * @return Current baseline in ECEF x or NED north component in mm. + */ +static inline int32_t mavlink_msg_gps2_rtk_get_baseline_a_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field baseline_b_mm from gps2_rtk message + * + * @return Current baseline in ECEF y or NED east component in mm. + */ +static inline int32_t mavlink_msg_gps2_rtk_get_baseline_b_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field baseline_c_mm from gps2_rtk message + * + * @return Current baseline in ECEF z or NED down component in mm. + */ +static inline int32_t mavlink_msg_gps2_rtk_get_baseline_c_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field accuracy from gps2_rtk message + * + * @return Current estimate of baseline accuracy. + */ +static inline uint32_t mavlink_msg_gps2_rtk_get_accuracy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 20); +} + +/** + * @brief Get field iar_num_hypotheses from gps2_rtk message + * + * @return Current number of integer ambiguity hypotheses. + */ +static inline int32_t mavlink_msg_gps2_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 24); +} + +/** + * @brief Decode a gps2_rtk message into a struct + * + * @param msg The message to decode + * @param gps2_rtk C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps2_rtk_decode(const mavlink_message_t* msg, mavlink_gps2_rtk_t* gps2_rtk) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps2_rtk->time_last_baseline_ms = mavlink_msg_gps2_rtk_get_time_last_baseline_ms(msg); + gps2_rtk->tow = mavlink_msg_gps2_rtk_get_tow(msg); + gps2_rtk->baseline_a_mm = mavlink_msg_gps2_rtk_get_baseline_a_mm(msg); + gps2_rtk->baseline_b_mm = mavlink_msg_gps2_rtk_get_baseline_b_mm(msg); + gps2_rtk->baseline_c_mm = mavlink_msg_gps2_rtk_get_baseline_c_mm(msg); + gps2_rtk->accuracy = mavlink_msg_gps2_rtk_get_accuracy(msg); + gps2_rtk->iar_num_hypotheses = mavlink_msg_gps2_rtk_get_iar_num_hypotheses(msg); + gps2_rtk->wn = mavlink_msg_gps2_rtk_get_wn(msg); + gps2_rtk->rtk_receiver_id = mavlink_msg_gps2_rtk_get_rtk_receiver_id(msg); + gps2_rtk->rtk_health = mavlink_msg_gps2_rtk_get_rtk_health(msg); + gps2_rtk->rtk_rate = mavlink_msg_gps2_rtk_get_rtk_rate(msg); + gps2_rtk->nsats = mavlink_msg_gps2_rtk_get_nsats(msg); + gps2_rtk->baseline_coords_type = mavlink_msg_gps2_rtk_get_baseline_coords_type(msg); +#else + memcpy(gps2_rtk, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h new file mode 100644 index 0000000..58048c1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h @@ -0,0 +1,257 @@ +// MESSAGE GPS_GLOBAL_ORIGIN PACKING + +#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49 + +typedef struct __mavlink_gps_global_origin_t +{ + int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t longitude; /*< Longitude (WGS84), in degrees * 1E7*/ + int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ +} mavlink_gps_global_origin_t; + +#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12 +#define MAVLINK_MSG_ID_49_LEN 12 + +#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC 39 +#define MAVLINK_MSG_ID_49_CRC 39 + + + +#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \ + "GPS_GLOBAL_ORIGIN", \ + 3, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_global_origin_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_global_origin_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_global_origin_t, altitude) }, \ + } \ +} + + +/** + * @brief Pack a gps_global_origin message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84), in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#else + mavlink_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif +} + +/** + * @brief Pack a gps_global_origin message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84), in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int32_t latitude,int32_t longitude,int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#else + mavlink_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif +} + +/** + * @brief Encode a gps_global_origin struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_global_origin C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin) +{ + return mavlink_msg_gps_global_origin_pack(system_id, component_id, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude); +} + +/** + * @brief Encode a gps_global_origin struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps_global_origin C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_global_origin_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin) +{ + return mavlink_msg_gps_global_origin_pack_chan(system_id, component_id, chan, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude); +} + +/** + * @brief Send a gps_global_origin message + * @param chan MAVLink channel to send the message + * + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84), in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif +#else + mavlink_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps_global_origin_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif +#else + mavlink_gps_global_origin_t *packet = (mavlink_gps_global_origin_t *)msgbuf; + packet->latitude = latitude; + packet->longitude = longitude; + packet->altitude = altitude; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS_GLOBAL_ORIGIN UNPACKING + + +/** + * @brief Get field latitude from gps_global_origin message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from gps_global_origin message + * + * @return Longitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from gps_global_origin message + * + * @return Altitude (AMSL), in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Decode a gps_global_origin message into a struct + * + * @param msg The message to decode + * @param gps_global_origin C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_global_origin_t* gps_global_origin) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_global_origin->latitude = mavlink_msg_gps_global_origin_get_latitude(msg); + gps_global_origin->longitude = mavlink_msg_gps_global_origin_get_longitude(msg); + gps_global_origin->altitude = mavlink_msg_gps_global_origin_get_altitude(msg); +#else + memcpy(gps_global_origin, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h new file mode 100644 index 0000000..1eca5d8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h @@ -0,0 +1,273 @@ +// MESSAGE GPS_INJECT_DATA PACKING + +#define MAVLINK_MSG_ID_GPS_INJECT_DATA 123 + +typedef struct __mavlink_gps_inject_data_t +{ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t len; /*< data length*/ + uint8_t data[110]; /*< raw data (110 is enough for 12 satellites of RTCMv2)*/ +} mavlink_gps_inject_data_t; + +#define MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113 +#define MAVLINK_MSG_ID_123_LEN 113 + +#define MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC 250 +#define MAVLINK_MSG_ID_123_CRC 250 + +#define MAVLINK_MSG_GPS_INJECT_DATA_FIELD_DATA_LEN 110 + +#define MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA { \ + "GPS_INJECT_DATA", \ + 4, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_inject_data_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_inject_data_t, target_component) }, \ + { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gps_inject_data_t, len) }, \ + { "data", NULL, MAVLINK_TYPE_UINT8_T, 110, 3, offsetof(mavlink_gps_inject_data_t, data) }, \ + } \ +} + + +/** + * @brief Pack a gps_inject_data message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param len data length + * @param data raw data (110 is enough for 12 satellites of RTCMv2) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_inject_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, len); + _mav_put_uint8_t_array(buf, 3, data, 110); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#else + mavlink_gps_inject_data_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.len = len; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif +} + +/** + * @brief Pack a gps_inject_data message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param len data length + * @param data raw data (110 is enough for 12 satellites of RTCMv2) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_inject_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t len,const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, len); + _mav_put_uint8_t_array(buf, 3, data, 110); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#else + mavlink_gps_inject_data_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.len = len; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif +} + +/** + * @brief Encode a gps_inject_data struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_inject_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_inject_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data) +{ + return mavlink_msg_gps_inject_data_pack(system_id, component_id, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data); +} + +/** + * @brief Encode a gps_inject_data struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps_inject_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_inject_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data) +{ + return mavlink_msg_gps_inject_data_pack_chan(system_id, component_id, chan, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data); +} + +/** + * @brief Send a gps_inject_data message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param len data length + * @param data raw data (110 is enough for 12 satellites of RTCMv2) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_inject_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, len); + _mav_put_uint8_t_array(buf, 3, data, 110); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif +#else + mavlink_gps_inject_data_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.len = len; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps_inject_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, len); + _mav_put_uint8_t_array(buf, 3, data, 110); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif +#else + mavlink_gps_inject_data_t *packet = (mavlink_gps_inject_data_t *)msgbuf; + packet->target_system = target_system; + packet->target_component = target_component; + packet->len = len; + mav_array_memcpy(packet->data, data, sizeof(uint8_t)*110); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS_INJECT_DATA UNPACKING + + +/** + * @brief Get field target_system from gps_inject_data message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_gps_inject_data_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from gps_inject_data message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_gps_inject_data_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field len from gps_inject_data message + * + * @return data length + */ +static inline uint8_t mavlink_msg_gps_inject_data_get_len(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field data from gps_inject_data message + * + * @return raw data (110 is enough for 12 satellites of RTCMv2) + */ +static inline uint16_t mavlink_msg_gps_inject_data_get_data(const mavlink_message_t* msg, uint8_t *data) +{ + return _MAV_RETURN_uint8_t_array(msg, data, 110, 3); +} + +/** + * @brief Decode a gps_inject_data message into a struct + * + * @param msg The message to decode + * @param gps_inject_data C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_inject_data_decode(const mavlink_message_t* msg, mavlink_gps_inject_data_t* gps_inject_data) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_inject_data->target_system = mavlink_msg_gps_inject_data_get_target_system(msg); + gps_inject_data->target_component = mavlink_msg_gps_inject_data_get_target_component(msg); + gps_inject_data->len = mavlink_msg_gps_inject_data_get_len(msg); + mavlink_msg_gps_inject_data_get_data(msg, gps_inject_data->data); +#else + memcpy(gps_inject_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h new file mode 100644 index 0000000..feb5d13 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h @@ -0,0 +1,425 @@ +// MESSAGE GPS_RAW_INT PACKING + +#define MAVLINK_MSG_ID_GPS_RAW_INT 24 + +typedef struct __mavlink_gps_raw_int_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ + int32_t alt; /*< Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.*/ + uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/ + uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/ + uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX*/ + uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ + uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.*/ + uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ +} mavlink_gps_raw_int_t; + +#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30 +#define MAVLINK_MSG_ID_24_LEN 30 + +#define MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24 +#define MAVLINK_MSG_ID_24_CRC 24 + + + +#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \ + "GPS_RAW_INT", \ + 10, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \ + { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \ + { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \ + { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \ + { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ + { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \ + } \ +} + + +/** + * @brief Pack a gps_raw_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. + * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_uint16_t(buf, 26, cog); + _mav_put_uint8_t(buf, 28, fix_type); + _mav_put_uint8_t(buf, 29, satellites_visible); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#else + mavlink_gps_raw_int_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif +} + +/** + * @brief Pack a gps_raw_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. + * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_uint16_t(buf, 26, cog); + _mav_put_uint8_t(buf, 28, fix_type); + _mav_put_uint8_t(buf, 29, satellites_visible); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#else + mavlink_gps_raw_int_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif +} + +/** + * @brief Encode a gps_raw_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_raw_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int) +{ + return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible); +} + +/** + * @brief Encode a gps_raw_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps_raw_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int) +{ + return mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, chan, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible); +} + +/** + * @brief Send a gps_raw_int message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. + * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_uint16_t(buf, 26, cog); + _mav_put_uint8_t(buf, 28, fix_type); + _mav_put_uint8_t(buf, 29, satellites_visible); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif +#else + mavlink_gps_raw_int_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS_RAW_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_uint16_t(buf, 26, cog); + _mav_put_uint8_t(buf, 28, fix_type); + _mav_put_uint8_t(buf, 29, satellites_visible); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif +#else + mavlink_gps_raw_int_t *packet = (mavlink_gps_raw_int_t *)msgbuf; + packet->time_usec = time_usec; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->eph = eph; + packet->epv = epv; + packet->vel = vel; + packet->cog = cog; + packet->fix_type = fix_type; + packet->satellites_visible = satellites_visible; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS_RAW_INT UNPACKING + + +/** + * @brief Get field time_usec from gps_raw_int message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field fix_type from gps_raw_int message + * + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + */ +static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 28); +} + +/** + * @brief Get field lat from gps_raw_int message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field lon from gps_raw_int message + * + * @return Longitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field alt from gps_raw_int message + * + * @return Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. + */ +static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field eph from gps_raw_int message + * + * @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field epv from gps_raw_int message + * + * @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field vel from gps_raw_int message + * + * @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field cog from gps_raw_int message + * + * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field satellites_visible from gps_raw_int message + * + * @return Number of satellites visible. If unknown, set to 255 + */ +static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 29); +} + +/** + * @brief Decode a gps_raw_int message into a struct + * + * @param msg The message to decode + * @param gps_raw_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_raw_int->time_usec = mavlink_msg_gps_raw_int_get_time_usec(msg); + gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg); + gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg); + gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg); + gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg); + gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg); + gps_raw_int->vel = mavlink_msg_gps_raw_int_get_vel(msg); + gps_raw_int->cog = mavlink_msg_gps_raw_int_get_cog(msg); + gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg); + gps_raw_int->satellites_visible = mavlink_msg_gps_raw_int_get_satellites_visible(msg); +#else + memcpy(gps_raw_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_RAW_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps_rtk.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps_rtk.h new file mode 100644 index 0000000..b627d89 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps_rtk.h @@ -0,0 +1,497 @@ +// MESSAGE GPS_RTK PACKING + +#define MAVLINK_MSG_ID_GPS_RTK 127 + +typedef struct __mavlink_gps_rtk_t +{ + uint32_t time_last_baseline_ms; /*< Time since boot of last baseline message received in ms.*/ + uint32_t tow; /*< GPS Time of Week of last baseline*/ + int32_t baseline_a_mm; /*< Current baseline in ECEF x or NED north component in mm.*/ + int32_t baseline_b_mm; /*< Current baseline in ECEF y or NED east component in mm.*/ + int32_t baseline_c_mm; /*< Current baseline in ECEF z or NED down component in mm.*/ + uint32_t accuracy; /*< Current estimate of baseline accuracy.*/ + int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/ + uint16_t wn; /*< GPS Week Number of last baseline*/ + uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/ + uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/ + uint8_t rtk_rate; /*< Rate of baseline messages being received by GPS, in HZ*/ + uint8_t nsats; /*< Current number of sats used for RTK calculation.*/ + uint8_t baseline_coords_type; /*< Coordinate system of baseline. 0 == ECEF, 1 == NED*/ +} mavlink_gps_rtk_t; + +#define MAVLINK_MSG_ID_GPS_RTK_LEN 35 +#define MAVLINK_MSG_ID_127_LEN 35 + +#define MAVLINK_MSG_ID_GPS_RTK_CRC 25 +#define MAVLINK_MSG_ID_127_CRC 25 + + + +#define MAVLINK_MESSAGE_INFO_GPS_RTK { \ + "GPS_RTK", \ + 13, \ + { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps_rtk_t, time_last_baseline_ms) }, \ + { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps_rtk_t, tow) }, \ + { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_rtk_t, baseline_a_mm) }, \ + { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_rtk_t, baseline_b_mm) }, \ + { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_rtk_t, baseline_c_mm) }, \ + { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps_rtk_t, accuracy) }, \ + { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps_rtk_t, iar_num_hypotheses) }, \ + { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \ + { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \ + { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \ + { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \ + { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \ + { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \ + } \ +} + + +/** + * @brief Pack a gps_rtk message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTK_LEN); +#else + mavlink_gps_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RTK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +} + +/** + * @brief Pack a gps_rtk message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_last_baseline_ms,uint8_t rtk_receiver_id,uint16_t wn,uint32_t tow,uint8_t rtk_health,uint8_t rtk_rate,uint8_t nsats,uint8_t baseline_coords_type,int32_t baseline_a_mm,int32_t baseline_b_mm,int32_t baseline_c_mm,uint32_t accuracy,int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTK_LEN); +#else + mavlink_gps_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RTK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +} + +/** + * @brief Encode a gps_rtk struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_rtk C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_rtk_t* gps_rtk) +{ + return mavlink_msg_gps_rtk_pack(system_id, component_id, msg, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses); +} + +/** + * @brief Encode a gps_rtk struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps_rtk C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_rtk_t* gps_rtk) +{ + return mavlink_msg_gps_rtk_pack_chan(system_id, component_id, chan, msg, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses); +} + +/** + * @brief Send a gps_rtk message + * @param chan MAVLink channel to send the message + * + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_rtk_send(mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +#else + mavlink_gps_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps_rtk_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +#else + mavlink_gps_rtk_t *packet = (mavlink_gps_rtk_t *)msgbuf; + packet->time_last_baseline_ms = time_last_baseline_ms; + packet->tow = tow; + packet->baseline_a_mm = baseline_a_mm; + packet->baseline_b_mm = baseline_b_mm; + packet->baseline_c_mm = baseline_c_mm; + packet->accuracy = accuracy; + packet->iar_num_hypotheses = iar_num_hypotheses; + packet->wn = wn; + packet->rtk_receiver_id = rtk_receiver_id; + packet->rtk_health = rtk_health; + packet->rtk_rate = rtk_rate; + packet->nsats = nsats; + packet->baseline_coords_type = baseline_coords_type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS_RTK UNPACKING + + +/** + * @brief Get field time_last_baseline_ms from gps_rtk message + * + * @return Time since boot of last baseline message received in ms. + */ +static inline uint32_t mavlink_msg_gps_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field rtk_receiver_id from gps_rtk message + * + * @return Identification of connected RTK receiver. + */ +static inline uint8_t mavlink_msg_gps_rtk_get_rtk_receiver_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 30); +} + +/** + * @brief Get field wn from gps_rtk message + * + * @return GPS Week Number of last baseline + */ +static inline uint16_t mavlink_msg_gps_rtk_get_wn(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field tow from gps_rtk message + * + * @return GPS Time of Week of last baseline + */ +static inline uint32_t mavlink_msg_gps_rtk_get_tow(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Get field rtk_health from gps_rtk message + * + * @return GPS-specific health report for RTK data. + */ +static inline uint8_t mavlink_msg_gps_rtk_get_rtk_health(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 31); +} + +/** + * @brief Get field rtk_rate from gps_rtk message + * + * @return Rate of baseline messages being received by GPS, in HZ + */ +static inline uint8_t mavlink_msg_gps_rtk_get_rtk_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field nsats from gps_rtk message + * + * @return Current number of sats used for RTK calculation. + */ +static inline uint8_t mavlink_msg_gps_rtk_get_nsats(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field baseline_coords_type from gps_rtk message + * + * @return Coordinate system of baseline. 0 == ECEF, 1 == NED + */ +static inline uint8_t mavlink_msg_gps_rtk_get_baseline_coords_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field baseline_a_mm from gps_rtk message + * + * @return Current baseline in ECEF x or NED north component in mm. + */ +static inline int32_t mavlink_msg_gps_rtk_get_baseline_a_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field baseline_b_mm from gps_rtk message + * + * @return Current baseline in ECEF y or NED east component in mm. + */ +static inline int32_t mavlink_msg_gps_rtk_get_baseline_b_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field baseline_c_mm from gps_rtk message + * + * @return Current baseline in ECEF z or NED down component in mm. + */ +static inline int32_t mavlink_msg_gps_rtk_get_baseline_c_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field accuracy from gps_rtk message + * + * @return Current estimate of baseline accuracy. + */ +static inline uint32_t mavlink_msg_gps_rtk_get_accuracy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 20); +} + +/** + * @brief Get field iar_num_hypotheses from gps_rtk message + * + * @return Current number of integer ambiguity hypotheses. + */ +static inline int32_t mavlink_msg_gps_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 24); +} + +/** + * @brief Decode a gps_rtk message into a struct + * + * @param msg The message to decode + * @param gps_rtk C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_rtk_decode(const mavlink_message_t* msg, mavlink_gps_rtk_t* gps_rtk) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_rtk->time_last_baseline_ms = mavlink_msg_gps_rtk_get_time_last_baseline_ms(msg); + gps_rtk->tow = mavlink_msg_gps_rtk_get_tow(msg); + gps_rtk->baseline_a_mm = mavlink_msg_gps_rtk_get_baseline_a_mm(msg); + gps_rtk->baseline_b_mm = mavlink_msg_gps_rtk_get_baseline_b_mm(msg); + gps_rtk->baseline_c_mm = mavlink_msg_gps_rtk_get_baseline_c_mm(msg); + gps_rtk->accuracy = mavlink_msg_gps_rtk_get_accuracy(msg); + gps_rtk->iar_num_hypotheses = mavlink_msg_gps_rtk_get_iar_num_hypotheses(msg); + gps_rtk->wn = mavlink_msg_gps_rtk_get_wn(msg); + gps_rtk->rtk_receiver_id = mavlink_msg_gps_rtk_get_rtk_receiver_id(msg); + gps_rtk->rtk_health = mavlink_msg_gps_rtk_get_rtk_health(msg); + gps_rtk->rtk_rate = mavlink_msg_gps_rtk_get_rtk_rate(msg); + gps_rtk->nsats = mavlink_msg_gps_rtk_get_nsats(msg); + gps_rtk->baseline_coords_type = mavlink_msg_gps_rtk_get_baseline_coords_type(msg); +#else + memcpy(gps_rtk, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps_status.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps_status.h new file mode 100644 index 0000000..3e279b4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_gps_status.h @@ -0,0 +1,325 @@ +// MESSAGE GPS_STATUS PACKING + +#define MAVLINK_MSG_ID_GPS_STATUS 25 + +typedef struct __mavlink_gps_status_t +{ + uint8_t satellites_visible; /*< Number of satellites visible*/ + uint8_t satellite_prn[20]; /*< Global satellite ID*/ + uint8_t satellite_used[20]; /*< 0: Satellite not used, 1: used for localization*/ + uint8_t satellite_elevation[20]; /*< Elevation (0: right on top of receiver, 90: on the horizon) of satellite*/ + uint8_t satellite_azimuth[20]; /*< Direction of satellite, 0: 0 deg, 255: 360 deg.*/ + uint8_t satellite_snr[20]; /*< Signal to noise ratio of satellite*/ +} mavlink_gps_status_t; + +#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101 +#define MAVLINK_MSG_ID_25_LEN 101 + +#define MAVLINK_MSG_ID_GPS_STATUS_CRC 23 +#define MAVLINK_MSG_ID_25_CRC 23 + +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20 + +#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \ + "GPS_STATUS", \ + 6, \ + { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \ + { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \ + { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \ + { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \ + { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \ + { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \ + } \ +} + + +/** + * @brief Pack a gps_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN]; + _mav_put_uint8_t(buf, 0, satellites_visible); + _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); + _mav_put_uint8_t_array(buf, 21, satellite_used, 20); + _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); + _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); + _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#else + mavlink_gps_status_t packet; + packet.satellites_visible = satellites_visible; + mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif +} + +/** + * @brief Pack a gps_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t satellites_visible,const uint8_t *satellite_prn,const uint8_t *satellite_used,const uint8_t *satellite_elevation,const uint8_t *satellite_azimuth,const uint8_t *satellite_snr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN]; + _mav_put_uint8_t(buf, 0, satellites_visible); + _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); + _mav_put_uint8_t_array(buf, 21, satellite_used, 20); + _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); + _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); + _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#else + mavlink_gps_status_t packet; + packet.satellites_visible = satellites_visible; + mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif +} + +/** + * @brief Encode a gps_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) +{ + return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); +} + +/** + * @brief Encode a gps_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) +{ + return mavlink_msg_gps_status_pack_chan(system_id, component_id, chan, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); +} + +/** + * @brief Send a gps_status message + * @param chan MAVLink channel to send the message + * + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN]; + _mav_put_uint8_t(buf, 0, satellites_visible); + _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); + _mav_put_uint8_t_array(buf, 21, satellite_used, 20); + _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); + _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); + _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif +#else + mavlink_gps_status_t packet; + packet.satellites_visible = satellites_visible; + mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); + mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, satellites_visible); + _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); + _mav_put_uint8_t_array(buf, 21, satellite_used, 20); + _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); + _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); + _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif +#else + mavlink_gps_status_t *packet = (mavlink_gps_status_t *)msgbuf; + packet->satellites_visible = satellites_visible; + mav_array_memcpy(packet->satellite_prn, satellite_prn, sizeof(uint8_t)*20); + mav_array_memcpy(packet->satellite_used, satellite_used, sizeof(uint8_t)*20); + mav_array_memcpy(packet->satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); + mav_array_memcpy(packet->satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); + mav_array_memcpy(packet->satellite_snr, satellite_snr, sizeof(uint8_t)*20); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS_STATUS UNPACKING + + +/** + * @brief Get field satellites_visible from gps_status message + * + * @return Number of satellites visible + */ +static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field satellite_prn from gps_status message + * + * @return Global satellite ID + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_prn, 20, 1); +} + +/** + * @brief Get field satellite_used from gps_status message + * + * @return 0: Satellite not used, 1: used for localization + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_used, 20, 21); +} + +/** + * @brief Get field satellite_elevation from gps_status message + * + * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, 20, 41); +} + +/** + * @brief Get field satellite_azimuth from gps_status message + * + * @return Direction of satellite, 0: 0 deg, 255: 360 deg. + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, 20, 61); +} + +/** + * @brief Get field satellite_snr from gps_status message + * + * @return Signal to noise ratio of satellite + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_snr, 20, 81); +} + +/** + * @brief Decode a gps_status message into a struct + * + * @param msg The message to decode + * @param gps_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg); + mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn); + mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used); + mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation); + mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth); + mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr); +#else + memcpy(gps_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_STATUS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_heartbeat.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_heartbeat.h new file mode 100644 index 0000000..682b4d8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_heartbeat.h @@ -0,0 +1,326 @@ +// MESSAGE HEARTBEAT PACKING + +#define MAVLINK_MSG_ID_HEARTBEAT 0 + +typedef struct __mavlink_heartbeat_t +{ + uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/ + uint8_t type; /*< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)*/ + uint8_t autopilot; /*< Autopilot type / class. defined in MAV_AUTOPILOT ENUM*/ + uint8_t base_mode; /*< System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h*/ + uint8_t system_status; /*< System status flag, see MAV_STATE ENUM*/ + uint8_t mavlink_version; /*< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version*/ +} mavlink_heartbeat_t; + +#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9 +#define MAVLINK_MSG_ID_0_LEN 9 + +#define MAVLINK_MSG_ID_HEARTBEAT_CRC 50 +#define MAVLINK_MSG_ID_0_CRC 50 + + + +#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \ + "HEARTBEAT", \ + 6, \ + { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ + { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \ + { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \ + { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \ + { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ + } \ +} + + +/** + * @brief Pack a heartbeat message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM + * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param system_status System status flag, see MAV_STATE ENUM + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 3); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#else + mavlink_heartbeat_t packet; + packet.custom_mode = custom_mode; + packet.type = type; + packet.autopilot = autopilot; + packet.base_mode = base_mode; + packet.system_status = system_status; + packet.mavlink_version = 3; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif +} + +/** + * @brief Pack a heartbeat message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM + * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param system_status System status flag, see MAV_STATE ENUM + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 3); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#else + mavlink_heartbeat_t packet; + packet.custom_mode = custom_mode; + packet.type = type; + packet.autopilot = autopilot; + packet.base_mode = base_mode; + packet.system_status = system_status; + packet.mavlink_version = 3; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif +} + +/** + * @brief Encode a heartbeat struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param heartbeat C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) +{ + return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); +} + +/** + * @brief Encode a heartbeat struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param heartbeat C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) +{ + return mavlink_msg_heartbeat_pack_chan(system_id, component_id, chan, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); +} + +/** + * @brief Send a heartbeat message + * @param chan MAVLink channel to send the message + * + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM + * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h + * @param custom_mode A bitfield for use for autopilot-specific flags. + * @param system_status System status flag, see MAV_STATE ENUM + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 3); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif +#else + mavlink_heartbeat_t packet; + packet.custom_mode = custom_mode; + packet.type = type; + packet.autopilot = autopilot; + packet.base_mode = base_mode; + packet.system_status = system_status; + packet.mavlink_version = 3; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 3); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif +#else + mavlink_heartbeat_t *packet = (mavlink_heartbeat_t *)msgbuf; + packet->custom_mode = custom_mode; + packet->type = type; + packet->autopilot = autopilot; + packet->base_mode = base_mode; + packet->system_status = system_status; + packet->mavlink_version = 3; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HEARTBEAT UNPACKING + + +/** + * @brief Get field type from heartbeat message + * + * @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + */ +static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field autopilot from heartbeat message + * + * @return Autopilot type / class. defined in MAV_AUTOPILOT ENUM + */ +static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field base_mode from heartbeat message + * + * @return System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h + */ +static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field custom_mode from heartbeat message + * + * @return A bitfield for use for autopilot-specific flags. + */ +static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field system_status from heartbeat message + * + * @return System status flag, see MAV_STATE ENUM + */ +static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field mavlink_version from heartbeat message + * + * @return MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version + */ +static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Decode a heartbeat message into a struct + * + * @param msg The message to decode + * @param heartbeat C-struct to decode the message contents into + */ +static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat) +{ +#if MAVLINK_NEED_BYTE_SWAP + heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg); + heartbeat->type = mavlink_msg_heartbeat_get_type(msg); + heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg); + heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg); + heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg); + heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg); +#else + memcpy(heartbeat, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HEARTBEAT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_highres_imu.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_highres_imu.h new file mode 100644 index 0000000..654953d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_highres_imu.h @@ -0,0 +1,545 @@ +// MESSAGE HIGHRES_IMU PACKING + +#define MAVLINK_MSG_ID_HIGHRES_IMU 105 + +typedef struct __mavlink_highres_imu_t +{ + uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + float xacc; /*< X acceleration (m/s^2)*/ + float yacc; /*< Y acceleration (m/s^2)*/ + float zacc; /*< Z acceleration (m/s^2)*/ + float xgyro; /*< Angular speed around X axis (rad / sec)*/ + float ygyro; /*< Angular speed around Y axis (rad / sec)*/ + float zgyro; /*< Angular speed around Z axis (rad / sec)*/ + float xmag; /*< X Magnetic field (Gauss)*/ + float ymag; /*< Y Magnetic field (Gauss)*/ + float zmag; /*< Z Magnetic field (Gauss)*/ + float abs_pressure; /*< Absolute pressure in millibar*/ + float diff_pressure; /*< Differential pressure in millibar*/ + float pressure_alt; /*< Altitude calculated from pressure*/ + float temperature; /*< Temperature in degrees celsius*/ + uint16_t fields_updated; /*< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature*/ +} mavlink_highres_imu_t; + +#define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62 +#define MAVLINK_MSG_ID_105_LEN 62 + +#define MAVLINK_MSG_ID_HIGHRES_IMU_CRC 93 +#define MAVLINK_MSG_ID_105_CRC 93 + + + +#define MAVLINK_MESSAGE_INFO_HIGHRES_IMU { \ + "HIGHRES_IMU", \ + 15, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_highres_imu_t, time_usec) }, \ + { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_highres_imu_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_highres_imu_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_highres_imu_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_highres_imu_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_highres_imu_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_highres_imu_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_highres_imu_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_highres_imu_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_highres_imu_t, zmag) }, \ + { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_highres_imu_t, abs_pressure) }, \ + { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_highres_imu_t, diff_pressure) }, \ + { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_highres_imu_t, pressure_alt) }, \ + { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_highres_imu_t, temperature) }, \ + { "fields_updated", NULL, MAVLINK_TYPE_UINT16_T, 0, 60, offsetof(mavlink_highres_imu_t, fields_updated) }, \ + } \ +} + + +/** + * @brief Pack a highres_imu message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param xacc X acceleration (m/s^2) + * @param yacc Y acceleration (m/s^2) + * @param zacc Z acceleration (m/s^2) + * @param xgyro Angular speed around X axis (rad / sec) + * @param ygyro Angular speed around Y axis (rad / sec) + * @param zgyro Angular speed around Z axis (rad / sec) + * @param xmag X Magnetic field (Gauss) + * @param ymag Y Magnetic field (Gauss) + * @param zmag Z Magnetic field (Gauss) + * @param abs_pressure Absolute pressure in millibar + * @param diff_pressure Differential pressure in millibar + * @param pressure_alt Altitude calculated from pressure + * @param temperature Temperature in degrees celsius + * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint16_t(buf, 60, fields_updated); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#else + mavlink_highres_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + packet.abs_pressure = abs_pressure; + packet.diff_pressure = diff_pressure; + packet.pressure_alt = pressure_alt; + packet.temperature = temperature; + packet.fields_updated = fields_updated; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIGHRES_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif +} + +/** + * @brief Pack a highres_imu message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param xacc X acceleration (m/s^2) + * @param yacc Y acceleration (m/s^2) + * @param zacc Z acceleration (m/s^2) + * @param xgyro Angular speed around X axis (rad / sec) + * @param ygyro Angular speed around Y axis (rad / sec) + * @param zgyro Angular speed around Z axis (rad / sec) + * @param xmag X Magnetic field (Gauss) + * @param ymag Y Magnetic field (Gauss) + * @param zmag Z Magnetic field (Gauss) + * @param abs_pressure Absolute pressure in millibar + * @param diff_pressure Differential pressure in millibar + * @param pressure_alt Altitude calculated from pressure + * @param temperature Temperature in degrees celsius + * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,uint16_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint16_t(buf, 60, fields_updated); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#else + mavlink_highres_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + packet.abs_pressure = abs_pressure; + packet.diff_pressure = diff_pressure; + packet.pressure_alt = pressure_alt; + packet.temperature = temperature; + packet.fields_updated = fields_updated; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIGHRES_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif +} + +/** + * @brief Encode a highres_imu struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param highres_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_highres_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu) +{ + return mavlink_msg_highres_imu_pack(system_id, component_id, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated); +} + +/** + * @brief Encode a highres_imu struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param highres_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_highres_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu) +{ + return mavlink_msg_highres_imu_pack_chan(system_id, component_id, chan, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated); +} + +/** + * @brief Send a highres_imu message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param xacc X acceleration (m/s^2) + * @param yacc Y acceleration (m/s^2) + * @param zacc Z acceleration (m/s^2) + * @param xgyro Angular speed around X axis (rad / sec) + * @param ygyro Angular speed around Y axis (rad / sec) + * @param zgyro Angular speed around Z axis (rad / sec) + * @param xmag X Magnetic field (Gauss) + * @param ymag Y Magnetic field (Gauss) + * @param zmag Z Magnetic field (Gauss) + * @param abs_pressure Absolute pressure in millibar + * @param diff_pressure Differential pressure in millibar + * @param pressure_alt Altitude calculated from pressure + * @param temperature Temperature in degrees celsius + * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_highres_imu_send(mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint16_t(buf, 60, fields_updated); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif +#else + mavlink_highres_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + packet.abs_pressure = abs_pressure; + packet.diff_pressure = diff_pressure; + packet.pressure_alt = pressure_alt; + packet.temperature = temperature; + packet.fields_updated = fields_updated; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIGHRES_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_highres_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint16_t(buf, 60, fields_updated); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif +#else + mavlink_highres_imu_t *packet = (mavlink_highres_imu_t *)msgbuf; + packet->time_usec = time_usec; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->xmag = xmag; + packet->ymag = ymag; + packet->zmag = zmag; + packet->abs_pressure = abs_pressure; + packet->diff_pressure = diff_pressure; + packet->pressure_alt = pressure_alt; + packet->temperature = temperature; + packet->fields_updated = fields_updated; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIGHRES_IMU UNPACKING + + +/** + * @brief Get field time_usec from highres_imu message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_highres_imu_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field xacc from highres_imu message + * + * @return X acceleration (m/s^2) + */ +static inline float mavlink_msg_highres_imu_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yacc from highres_imu message + * + * @return Y acceleration (m/s^2) + */ +static inline float mavlink_msg_highres_imu_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field zacc from highres_imu message + * + * @return Z acceleration (m/s^2) + */ +static inline float mavlink_msg_highres_imu_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field xgyro from highres_imu message + * + * @return Angular speed around X axis (rad / sec) + */ +static inline float mavlink_msg_highres_imu_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field ygyro from highres_imu message + * + * @return Angular speed around Y axis (rad / sec) + */ +static inline float mavlink_msg_highres_imu_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field zgyro from highres_imu message + * + * @return Angular speed around Z axis (rad / sec) + */ +static inline float mavlink_msg_highres_imu_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field xmag from highres_imu message + * + * @return X Magnetic field (Gauss) + */ +static inline float mavlink_msg_highres_imu_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field ymag from highres_imu message + * + * @return Y Magnetic field (Gauss) + */ +static inline float mavlink_msg_highres_imu_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field zmag from highres_imu message + * + * @return Z Magnetic field (Gauss) + */ +static inline float mavlink_msg_highres_imu_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field abs_pressure from highres_imu message + * + * @return Absolute pressure in millibar + */ +static inline float mavlink_msg_highres_imu_get_abs_pressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field diff_pressure from highres_imu message + * + * @return Differential pressure in millibar + */ +static inline float mavlink_msg_highres_imu_get_diff_pressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 48); +} + +/** + * @brief Get field pressure_alt from highres_imu message + * + * @return Altitude calculated from pressure + */ +static inline float mavlink_msg_highres_imu_get_pressure_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 52); +} + +/** + * @brief Get field temperature from highres_imu message + * + * @return Temperature in degrees celsius + */ +static inline float mavlink_msg_highres_imu_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 56); +} + +/** + * @brief Get field fields_updated from highres_imu message + * + * @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + */ +static inline uint16_t mavlink_msg_highres_imu_get_fields_updated(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 60); +} + +/** + * @brief Decode a highres_imu message into a struct + * + * @param msg The message to decode + * @param highres_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_highres_imu_decode(const mavlink_message_t* msg, mavlink_highres_imu_t* highres_imu) +{ +#if MAVLINK_NEED_BYTE_SWAP + highres_imu->time_usec = mavlink_msg_highres_imu_get_time_usec(msg); + highres_imu->xacc = mavlink_msg_highres_imu_get_xacc(msg); + highres_imu->yacc = mavlink_msg_highres_imu_get_yacc(msg); + highres_imu->zacc = mavlink_msg_highres_imu_get_zacc(msg); + highres_imu->xgyro = mavlink_msg_highres_imu_get_xgyro(msg); + highres_imu->ygyro = mavlink_msg_highres_imu_get_ygyro(msg); + highres_imu->zgyro = mavlink_msg_highres_imu_get_zgyro(msg); + highres_imu->xmag = mavlink_msg_highres_imu_get_xmag(msg); + highres_imu->ymag = mavlink_msg_highres_imu_get_ymag(msg); + highres_imu->zmag = mavlink_msg_highres_imu_get_zmag(msg); + highres_imu->abs_pressure = mavlink_msg_highres_imu_get_abs_pressure(msg); + highres_imu->diff_pressure = mavlink_msg_highres_imu_get_diff_pressure(msg); + highres_imu->pressure_alt = mavlink_msg_highres_imu_get_pressure_alt(msg); + highres_imu->temperature = mavlink_msg_highres_imu_get_temperature(msg); + highres_imu->fields_updated = mavlink_msg_highres_imu_get_fields_updated(msg); +#else + memcpy(highres_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIGHRES_IMU_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_controls.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_controls.h new file mode 100644 index 0000000..4d586af --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_controls.h @@ -0,0 +1,449 @@ +// MESSAGE HIL_CONTROLS PACKING + +#define MAVLINK_MSG_ID_HIL_CONTROLS 91 + +typedef struct __mavlink_hil_controls_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + float roll_ailerons; /*< Control output -1 .. 1*/ + float pitch_elevator; /*< Control output -1 .. 1*/ + float yaw_rudder; /*< Control output -1 .. 1*/ + float throttle; /*< Throttle 0 .. 1*/ + float aux1; /*< Aux 1, -1 .. 1*/ + float aux2; /*< Aux 2, -1 .. 1*/ + float aux3; /*< Aux 3, -1 .. 1*/ + float aux4; /*< Aux 4, -1 .. 1*/ + uint8_t mode; /*< System mode (MAV_MODE)*/ + uint8_t nav_mode; /*< Navigation mode (MAV_NAV_MODE)*/ +} mavlink_hil_controls_t; + +#define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42 +#define MAVLINK_MSG_ID_91_LEN 42 + +#define MAVLINK_MSG_ID_HIL_CONTROLS_CRC 63 +#define MAVLINK_MSG_ID_91_CRC 63 + + + +#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \ + "HIL_CONTROLS", \ + 11, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \ + { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \ + { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \ + { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \ + { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \ + { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \ + { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \ + { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \ + { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \ + { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \ + { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \ + } \ +} + + +/** + * @brief Pack a hil_controls message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll_ailerons Control output -1 .. 1 + * @param pitch_elevator Control output -1 .. 1 + * @param yaw_rudder Control output -1 .. 1 + * @param throttle Throttle 0 .. 1 + * @param aux1 Aux 1, -1 .. 1 + * @param aux2 Aux 2, -1 .. 1 + * @param aux3 Aux 3, -1 .. 1 + * @param aux4 Aux 4, -1 .. 1 + * @param mode System mode (MAV_MODE) + * @param nav_mode Navigation mode (MAV_NAV_MODE) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll_ailerons); + _mav_put_float(buf, 12, pitch_elevator); + _mav_put_float(buf, 16, yaw_rudder); + _mav_put_float(buf, 20, throttle); + _mav_put_float(buf, 24, aux1); + _mav_put_float(buf, 28, aux2); + _mav_put_float(buf, 32, aux3); + _mav_put_float(buf, 36, aux4); + _mav_put_uint8_t(buf, 40, mode); + _mav_put_uint8_t(buf, 41, nav_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#else + mavlink_hil_controls_t packet; + packet.time_usec = time_usec; + packet.roll_ailerons = roll_ailerons; + packet.pitch_elevator = pitch_elevator; + packet.yaw_rudder = yaw_rudder; + packet.throttle = throttle; + packet.aux1 = aux1; + packet.aux2 = aux2; + packet.aux3 = aux3; + packet.aux4 = aux4; + packet.mode = mode; + packet.nav_mode = nav_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif +} + +/** + * @brief Pack a hil_controls message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll_ailerons Control output -1 .. 1 + * @param pitch_elevator Control output -1 .. 1 + * @param yaw_rudder Control output -1 .. 1 + * @param throttle Throttle 0 .. 1 + * @param aux1 Aux 1, -1 .. 1 + * @param aux2 Aux 2, -1 .. 1 + * @param aux3 Aux 3, -1 .. 1 + * @param aux4 Aux 4, -1 .. 1 + * @param mode System mode (MAV_MODE) + * @param nav_mode Navigation mode (MAV_NAV_MODE) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,uint8_t mode,uint8_t nav_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll_ailerons); + _mav_put_float(buf, 12, pitch_elevator); + _mav_put_float(buf, 16, yaw_rudder); + _mav_put_float(buf, 20, throttle); + _mav_put_float(buf, 24, aux1); + _mav_put_float(buf, 28, aux2); + _mav_put_float(buf, 32, aux3); + _mav_put_float(buf, 36, aux4); + _mav_put_uint8_t(buf, 40, mode); + _mav_put_uint8_t(buf, 41, nav_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#else + mavlink_hil_controls_t packet; + packet.time_usec = time_usec; + packet.roll_ailerons = roll_ailerons; + packet.pitch_elevator = pitch_elevator; + packet.yaw_rudder = yaw_rudder; + packet.throttle = throttle; + packet.aux1 = aux1; + packet.aux2 = aux2; + packet.aux3 = aux3; + packet.aux4 = aux4; + packet.mode = mode; + packet.nav_mode = nav_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif +} + +/** + * @brief Encode a hil_controls struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_controls C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls) +{ + return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); +} + +/** + * @brief Encode a hil_controls struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param hil_controls C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_controls_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls) +{ + return mavlink_msg_hil_controls_pack_chan(system_id, component_id, chan, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); +} + +/** + * @brief Send a hil_controls message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll_ailerons Control output -1 .. 1 + * @param pitch_elevator Control output -1 .. 1 + * @param yaw_rudder Control output -1 .. 1 + * @param throttle Throttle 0 .. 1 + * @param aux1 Aux 1, -1 .. 1 + * @param aux2 Aux 2, -1 .. 1 + * @param aux3 Aux 3, -1 .. 1 + * @param aux4 Aux 4, -1 .. 1 + * @param mode System mode (MAV_MODE) + * @param nav_mode Navigation mode (MAV_NAV_MODE) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll_ailerons); + _mav_put_float(buf, 12, pitch_elevator); + _mav_put_float(buf, 16, yaw_rudder); + _mav_put_float(buf, 20, throttle); + _mav_put_float(buf, 24, aux1); + _mav_put_float(buf, 28, aux2); + _mav_put_float(buf, 32, aux3); + _mav_put_float(buf, 36, aux4); + _mav_put_uint8_t(buf, 40, mode); + _mav_put_uint8_t(buf, 41, nav_mode); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif +#else + mavlink_hil_controls_t packet; + packet.time_usec = time_usec; + packet.roll_ailerons = roll_ailerons; + packet.pitch_elevator = pitch_elevator; + packet.yaw_rudder = yaw_rudder; + packet.throttle = throttle; + packet.aux1 = aux1; + packet.aux2 = aux2; + packet.aux3 = aux3; + packet.aux4 = aux4; + packet.mode = mode; + packet.nav_mode = nav_mode; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIL_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_hil_controls_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll_ailerons); + _mav_put_float(buf, 12, pitch_elevator); + _mav_put_float(buf, 16, yaw_rudder); + _mav_put_float(buf, 20, throttle); + _mav_put_float(buf, 24, aux1); + _mav_put_float(buf, 28, aux2); + _mav_put_float(buf, 32, aux3); + _mav_put_float(buf, 36, aux4); + _mav_put_uint8_t(buf, 40, mode); + _mav_put_uint8_t(buf, 41, nav_mode); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif +#else + mavlink_hil_controls_t *packet = (mavlink_hil_controls_t *)msgbuf; + packet->time_usec = time_usec; + packet->roll_ailerons = roll_ailerons; + packet->pitch_elevator = pitch_elevator; + packet->yaw_rudder = yaw_rudder; + packet->throttle = throttle; + packet->aux1 = aux1; + packet->aux2 = aux2; + packet->aux3 = aux3; + packet->aux4 = aux4; + packet->mode = mode; + packet->nav_mode = nav_mode; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIL_CONTROLS UNPACKING + + +/** + * @brief Get field time_usec from hil_controls message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field roll_ailerons from hil_controls message + * + * @return Control output -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field pitch_elevator from hil_controls message + * + * @return Control output -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field yaw_rudder from hil_controls message + * + * @return Control output -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field throttle from hil_controls message + * + * @return Throttle 0 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field aux1 from hil_controls message + * + * @return Aux 1, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field aux2 from hil_controls message + * + * @return Aux 2, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field aux3 from hil_controls message + * + * @return Aux 3, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field aux4 from hil_controls message + * + * @return Aux 4, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field mode from hil_controls message + * + * @return System mode (MAV_MODE) + */ +static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 40); +} + +/** + * @brief Get field nav_mode from hil_controls message + * + * @return Navigation mode (MAV_NAV_MODE) + */ +static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 41); +} + +/** + * @brief Decode a hil_controls message into a struct + * + * @param msg The message to decode + * @param hil_controls C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_controls->time_usec = mavlink_msg_hil_controls_get_time_usec(msg); + hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg); + hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg); + hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg); + hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg); + hil_controls->aux1 = mavlink_msg_hil_controls_get_aux1(msg); + hil_controls->aux2 = mavlink_msg_hil_controls_get_aux2(msg); + hil_controls->aux3 = mavlink_msg_hil_controls_get_aux3(msg); + hil_controls->aux4 = mavlink_msg_hil_controls_get_aux4(msg); + hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg); + hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg); +#else + memcpy(hil_controls, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_CONTROLS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_gps.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_gps.h new file mode 100644 index 0000000..aef125c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_gps.h @@ -0,0 +1,497 @@ +// MESSAGE HIL_GPS PACKING + +#define MAVLINK_MSG_ID_HIL_GPS 113 + +typedef struct __mavlink_hil_gps_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/ + int32_t alt; /*< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)*/ + uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535*/ + uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535*/ + uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: 65535*/ + int16_t vn; /*< GPS velocity in cm/s in NORTH direction in earth-fixed NED frame*/ + int16_t ve; /*< GPS velocity in cm/s in EAST direction in earth-fixed NED frame*/ + int16_t vd; /*< GPS velocity in cm/s in DOWN direction in earth-fixed NED frame*/ + uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535*/ + uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.*/ + uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/ +} mavlink_hil_gps_t; + +#define MAVLINK_MSG_ID_HIL_GPS_LEN 36 +#define MAVLINK_MSG_ID_113_LEN 36 + +#define MAVLINK_MSG_ID_HIL_GPS_CRC 124 +#define MAVLINK_MSG_ID_113_CRC 124 + + + +#define MAVLINK_MESSAGE_INFO_HIL_GPS { \ + "HIL_GPS", \ + 13, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \ + { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_gps_t, eph) }, \ + { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_gps_t, epv) }, \ + { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_gps_t, vel) }, \ + { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_hil_gps_t, vn) }, \ + { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \ + { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \ + { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \ + { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \ + } \ +} + + +/** + * @brief Pack a hil_gps message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 + * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 + * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame + * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame + * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_int16_t(buf, 26, vn); + _mav_put_int16_t(buf, 28, ve); + _mav_put_int16_t(buf, 30, vd); + _mav_put_uint16_t(buf, 32, cog); + _mav_put_uint8_t(buf, 34, fix_type); + _mav_put_uint8_t(buf, 35, satellites_visible); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN); +#else + mavlink_hil_gps_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.vn = vn; + packet.ve = ve; + packet.vd = vd; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_GPS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif +} + +/** + * @brief Pack a hil_gps message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 + * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 + * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame + * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame + * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_gps_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,int16_t vn,int16_t ve,int16_t vd,uint16_t cog,uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_int16_t(buf, 26, vn); + _mav_put_int16_t(buf, 28, ve); + _mav_put_int16_t(buf, 30, vd); + _mav_put_uint16_t(buf, 32, cog); + _mav_put_uint8_t(buf, 34, fix_type); + _mav_put_uint8_t(buf, 35, satellites_visible); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN); +#else + mavlink_hil_gps_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.vn = vn; + packet.ve = ve; + packet.vd = vd; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_GPS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif +} + +/** + * @brief Encode a hil_gps struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_gps C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_gps_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps) +{ + return mavlink_msg_hil_gps_pack(system_id, component_id, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible); +} + +/** + * @brief Encode a hil_gps struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param hil_gps C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps) +{ + return mavlink_msg_hil_gps_pack_chan(system_id, component_id, chan, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible); +} + +/** + * @brief Send a hil_gps message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude (WGS84), in degrees * 1E7 + * @param lon Longitude (WGS84), in degrees * 1E7 + * @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 + * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 + * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame + * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame + * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_gps_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_int16_t(buf, 26, vn); + _mav_put_int16_t(buf, 28, ve); + _mav_put_int16_t(buf, 30, vd); + _mav_put_uint16_t(buf, 32, cog); + _mav_put_uint8_t(buf, 34, fix_type); + _mav_put_uint8_t(buf, 35, satellites_visible); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif +#else + mavlink_hil_gps_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.vn = vn; + packet.ve = ve; + packet.vd = vd; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIL_GPS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_hil_gps_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_int16_t(buf, 26, vn); + _mav_put_int16_t(buf, 28, ve); + _mav_put_int16_t(buf, 30, vd); + _mav_put_uint16_t(buf, 32, cog); + _mav_put_uint8_t(buf, 34, fix_type); + _mav_put_uint8_t(buf, 35, satellites_visible); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif +#else + mavlink_hil_gps_t *packet = (mavlink_hil_gps_t *)msgbuf; + packet->time_usec = time_usec; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->eph = eph; + packet->epv = epv; + packet->vel = vel; + packet->vn = vn; + packet->ve = ve; + packet->vd = vd; + packet->cog = cog; + packet->fix_type = fix_type; + packet->satellites_visible = satellites_visible; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIL_GPS UNPACKING + + +/** + * @brief Get field time_usec from hil_gps message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_gps_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field fix_type from hil_gps message + * + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + */ +static inline uint8_t mavlink_msg_hil_gps_get_fix_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field lat from hil_gps message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field lon from hil_gps message + * + * @return Longitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field alt from hil_gps message + * + * @return Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field eph from hil_gps message + * + * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field epv from hil_gps message + * + * @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field vel from hil_gps message + * + * @return GPS ground speed (m/s * 100). If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field vn from hil_gps message + * + * @return GPS velocity in cm/s in NORTH direction in earth-fixed NED frame + */ +static inline int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 26); +} + +/** + * @brief Get field ve from hil_gps message + * + * @return GPS velocity in cm/s in EAST direction in earth-fixed NED frame + */ +static inline int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 28); +} + +/** + * @brief Get field vd from hil_gps message + * + * @return GPS velocity in cm/s in DOWN direction in earth-fixed NED frame + */ +static inline int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 30); +} + +/** + * @brief Get field cog from hil_gps message + * + * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_hil_gps_get_cog(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 32); +} + +/** + * @brief Get field satellites_visible from hil_gps message + * + * @return Number of satellites visible. If unknown, set to 255 + */ +static inline uint8_t mavlink_msg_hil_gps_get_satellites_visible(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 35); +} + +/** + * @brief Decode a hil_gps message into a struct + * + * @param msg The message to decode + * @param hil_gps C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_gps_decode(const mavlink_message_t* msg, mavlink_hil_gps_t* hil_gps) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_gps->time_usec = mavlink_msg_hil_gps_get_time_usec(msg); + hil_gps->lat = mavlink_msg_hil_gps_get_lat(msg); + hil_gps->lon = mavlink_msg_hil_gps_get_lon(msg); + hil_gps->alt = mavlink_msg_hil_gps_get_alt(msg); + hil_gps->eph = mavlink_msg_hil_gps_get_eph(msg); + hil_gps->epv = mavlink_msg_hil_gps_get_epv(msg); + hil_gps->vel = mavlink_msg_hil_gps_get_vel(msg); + hil_gps->vn = mavlink_msg_hil_gps_get_vn(msg); + hil_gps->ve = mavlink_msg_hil_gps_get_ve(msg); + hil_gps->vd = mavlink_msg_hil_gps_get_vd(msg); + hil_gps->cog = mavlink_msg_hil_gps_get_cog(msg); + hil_gps->fix_type = mavlink_msg_hil_gps_get_fix_type(msg); + hil_gps->satellites_visible = mavlink_msg_hil_gps_get_satellites_visible(msg); +#else + memcpy(hil_gps, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_GPS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h new file mode 100644 index 0000000..27abb05 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h @@ -0,0 +1,473 @@ +// MESSAGE HIL_OPTICAL_FLOW PACKING + +#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW 114 + +typedef struct __mavlink_hil_optical_flow_t +{ + uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + uint32_t integration_time_us; /*< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/ + float integrated_x; /*< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/ + float integrated_y; /*< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/ + float integrated_xgyro; /*< RH rotation around X axis (rad)*/ + float integrated_ygyro; /*< RH rotation around Y axis (rad)*/ + float integrated_zgyro; /*< RH rotation around Z axis (rad)*/ + uint32_t time_delta_distance_us; /*< Time in microseconds since the distance was sampled.*/ + float distance; /*< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.*/ + int16_t temperature; /*< Temperature * 100 in centi-degrees Celsius*/ + uint8_t sensor_id; /*< Sensor ID*/ + uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/ +} mavlink_hil_optical_flow_t; + +#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 44 +#define MAVLINK_MSG_ID_114_LEN 44 + +#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC 237 +#define MAVLINK_MSG_ID_114_CRC 237 + + + +#define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW { \ + "HIL_OPTICAL_FLOW", \ + 12, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \ + { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \ + { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \ + { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \ + { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \ + { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \ + { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \ + { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \ + { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \ + { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \ + } \ +} + + +/** + * @brief Pack a hil_optical_flow message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param sensor_id Sensor ID + * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro RH rotation around X axis (rad) + * @param integrated_ygyro RH rotation around Y axis (rad) + * @param integrated_zgyro RH rotation around Z axis (rad) + * @param temperature Temperature * 100 in centi-degrees Celsius + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us Time in microseconds since the distance was sampled. + * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#else + mavlink_hil_optical_flow_t packet; + packet.time_usec = time_usec; + packet.integration_time_us = integration_time_us; + packet.integrated_x = integrated_x; + packet.integrated_y = integrated_y; + packet.integrated_xgyro = integrated_xgyro; + packet.integrated_ygyro = integrated_ygyro; + packet.integrated_zgyro = integrated_zgyro; + packet.time_delta_distance_us = time_delta_distance_us; + packet.distance = distance; + packet.temperature = temperature; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif +} + +/** + * @brief Pack a hil_optical_flow message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param sensor_id Sensor ID + * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro RH rotation around X axis (rad) + * @param integrated_ygyro RH rotation around Y axis (rad) + * @param integrated_zgyro RH rotation around Z axis (rad) + * @param temperature Temperature * 100 in centi-degrees Celsius + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us Time in microseconds since the distance was sampled. + * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t sensor_id,uint32_t integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,int16_t temperature,uint8_t quality,uint32_t time_delta_distance_us,float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#else + mavlink_hil_optical_flow_t packet; + packet.time_usec = time_usec; + packet.integration_time_us = integration_time_us; + packet.integrated_x = integrated_x; + packet.integrated_y = integrated_y; + packet.integrated_xgyro = integrated_xgyro; + packet.integrated_ygyro = integrated_ygyro; + packet.integrated_zgyro = integrated_zgyro; + packet.time_delta_distance_us = time_delta_distance_us; + packet.distance = distance; + packet.temperature = temperature; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif +} + +/** + * @brief Encode a hil_optical_flow struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_optical_flow C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow) +{ + return mavlink_msg_hil_optical_flow_pack(system_id, component_id, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance); +} + +/** + * @brief Encode a hil_optical_flow struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param hil_optical_flow C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow) +{ + return mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, chan, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance); +} + +/** + * @brief Send a hil_optical_flow message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param sensor_id Sensor ID + * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro RH rotation around X axis (rad) + * @param integrated_ygyro RH rotation around Y axis (rad) + * @param integrated_zgyro RH rotation around Z axis (rad) + * @param temperature Temperature * 100 in centi-degrees Celsius + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us Time in microseconds since the distance was sampled. + * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif +#else + mavlink_hil_optical_flow_t packet; + packet.time_usec = time_usec; + packet.integration_time_us = integration_time_us; + packet.integrated_x = integrated_x; + packet.integrated_y = integrated_y; + packet.integrated_xgyro = integrated_xgyro; + packet.integrated_ygyro = integrated_ygyro; + packet.integrated_zgyro = integrated_zgyro; + packet.time_delta_distance_us = time_delta_distance_us; + packet.distance = distance; + packet.temperature = temperature; + packet.sensor_id = sensor_id; + packet.quality = quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_hil_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif +#else + mavlink_hil_optical_flow_t *packet = (mavlink_hil_optical_flow_t *)msgbuf; + packet->time_usec = time_usec; + packet->integration_time_us = integration_time_us; + packet->integrated_x = integrated_x; + packet->integrated_y = integrated_y; + packet->integrated_xgyro = integrated_xgyro; + packet->integrated_ygyro = integrated_ygyro; + packet->integrated_zgyro = integrated_zgyro; + packet->time_delta_distance_us = time_delta_distance_us; + packet->distance = distance; + packet->temperature = temperature; + packet->sensor_id = sensor_id; + packet->quality = quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIL_OPTICAL_FLOW UNPACKING + + +/** + * @brief Get field time_usec from hil_optical_flow message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_hil_optical_flow_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field sensor_id from hil_optical_flow message + * + * @return Sensor ID + */ +static inline uint8_t mavlink_msg_hil_optical_flow_get_sensor_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 42); +} + +/** + * @brief Get field integration_time_us from hil_optical_flow message + * + * @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + */ +static inline uint32_t mavlink_msg_hil_optical_flow_get_integration_time_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field integrated_x from hil_optical_flow message + * + * @return Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + */ +static inline float mavlink_msg_hil_optical_flow_get_integrated_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field integrated_y from hil_optical_flow message + * + * @return Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + */ +static inline float mavlink_msg_hil_optical_flow_get_integrated_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field integrated_xgyro from hil_optical_flow message + * + * @return RH rotation around X axis (rad) + */ +static inline float mavlink_msg_hil_optical_flow_get_integrated_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field integrated_ygyro from hil_optical_flow message + * + * @return RH rotation around Y axis (rad) + */ +static inline float mavlink_msg_hil_optical_flow_get_integrated_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field integrated_zgyro from hil_optical_flow message + * + * @return RH rotation around Z axis (rad) + */ +static inline float mavlink_msg_hil_optical_flow_get_integrated_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field temperature from hil_optical_flow message + * + * @return Temperature * 100 in centi-degrees Celsius + */ +static inline int16_t mavlink_msg_hil_optical_flow_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 40); +} + +/** + * @brief Get field quality from hil_optical_flow message + * + * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + */ +static inline uint8_t mavlink_msg_hil_optical_flow_get_quality(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 43); +} + +/** + * @brief Get field time_delta_distance_us from hil_optical_flow message + * + * @return Time in microseconds since the distance was sampled. + */ +static inline uint32_t mavlink_msg_hil_optical_flow_get_time_delta_distance_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 32); +} + +/** + * @brief Get field distance from hil_optical_flow message + * + * @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + */ +static inline float mavlink_msg_hil_optical_flow_get_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Decode a hil_optical_flow message into a struct + * + * @param msg The message to decode + * @param hil_optical_flow C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_optical_flow_decode(const mavlink_message_t* msg, mavlink_hil_optical_flow_t* hil_optical_flow) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_optical_flow->time_usec = mavlink_msg_hil_optical_flow_get_time_usec(msg); + hil_optical_flow->integration_time_us = mavlink_msg_hil_optical_flow_get_integration_time_us(msg); + hil_optical_flow->integrated_x = mavlink_msg_hil_optical_flow_get_integrated_x(msg); + hil_optical_flow->integrated_y = mavlink_msg_hil_optical_flow_get_integrated_y(msg); + hil_optical_flow->integrated_xgyro = mavlink_msg_hil_optical_flow_get_integrated_xgyro(msg); + hil_optical_flow->integrated_ygyro = mavlink_msg_hil_optical_flow_get_integrated_ygyro(msg); + hil_optical_flow->integrated_zgyro = mavlink_msg_hil_optical_flow_get_integrated_zgyro(msg); + hil_optical_flow->time_delta_distance_us = mavlink_msg_hil_optical_flow_get_time_delta_distance_us(msg); + hil_optical_flow->distance = mavlink_msg_hil_optical_flow_get_distance(msg); + hil_optical_flow->temperature = mavlink_msg_hil_optical_flow_get_temperature(msg); + hil_optical_flow->sensor_id = mavlink_msg_hil_optical_flow_get_sensor_id(msg); + hil_optical_flow->quality = mavlink_msg_hil_optical_flow_get_quality(msg); +#else + memcpy(hil_optical_flow, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h new file mode 100644 index 0000000..be30cd4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h @@ -0,0 +1,521 @@ +// MESSAGE HIL_RC_INPUTS_RAW PACKING + +#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW 92 + +typedef struct __mavlink_hil_rc_inputs_raw_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + uint16_t chan1_raw; /*< RC channel 1 value, in microseconds*/ + uint16_t chan2_raw; /*< RC channel 2 value, in microseconds*/ + uint16_t chan3_raw; /*< RC channel 3 value, in microseconds*/ + uint16_t chan4_raw; /*< RC channel 4 value, in microseconds*/ + uint16_t chan5_raw; /*< RC channel 5 value, in microseconds*/ + uint16_t chan6_raw; /*< RC channel 6 value, in microseconds*/ + uint16_t chan7_raw; /*< RC channel 7 value, in microseconds*/ + uint16_t chan8_raw; /*< RC channel 8 value, in microseconds*/ + uint16_t chan9_raw; /*< RC channel 9 value, in microseconds*/ + uint16_t chan10_raw; /*< RC channel 10 value, in microseconds*/ + uint16_t chan11_raw; /*< RC channel 11 value, in microseconds*/ + uint16_t chan12_raw; /*< RC channel 12 value, in microseconds*/ + uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 255: 100%*/ +} mavlink_hil_rc_inputs_raw_t; + +#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33 +#define MAVLINK_MSG_ID_92_LEN 33 + +#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC 54 +#define MAVLINK_MSG_ID_92_CRC 54 + + + +#define MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW { \ + "HIL_RC_INPUTS_RAW", \ + 14, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_rc_inputs_raw_t, time_usec) }, \ + { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_hil_rc_inputs_raw_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_hil_rc_inputs_raw_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_hil_rc_inputs_raw_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_hil_rc_inputs_raw_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_hil_rc_inputs_raw_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_hil_rc_inputs_raw_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_rc_inputs_raw_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_rc_inputs_raw_t, chan8_raw) }, \ + { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_rc_inputs_raw_t, chan9_raw) }, \ + { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_hil_rc_inputs_raw_t, chan10_raw) }, \ + { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_hil_rc_inputs_raw_t, chan11_raw) }, \ + { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_hil_rc_inputs_raw_t, chan12_raw) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_hil_rc_inputs_raw_t, rssi) }, \ + } \ +} + + +/** + * @brief Pack a hil_rc_inputs_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param chan9_raw RC channel 9 value, in microseconds + * @param chan10_raw RC channel 10 value, in microseconds + * @param chan11_raw RC channel 11 value, in microseconds + * @param chan12_raw RC channel 12 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 8, chan1_raw); + _mav_put_uint16_t(buf, 10, chan2_raw); + _mav_put_uint16_t(buf, 12, chan3_raw); + _mav_put_uint16_t(buf, 14, chan4_raw); + _mav_put_uint16_t(buf, 16, chan5_raw); + _mav_put_uint16_t(buf, 18, chan6_raw); + _mav_put_uint16_t(buf, 20, chan7_raw); + _mav_put_uint16_t(buf, 22, chan8_raw); + _mav_put_uint16_t(buf, 24, chan9_raw); + _mav_put_uint16_t(buf, 26, chan10_raw); + _mav_put_uint16_t(buf, 28, chan11_raw); + _mav_put_uint16_t(buf, 30, chan12_raw); + _mav_put_uint8_t(buf, 32, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#else + mavlink_hil_rc_inputs_raw_t packet; + packet.time_usec = time_usec; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif +} + +/** + * @brief Pack a hil_rc_inputs_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param chan9_raw RC channel 9 value, in microseconds + * @param chan10_raw RC channel 10 value, in microseconds + * @param chan11_raw RC channel 11 value, in microseconds + * @param chan12_raw RC channel 12 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 8, chan1_raw); + _mav_put_uint16_t(buf, 10, chan2_raw); + _mav_put_uint16_t(buf, 12, chan3_raw); + _mav_put_uint16_t(buf, 14, chan4_raw); + _mav_put_uint16_t(buf, 16, chan5_raw); + _mav_put_uint16_t(buf, 18, chan6_raw); + _mav_put_uint16_t(buf, 20, chan7_raw); + _mav_put_uint16_t(buf, 22, chan8_raw); + _mav_put_uint16_t(buf, 24, chan9_raw); + _mav_put_uint16_t(buf, 26, chan10_raw); + _mav_put_uint16_t(buf, 28, chan11_raw); + _mav_put_uint16_t(buf, 30, chan12_raw); + _mav_put_uint8_t(buf, 32, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#else + mavlink_hil_rc_inputs_raw_t packet; + packet.time_usec = time_usec; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif +} + +/** + * @brief Encode a hil_rc_inputs_raw struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_rc_inputs_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) +{ + return mavlink_msg_hil_rc_inputs_raw_pack(system_id, component_id, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); +} + +/** + * @brief Encode a hil_rc_inputs_raw struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param hil_rc_inputs_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) +{ + return mavlink_msg_hil_rc_inputs_raw_pack_chan(system_id, component_id, chan, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); +} + +/** + * @brief Send a hil_rc_inputs_raw message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param chan9_raw RC channel 9 value, in microseconds + * @param chan10_raw RC channel 10 value, in microseconds + * @param chan11_raw RC channel 11 value, in microseconds + * @param chan12_raw RC channel 12 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_rc_inputs_raw_send(mavlink_channel_t chan, uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 8, chan1_raw); + _mav_put_uint16_t(buf, 10, chan2_raw); + _mav_put_uint16_t(buf, 12, chan3_raw); + _mav_put_uint16_t(buf, 14, chan4_raw); + _mav_put_uint16_t(buf, 16, chan5_raw); + _mav_put_uint16_t(buf, 18, chan6_raw); + _mav_put_uint16_t(buf, 20, chan7_raw); + _mav_put_uint16_t(buf, 22, chan8_raw); + _mav_put_uint16_t(buf, 24, chan9_raw); + _mav_put_uint16_t(buf, 26, chan10_raw); + _mav_put_uint16_t(buf, 28, chan11_raw); + _mav_put_uint16_t(buf, 30, chan12_raw); + _mav_put_uint8_t(buf, 32, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif +#else + mavlink_hil_rc_inputs_raw_t packet; + packet.time_usec = time_usec; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_hil_rc_inputs_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 8, chan1_raw); + _mav_put_uint16_t(buf, 10, chan2_raw); + _mav_put_uint16_t(buf, 12, chan3_raw); + _mav_put_uint16_t(buf, 14, chan4_raw); + _mav_put_uint16_t(buf, 16, chan5_raw); + _mav_put_uint16_t(buf, 18, chan6_raw); + _mav_put_uint16_t(buf, 20, chan7_raw); + _mav_put_uint16_t(buf, 22, chan8_raw); + _mav_put_uint16_t(buf, 24, chan9_raw); + _mav_put_uint16_t(buf, 26, chan10_raw); + _mav_put_uint16_t(buf, 28, chan11_raw); + _mav_put_uint16_t(buf, 30, chan12_raw); + _mav_put_uint8_t(buf, 32, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif +#else + mavlink_hil_rc_inputs_raw_t *packet = (mavlink_hil_rc_inputs_raw_t *)msgbuf; + packet->time_usec = time_usec; + packet->chan1_raw = chan1_raw; + packet->chan2_raw = chan2_raw; + packet->chan3_raw = chan3_raw; + packet->chan4_raw = chan4_raw; + packet->chan5_raw = chan5_raw; + packet->chan6_raw = chan6_raw; + packet->chan7_raw = chan7_raw; + packet->chan8_raw = chan8_raw; + packet->chan9_raw = chan9_raw; + packet->chan10_raw = chan10_raw; + packet->chan11_raw = chan11_raw; + packet->chan12_raw = chan12_raw; + packet->rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIL_RC_INPUTS_RAW UNPACKING + + +/** + * @brief Get field time_usec from hil_rc_inputs_raw message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_rc_inputs_raw_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field chan1_raw from hil_rc_inputs_raw message + * + * @return RC channel 1 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field chan2_raw from hil_rc_inputs_raw message + * + * @return RC channel 2 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field chan3_raw from hil_rc_inputs_raw message + * + * @return RC channel 3 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field chan4_raw from hil_rc_inputs_raw message + * + * @return RC channel 4 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field chan5_raw from hil_rc_inputs_raw message + * + * @return RC channel 5 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field chan6_raw from hil_rc_inputs_raw message + * + * @return RC channel 6 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field chan7_raw from hil_rc_inputs_raw message + * + * @return RC channel 7 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field chan8_raw from hil_rc_inputs_raw message + * + * @return RC channel 8 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field chan9_raw from hil_rc_inputs_raw message + * + * @return RC channel 9 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field chan10_raw from hil_rc_inputs_raw message + * + * @return RC channel 10 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field chan11_raw from hil_rc_inputs_raw message + * + * @return RC channel 11 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field chan12_raw from hil_rc_inputs_raw message + * + * @return RC channel 12 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 30); +} + +/** + * @brief Get field rssi from hil_rc_inputs_raw message + * + * @return Receive signal strength indicator, 0: 0%, 255: 100% + */ +static inline uint8_t mavlink_msg_hil_rc_inputs_raw_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Decode a hil_rc_inputs_raw message into a struct + * + * @param msg The message to decode + * @param hil_rc_inputs_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_rc_inputs_raw_decode(const mavlink_message_t* msg, mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_rc_inputs_raw->time_usec = mavlink_msg_hil_rc_inputs_raw_get_time_usec(msg); + hil_rc_inputs_raw->chan1_raw = mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(msg); + hil_rc_inputs_raw->chan2_raw = mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(msg); + hil_rc_inputs_raw->chan3_raw = mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(msg); + hil_rc_inputs_raw->chan4_raw = mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(msg); + hil_rc_inputs_raw->chan5_raw = mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(msg); + hil_rc_inputs_raw->chan6_raw = mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(msg); + hil_rc_inputs_raw->chan7_raw = mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(msg); + hil_rc_inputs_raw->chan8_raw = mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(msg); + hil_rc_inputs_raw->chan9_raw = mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(msg); + hil_rc_inputs_raw->chan10_raw = mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(msg); + hil_rc_inputs_raw->chan11_raw = mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(msg); + hil_rc_inputs_raw->chan12_raw = mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(msg); + hil_rc_inputs_raw->rssi = mavlink_msg_hil_rc_inputs_raw_get_rssi(msg); +#else + memcpy(hil_rc_inputs_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_sensor.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_sensor.h new file mode 100644 index 0000000..baa3b27 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_sensor.h @@ -0,0 +1,545 @@ +// MESSAGE HIL_SENSOR PACKING + +#define MAVLINK_MSG_ID_HIL_SENSOR 107 + +typedef struct __mavlink_hil_sensor_t +{ + uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + float xacc; /*< X acceleration (m/s^2)*/ + float yacc; /*< Y acceleration (m/s^2)*/ + float zacc; /*< Z acceleration (m/s^2)*/ + float xgyro; /*< Angular speed around X axis in body frame (rad / sec)*/ + float ygyro; /*< Angular speed around Y axis in body frame (rad / sec)*/ + float zgyro; /*< Angular speed around Z axis in body frame (rad / sec)*/ + float xmag; /*< X Magnetic field (Gauss)*/ + float ymag; /*< Y Magnetic field (Gauss)*/ + float zmag; /*< Z Magnetic field (Gauss)*/ + float abs_pressure; /*< Absolute pressure in millibar*/ + float diff_pressure; /*< Differential pressure (airspeed) in millibar*/ + float pressure_alt; /*< Altitude calculated from pressure*/ + float temperature; /*< Temperature in degrees celsius*/ + uint32_t fields_updated; /*< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.*/ +} mavlink_hil_sensor_t; + +#define MAVLINK_MSG_ID_HIL_SENSOR_LEN 64 +#define MAVLINK_MSG_ID_107_LEN 64 + +#define MAVLINK_MSG_ID_HIL_SENSOR_CRC 108 +#define MAVLINK_MSG_ID_107_CRC 108 + + + +#define MAVLINK_MESSAGE_INFO_HIL_SENSOR { \ + "HIL_SENSOR", \ + 15, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_sensor_t, time_usec) }, \ + { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_sensor_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_sensor_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_sensor_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_sensor_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_sensor_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_sensor_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_sensor_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_sensor_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_hil_sensor_t, zmag) }, \ + { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_hil_sensor_t, abs_pressure) }, \ + { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_hil_sensor_t, diff_pressure) }, \ + { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_hil_sensor_t, pressure_alt) }, \ + { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_hil_sensor_t, temperature) }, \ + { "fields_updated", NULL, MAVLINK_TYPE_UINT32_T, 0, 60, offsetof(mavlink_hil_sensor_t, fields_updated) }, \ + } \ +} + + +/** + * @brief Pack a hil_sensor message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param xacc X acceleration (m/s^2) + * @param yacc Y acceleration (m/s^2) + * @param zacc Z acceleration (m/s^2) + * @param xgyro Angular speed around X axis in body frame (rad / sec) + * @param ygyro Angular speed around Y axis in body frame (rad / sec) + * @param zgyro Angular speed around Z axis in body frame (rad / sec) + * @param xmag X Magnetic field (Gauss) + * @param ymag Y Magnetic field (Gauss) + * @param zmag Z Magnetic field (Gauss) + * @param abs_pressure Absolute pressure in millibar + * @param diff_pressure Differential pressure (airspeed) in millibar + * @param pressure_alt Altitude calculated from pressure + * @param temperature Temperature in degrees celsius + * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint32_t(buf, 60, fields_updated); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#else + mavlink_hil_sensor_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + packet.abs_pressure = abs_pressure; + packet.diff_pressure = diff_pressure; + packet.pressure_alt = pressure_alt; + packet.temperature = temperature; + packet.fields_updated = fields_updated; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_SENSOR; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +} + +/** + * @brief Pack a hil_sensor message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param xacc X acceleration (m/s^2) + * @param yacc Y acceleration (m/s^2) + * @param zacc Z acceleration (m/s^2) + * @param xgyro Angular speed around X axis in body frame (rad / sec) + * @param ygyro Angular speed around Y axis in body frame (rad / sec) + * @param zgyro Angular speed around Z axis in body frame (rad / sec) + * @param xmag X Magnetic field (Gauss) + * @param ymag Y Magnetic field (Gauss) + * @param zmag Z Magnetic field (Gauss) + * @param abs_pressure Absolute pressure in millibar + * @param diff_pressure Differential pressure (airspeed) in millibar + * @param pressure_alt Altitude calculated from pressure + * @param temperature Temperature in degrees celsius + * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,uint32_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint32_t(buf, 60, fields_updated); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#else + mavlink_hil_sensor_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + packet.abs_pressure = abs_pressure; + packet.diff_pressure = diff_pressure; + packet.pressure_alt = pressure_alt; + packet.temperature = temperature; + packet.fields_updated = fields_updated; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_SENSOR; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +} + +/** + * @brief Encode a hil_sensor struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_sensor C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_sensor_t* hil_sensor) +{ + return mavlink_msg_hil_sensor_pack(system_id, component_id, msg, hil_sensor->time_usec, hil_sensor->xacc, hil_sensor->yacc, hil_sensor->zacc, hil_sensor->xgyro, hil_sensor->ygyro, hil_sensor->zgyro, hil_sensor->xmag, hil_sensor->ymag, hil_sensor->zmag, hil_sensor->abs_pressure, hil_sensor->diff_pressure, hil_sensor->pressure_alt, hil_sensor->temperature, hil_sensor->fields_updated); +} + +/** + * @brief Encode a hil_sensor struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param hil_sensor C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_sensor_t* hil_sensor) +{ + return mavlink_msg_hil_sensor_pack_chan(system_id, component_id, chan, msg, hil_sensor->time_usec, hil_sensor->xacc, hil_sensor->yacc, hil_sensor->zacc, hil_sensor->xgyro, hil_sensor->ygyro, hil_sensor->zgyro, hil_sensor->xmag, hil_sensor->ymag, hil_sensor->zmag, hil_sensor->abs_pressure, hil_sensor->diff_pressure, hil_sensor->pressure_alt, hil_sensor->temperature, hil_sensor->fields_updated); +} + +/** + * @brief Send a hil_sensor message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param xacc X acceleration (m/s^2) + * @param yacc Y acceleration (m/s^2) + * @param zacc Z acceleration (m/s^2) + * @param xgyro Angular speed around X axis in body frame (rad / sec) + * @param ygyro Angular speed around Y axis in body frame (rad / sec) + * @param zgyro Angular speed around Z axis in body frame (rad / sec) + * @param xmag X Magnetic field (Gauss) + * @param ymag Y Magnetic field (Gauss) + * @param zmag Z Magnetic field (Gauss) + * @param abs_pressure Absolute pressure in millibar + * @param diff_pressure Differential pressure (airspeed) in millibar + * @param pressure_alt Altitude calculated from pressure + * @param temperature Temperature in degrees celsius + * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_sensor_send(mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint32_t(buf, 60, fields_updated); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +#else + mavlink_hil_sensor_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + packet.abs_pressure = abs_pressure; + packet.diff_pressure = diff_pressure; + packet.pressure_alt = pressure_alt; + packet.temperature = temperature; + packet.fields_updated = fields_updated; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIL_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_hil_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, xmag); + _mav_put_float(buf, 36, ymag); + _mav_put_float(buf, 40, zmag); + _mav_put_float(buf, 44, abs_pressure); + _mav_put_float(buf, 48, diff_pressure); + _mav_put_float(buf, 52, pressure_alt); + _mav_put_float(buf, 56, temperature); + _mav_put_uint32_t(buf, 60, fields_updated); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +#else + mavlink_hil_sensor_t *packet = (mavlink_hil_sensor_t *)msgbuf; + packet->time_usec = time_usec; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->xmag = xmag; + packet->ymag = ymag; + packet->zmag = zmag; + packet->abs_pressure = abs_pressure; + packet->diff_pressure = diff_pressure; + packet->pressure_alt = pressure_alt; + packet->temperature = temperature; + packet->fields_updated = fields_updated; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIL_SENSOR UNPACKING + + +/** + * @brief Get field time_usec from hil_sensor message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_hil_sensor_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field xacc from hil_sensor message + * + * @return X acceleration (m/s^2) + */ +static inline float mavlink_msg_hil_sensor_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yacc from hil_sensor message + * + * @return Y acceleration (m/s^2) + */ +static inline float mavlink_msg_hil_sensor_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field zacc from hil_sensor message + * + * @return Z acceleration (m/s^2) + */ +static inline float mavlink_msg_hil_sensor_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field xgyro from hil_sensor message + * + * @return Angular speed around X axis in body frame (rad / sec) + */ +static inline float mavlink_msg_hil_sensor_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field ygyro from hil_sensor message + * + * @return Angular speed around Y axis in body frame (rad / sec) + */ +static inline float mavlink_msg_hil_sensor_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field zgyro from hil_sensor message + * + * @return Angular speed around Z axis in body frame (rad / sec) + */ +static inline float mavlink_msg_hil_sensor_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field xmag from hil_sensor message + * + * @return X Magnetic field (Gauss) + */ +static inline float mavlink_msg_hil_sensor_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field ymag from hil_sensor message + * + * @return Y Magnetic field (Gauss) + */ +static inline float mavlink_msg_hil_sensor_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field zmag from hil_sensor message + * + * @return Z Magnetic field (Gauss) + */ +static inline float mavlink_msg_hil_sensor_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field abs_pressure from hil_sensor message + * + * @return Absolute pressure in millibar + */ +static inline float mavlink_msg_hil_sensor_get_abs_pressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field diff_pressure from hil_sensor message + * + * @return Differential pressure (airspeed) in millibar + */ +static inline float mavlink_msg_hil_sensor_get_diff_pressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 48); +} + +/** + * @brief Get field pressure_alt from hil_sensor message + * + * @return Altitude calculated from pressure + */ +static inline float mavlink_msg_hil_sensor_get_pressure_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 52); +} + +/** + * @brief Get field temperature from hil_sensor message + * + * @return Temperature in degrees celsius + */ +static inline float mavlink_msg_hil_sensor_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 56); +} + +/** + * @brief Get field fields_updated from hil_sensor message + * + * @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + */ +static inline uint32_t mavlink_msg_hil_sensor_get_fields_updated(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 60); +} + +/** + * @brief Decode a hil_sensor message into a struct + * + * @param msg The message to decode + * @param hil_sensor C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_sensor_decode(const mavlink_message_t* msg, mavlink_hil_sensor_t* hil_sensor) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_sensor->time_usec = mavlink_msg_hil_sensor_get_time_usec(msg); + hil_sensor->xacc = mavlink_msg_hil_sensor_get_xacc(msg); + hil_sensor->yacc = mavlink_msg_hil_sensor_get_yacc(msg); + hil_sensor->zacc = mavlink_msg_hil_sensor_get_zacc(msg); + hil_sensor->xgyro = mavlink_msg_hil_sensor_get_xgyro(msg); + hil_sensor->ygyro = mavlink_msg_hil_sensor_get_ygyro(msg); + hil_sensor->zgyro = mavlink_msg_hil_sensor_get_zgyro(msg); + hil_sensor->xmag = mavlink_msg_hil_sensor_get_xmag(msg); + hil_sensor->ymag = mavlink_msg_hil_sensor_get_ymag(msg); + hil_sensor->zmag = mavlink_msg_hil_sensor_get_zmag(msg); + hil_sensor->abs_pressure = mavlink_msg_hil_sensor_get_abs_pressure(msg); + hil_sensor->diff_pressure = mavlink_msg_hil_sensor_get_diff_pressure(msg); + hil_sensor->pressure_alt = mavlink_msg_hil_sensor_get_pressure_alt(msg); + hil_sensor->temperature = mavlink_msg_hil_sensor_get_temperature(msg); + hil_sensor->fields_updated = mavlink_msg_hil_sensor_get_fields_updated(msg); +#else + memcpy(hil_sensor, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_SENSOR_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_state.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_state.h new file mode 100644 index 0000000..e58141e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_state.h @@ -0,0 +1,569 @@ +// MESSAGE HIL_STATE PACKING + +#define MAVLINK_MSG_ID_HIL_STATE 90 + +typedef struct __mavlink_hil_state_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + float roll; /*< Roll angle (rad)*/ + float pitch; /*< Pitch angle (rad)*/ + float yaw; /*< Yaw angle (rad)*/ + float rollspeed; /*< Body frame roll / phi angular speed (rad/s)*/ + float pitchspeed; /*< Body frame pitch / theta angular speed (rad/s)*/ + float yawspeed; /*< Body frame yaw / psi angular speed (rad/s)*/ + int32_t lat; /*< Latitude, expressed as * 1E7*/ + int32_t lon; /*< Longitude, expressed as * 1E7*/ + int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters)*/ + int16_t vx; /*< Ground X Speed (Latitude), expressed as m/s * 100*/ + int16_t vy; /*< Ground Y Speed (Longitude), expressed as m/s * 100*/ + int16_t vz; /*< Ground Z Speed (Altitude), expressed as m/s * 100*/ + int16_t xacc; /*< X acceleration (mg)*/ + int16_t yacc; /*< Y acceleration (mg)*/ + int16_t zacc; /*< Z acceleration (mg)*/ +} mavlink_hil_state_t; + +#define MAVLINK_MSG_ID_HIL_STATE_LEN 56 +#define MAVLINK_MSG_ID_90_LEN 56 + +#define MAVLINK_MSG_ID_HIL_STATE_CRC 183 +#define MAVLINK_MSG_ID_90_CRC 183 + + + +#define MAVLINK_MESSAGE_INFO_HIL_STATE { \ + "HIL_STATE", \ + 16, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \ + { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \ + } \ +} + + +/** + * @brief Pack a hil_state message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Body frame roll / phi angular speed (rad/s) + * @param pitchspeed Body frame pitch / theta angular speed (rad/s) + * @param yawspeed Body frame yaw / psi angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_STATE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_int32_t(buf, 32, lat); + _mav_put_int32_t(buf, 36, lon); + _mav_put_int32_t(buf, 40, alt); + _mav_put_int16_t(buf, 44, vx); + _mav_put_int16_t(buf, 46, vy); + _mav_put_int16_t(buf, 48, vz); + _mav_put_int16_t(buf, 50, xacc); + _mav_put_int16_t(buf, 52, yacc); + _mav_put_int16_t(buf, 54, zacc); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN); +#else + mavlink_hil_state_t packet; + packet.time_usec = time_usec; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif +} + +/** + * @brief Pack a hil_state message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Body frame roll / phi angular speed (rad/s) + * @param pitchspeed Body frame pitch / theta angular speed (rad/s) + * @param yawspeed Body frame yaw / psi angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,int16_t xacc,int16_t yacc,int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_STATE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_int32_t(buf, 32, lat); + _mav_put_int32_t(buf, 36, lon); + _mav_put_int32_t(buf, 40, alt); + _mav_put_int16_t(buf, 44, vx); + _mav_put_int16_t(buf, 46, vy); + _mav_put_int16_t(buf, 48, vz); + _mav_put_int16_t(buf, 50, xacc); + _mav_put_int16_t(buf, 52, yacc); + _mav_put_int16_t(buf, 54, zacc); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN); +#else + mavlink_hil_state_t packet; + packet.time_usec = time_usec; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif +} + +/** + * @brief Encode a hil_state struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state) +{ + return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); +} + +/** + * @brief Encode a hil_state struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param hil_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state) +{ + return mavlink_msg_hil_state_pack_chan(system_id, component_id, chan, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); +} + +/** + * @brief Send a hil_state message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Body frame roll / phi angular speed (rad/s) + * @param pitchspeed Body frame pitch / theta angular speed (rad/s) + * @param yawspeed Body frame yaw / psi angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_STATE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_int32_t(buf, 32, lat); + _mav_put_int32_t(buf, 36, lon); + _mav_put_int32_t(buf, 40, alt); + _mav_put_int16_t(buf, 44, vx); + _mav_put_int16_t(buf, 46, vy); + _mav_put_int16_t(buf, 48, vz); + _mav_put_int16_t(buf, 50, xacc); + _mav_put_int16_t(buf, 52, yacc); + _mav_put_int16_t(buf, 54, zacc); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif +#else + mavlink_hil_state_t packet; + packet.time_usec = time_usec; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIL_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_hil_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_int32_t(buf, 32, lat); + _mav_put_int32_t(buf, 36, lon); + _mav_put_int32_t(buf, 40, alt); + _mav_put_int16_t(buf, 44, vx); + _mav_put_int16_t(buf, 46, vy); + _mav_put_int16_t(buf, 48, vz); + _mav_put_int16_t(buf, 50, xacc); + _mav_put_int16_t(buf, 52, yacc); + _mav_put_int16_t(buf, 54, zacc); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif +#else + mavlink_hil_state_t *packet = (mavlink_hil_state_t *)msgbuf; + packet->time_usec = time_usec; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + packet->rollspeed = rollspeed; + packet->pitchspeed = pitchspeed; + packet->yawspeed = yawspeed; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIL_STATE UNPACKING + + +/** + * @brief Get field time_usec from hil_state message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field roll from hil_state message + * + * @return Roll angle (rad) + */ +static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field pitch from hil_state message + * + * @return Pitch angle (rad) + */ +static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field yaw from hil_state message + * + * @return Yaw angle (rad) + */ +static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field rollspeed from hil_state message + * + * @return Body frame roll / phi angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitchspeed from hil_state message + * + * @return Body frame pitch / theta angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yawspeed from hil_state message + * + * @return Body frame yaw / psi angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field lat from hil_state message + * + * @return Latitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 32); +} + +/** + * @brief Get field lon from hil_state message + * + * @return Longitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 36); +} + +/** + * @brief Get field alt from hil_state message + * + * @return Altitude in meters, expressed as * 1000 (millimeters) + */ +static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 40); +} + +/** + * @brief Get field vx from hil_state message + * + * @return Ground X Speed (Latitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 44); +} + +/** + * @brief Get field vy from hil_state message + * + * @return Ground Y Speed (Longitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 46); +} + +/** + * @brief Get field vz from hil_state message + * + * @return Ground Z Speed (Altitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 48); +} + +/** + * @brief Get field xacc from hil_state message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 50); +} + +/** + * @brief Get field yacc from hil_state message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 52); +} + +/** + * @brief Get field zacc from hil_state message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 54); +} + +/** + * @brief Decode a hil_state message into a struct + * + * @param msg The message to decode + * @param hil_state C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_state->time_usec = mavlink_msg_hil_state_get_time_usec(msg); + hil_state->roll = mavlink_msg_hil_state_get_roll(msg); + hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg); + hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg); + hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg); + hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg); + hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg); + hil_state->lat = mavlink_msg_hil_state_get_lat(msg); + hil_state->lon = mavlink_msg_hil_state_get_lon(msg); + hil_state->alt = mavlink_msg_hil_state_get_alt(msg); + hil_state->vx = mavlink_msg_hil_state_get_vx(msg); + hil_state->vy = mavlink_msg_hil_state_get_vy(msg); + hil_state->vz = mavlink_msg_hil_state_get_vz(msg); + hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg); + hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg); + hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg); +#else + memcpy(hil_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_STATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h new file mode 100644 index 0000000..9663813 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h @@ -0,0 +1,561 @@ +// MESSAGE HIL_STATE_QUATERNION PACKING + +#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION 115 + +typedef struct __mavlink_hil_state_quaternion_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + float attitude_quaternion[4]; /*< Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)*/ + float rollspeed; /*< Body frame roll / phi angular speed (rad/s)*/ + float pitchspeed; /*< Body frame pitch / theta angular speed (rad/s)*/ + float yawspeed; /*< Body frame yaw / psi angular speed (rad/s)*/ + int32_t lat; /*< Latitude, expressed as * 1E7*/ + int32_t lon; /*< Longitude, expressed as * 1E7*/ + int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters)*/ + int16_t vx; /*< Ground X Speed (Latitude), expressed as m/s * 100*/ + int16_t vy; /*< Ground Y Speed (Longitude), expressed as m/s * 100*/ + int16_t vz; /*< Ground Z Speed (Altitude), expressed as m/s * 100*/ + uint16_t ind_airspeed; /*< Indicated airspeed, expressed as m/s * 100*/ + uint16_t true_airspeed; /*< True airspeed, expressed as m/s * 100*/ + int16_t xacc; /*< X acceleration (mg)*/ + int16_t yacc; /*< Y acceleration (mg)*/ + int16_t zacc; /*< Z acceleration (mg)*/ +} mavlink_hil_state_quaternion_t; + +#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN 64 +#define MAVLINK_MSG_ID_115_LEN 64 + +#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC 4 +#define MAVLINK_MSG_ID_115_CRC 4 + +#define MAVLINK_MSG_HIL_STATE_QUATERNION_FIELD_ATTITUDE_QUATERNION_LEN 4 + +#define MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION { \ + "HIL_STATE_QUATERNION", \ + 16, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_quaternion_t, time_usec) }, \ + { "attitude_quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_hil_state_quaternion_t, attitude_quaternion) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_quaternion_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_quaternion_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_state_quaternion_t, yawspeed) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_quaternion_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_quaternion_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_hil_state_quaternion_t, alt) }, \ + { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_quaternion_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_quaternion_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_quaternion_t, vz) }, \ + { "ind_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 54, offsetof(mavlink_hil_state_quaternion_t, ind_airspeed) }, \ + { "true_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_hil_state_quaternion_t, true_airspeed) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_hil_state_quaternion_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_hil_state_quaternion_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 62, offsetof(mavlink_hil_state_quaternion_t, zacc) }, \ + } \ +} + + +/** + * @brief Pack a hil_state_quaternion message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + * @param rollspeed Body frame roll / phi angular speed (rad/s) + * @param pitchspeed Body frame pitch / theta angular speed (rad/s) + * @param yawspeed Body frame yaw / psi angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param ind_airspeed Indicated airspeed, expressed as m/s * 100 + * @param true_airspeed True airspeed, expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_state_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, rollspeed); + _mav_put_float(buf, 28, pitchspeed); + _mav_put_float(buf, 32, yawspeed); + _mav_put_int32_t(buf, 36, lat); + _mav_put_int32_t(buf, 40, lon); + _mav_put_int32_t(buf, 44, alt); + _mav_put_int16_t(buf, 48, vx); + _mav_put_int16_t(buf, 50, vy); + _mav_put_int16_t(buf, 52, vz); + _mav_put_uint16_t(buf, 54, ind_airspeed); + _mav_put_uint16_t(buf, 56, true_airspeed); + _mav_put_int16_t(buf, 58, xacc); + _mav_put_int16_t(buf, 60, yacc); + _mav_put_int16_t(buf, 62, zacc); + _mav_put_float_array(buf, 8, attitude_quaternion, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#else + mavlink_hil_state_quaternion_t packet; + packet.time_usec = time_usec; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ind_airspeed = ind_airspeed; + packet.true_airspeed = true_airspeed; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif +} + +/** + * @brief Pack a hil_state_quaternion message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + * @param rollspeed Body frame roll / phi angular speed (rad/s) + * @param pitchspeed Body frame pitch / theta angular speed (rad/s) + * @param yawspeed Body frame yaw / psi angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param ind_airspeed Indicated airspeed, expressed as m/s * 100 + * @param true_airspeed True airspeed, expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_state_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,const float *attitude_quaternion,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,uint16_t ind_airspeed,uint16_t true_airspeed,int16_t xacc,int16_t yacc,int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, rollspeed); + _mav_put_float(buf, 28, pitchspeed); + _mav_put_float(buf, 32, yawspeed); + _mav_put_int32_t(buf, 36, lat); + _mav_put_int32_t(buf, 40, lon); + _mav_put_int32_t(buf, 44, alt); + _mav_put_int16_t(buf, 48, vx); + _mav_put_int16_t(buf, 50, vy); + _mav_put_int16_t(buf, 52, vz); + _mav_put_uint16_t(buf, 54, ind_airspeed); + _mav_put_uint16_t(buf, 56, true_airspeed); + _mav_put_int16_t(buf, 58, xacc); + _mav_put_int16_t(buf, 60, yacc); + _mav_put_int16_t(buf, 62, zacc); + _mav_put_float_array(buf, 8, attitude_quaternion, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#else + mavlink_hil_state_quaternion_t packet; + packet.time_usec = time_usec; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ind_airspeed = ind_airspeed; + packet.true_airspeed = true_airspeed; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif +} + +/** + * @brief Encode a hil_state_quaternion struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_state_quaternion C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_state_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion) +{ + return mavlink_msg_hil_state_quaternion_pack(system_id, component_id, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc); +} + +/** + * @brief Encode a hil_state_quaternion struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param hil_state_quaternion C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_state_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion) +{ + return mavlink_msg_hil_state_quaternion_pack_chan(system_id, component_id, chan, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc); +} + +/** + * @brief Send a hil_state_quaternion message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + * @param rollspeed Body frame roll / phi angular speed (rad/s) + * @param pitchspeed Body frame pitch / theta angular speed (rad/s) + * @param yawspeed Body frame yaw / psi angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param ind_airspeed Indicated airspeed, expressed as m/s * 100 + * @param true_airspeed True airspeed, expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_state_quaternion_send(mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, rollspeed); + _mav_put_float(buf, 28, pitchspeed); + _mav_put_float(buf, 32, yawspeed); + _mav_put_int32_t(buf, 36, lat); + _mav_put_int32_t(buf, 40, lon); + _mav_put_int32_t(buf, 44, alt); + _mav_put_int16_t(buf, 48, vx); + _mav_put_int16_t(buf, 50, vy); + _mav_put_int16_t(buf, 52, vz); + _mav_put_uint16_t(buf, 54, ind_airspeed); + _mav_put_uint16_t(buf, 56, true_airspeed); + _mav_put_int16_t(buf, 58, xacc); + _mav_put_int16_t(buf, 60, yacc); + _mav_put_int16_t(buf, 62, zacc); + _mav_put_float_array(buf, 8, attitude_quaternion, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif +#else + mavlink_hil_state_quaternion_t packet; + packet.time_usec = time_usec; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ind_airspeed = ind_airspeed; + packet.true_airspeed = true_airspeed; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_hil_state_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 24, rollspeed); + _mav_put_float(buf, 28, pitchspeed); + _mav_put_float(buf, 32, yawspeed); + _mav_put_int32_t(buf, 36, lat); + _mav_put_int32_t(buf, 40, lon); + _mav_put_int32_t(buf, 44, alt); + _mav_put_int16_t(buf, 48, vx); + _mav_put_int16_t(buf, 50, vy); + _mav_put_int16_t(buf, 52, vz); + _mav_put_uint16_t(buf, 54, ind_airspeed); + _mav_put_uint16_t(buf, 56, true_airspeed); + _mav_put_int16_t(buf, 58, xacc); + _mav_put_int16_t(buf, 60, yacc); + _mav_put_int16_t(buf, 62, zacc); + _mav_put_float_array(buf, 8, attitude_quaternion, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif +#else + mavlink_hil_state_quaternion_t *packet = (mavlink_hil_state_quaternion_t *)msgbuf; + packet->time_usec = time_usec; + packet->rollspeed = rollspeed; + packet->pitchspeed = pitchspeed; + packet->yawspeed = yawspeed; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->ind_airspeed = ind_airspeed; + packet->true_airspeed = true_airspeed; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + mav_array_memcpy(packet->attitude_quaternion, attitude_quaternion, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HIL_STATE_QUATERNION UNPACKING + + +/** + * @brief Get field time_usec from hil_state_quaternion message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_state_quaternion_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field attitude_quaternion from hil_state_quaternion message + * + * @return Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + */ +static inline uint16_t mavlink_msg_hil_state_quaternion_get_attitude_quaternion(const mavlink_message_t* msg, float *attitude_quaternion) +{ + return _MAV_RETURN_float_array(msg, attitude_quaternion, 4, 8); +} + +/** + * @brief Get field rollspeed from hil_state_quaternion message + * + * @return Body frame roll / phi angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_quaternion_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field pitchspeed from hil_state_quaternion message + * + * @return Body frame pitch / theta angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_quaternion_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field yawspeed from hil_state_quaternion message + * + * @return Body frame yaw / psi angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_quaternion_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field lat from hil_state_quaternion message + * + * @return Latitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_hil_state_quaternion_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 36); +} + +/** + * @brief Get field lon from hil_state_quaternion message + * + * @return Longitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_hil_state_quaternion_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 40); +} + +/** + * @brief Get field alt from hil_state_quaternion message + * + * @return Altitude in meters, expressed as * 1000 (millimeters) + */ +static inline int32_t mavlink_msg_hil_state_quaternion_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 44); +} + +/** + * @brief Get field vx from hil_state_quaternion message + * + * @return Ground X Speed (Latitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_quaternion_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 48); +} + +/** + * @brief Get field vy from hil_state_quaternion message + * + * @return Ground Y Speed (Longitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_quaternion_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 50); +} + +/** + * @brief Get field vz from hil_state_quaternion message + * + * @return Ground Z Speed (Altitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_quaternion_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 52); +} + +/** + * @brief Get field ind_airspeed from hil_state_quaternion message + * + * @return Indicated airspeed, expressed as m/s * 100 + */ +static inline uint16_t mavlink_msg_hil_state_quaternion_get_ind_airspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 54); +} + +/** + * @brief Get field true_airspeed from hil_state_quaternion message + * + * @return True airspeed, expressed as m/s * 100 + */ +static inline uint16_t mavlink_msg_hil_state_quaternion_get_true_airspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 56); +} + +/** + * @brief Get field xacc from hil_state_quaternion message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_quaternion_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 58); +} + +/** + * @brief Get field yacc from hil_state_quaternion message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_quaternion_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 60); +} + +/** + * @brief Get field zacc from hil_state_quaternion message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_quaternion_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 62); +} + +/** + * @brief Decode a hil_state_quaternion message into a struct + * + * @param msg The message to decode + * @param hil_state_quaternion C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_state_quaternion_decode(const mavlink_message_t* msg, mavlink_hil_state_quaternion_t* hil_state_quaternion) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_state_quaternion->time_usec = mavlink_msg_hil_state_quaternion_get_time_usec(msg); + mavlink_msg_hil_state_quaternion_get_attitude_quaternion(msg, hil_state_quaternion->attitude_quaternion); + hil_state_quaternion->rollspeed = mavlink_msg_hil_state_quaternion_get_rollspeed(msg); + hil_state_quaternion->pitchspeed = mavlink_msg_hil_state_quaternion_get_pitchspeed(msg); + hil_state_quaternion->yawspeed = mavlink_msg_hil_state_quaternion_get_yawspeed(msg); + hil_state_quaternion->lat = mavlink_msg_hil_state_quaternion_get_lat(msg); + hil_state_quaternion->lon = mavlink_msg_hil_state_quaternion_get_lon(msg); + hil_state_quaternion->alt = mavlink_msg_hil_state_quaternion_get_alt(msg); + hil_state_quaternion->vx = mavlink_msg_hil_state_quaternion_get_vx(msg); + hil_state_quaternion->vy = mavlink_msg_hil_state_quaternion_get_vy(msg); + hil_state_quaternion->vz = mavlink_msg_hil_state_quaternion_get_vz(msg); + hil_state_quaternion->ind_airspeed = mavlink_msg_hil_state_quaternion_get_ind_airspeed(msg); + hil_state_quaternion->true_airspeed = mavlink_msg_hil_state_quaternion_get_true_airspeed(msg); + hil_state_quaternion->xacc = mavlink_msg_hil_state_quaternion_get_xacc(msg); + hil_state_quaternion->yacc = mavlink_msg_hil_state_quaternion_get_yacc(msg); + hil_state_quaternion->zacc = mavlink_msg_hil_state_quaternion_get_zacc(msg); +#else + memcpy(hil_state_quaternion, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_home_position.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_home_position.h new file mode 100644 index 0000000..c7181b7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_home_position.h @@ -0,0 +1,417 @@ +// MESSAGE HOME_POSITION PACKING + +#define MAVLINK_MSG_ID_HOME_POSITION 242 + +typedef struct __mavlink_home_position_t +{ + int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/ + int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ + float x; /*< Local X position of this position in the local coordinate frame*/ + float y; /*< Local Y position of this position in the local coordinate frame*/ + float z; /*< Local Z position of this position in the local coordinate frame*/ + float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/ + float approach_x; /*< Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ + float approach_y; /*< Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ + float approach_z; /*< Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ +} mavlink_home_position_t; + +#define MAVLINK_MSG_ID_HOME_POSITION_LEN 52 +#define MAVLINK_MSG_ID_242_LEN 52 + +#define MAVLINK_MSG_ID_HOME_POSITION_CRC 104 +#define MAVLINK_MSG_ID_242_CRC 104 + +#define MAVLINK_MSG_HOME_POSITION_FIELD_Q_LEN 4 + +#define MAVLINK_MESSAGE_INFO_HOME_POSITION { \ + "HOME_POSITION", \ + 10, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_home_position_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_home_position_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_home_position_t, z) }, \ + { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_home_position_t, q) }, \ + { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \ + { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \ + { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \ + } \ +} + + +/** + * @brief Pack a home_position message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param x Local X position of this position in the local coordinate frame + * @param y Local Y position of this position in the local coordinate frame + * @param z Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_float_array(buf, 24, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#else + mavlink_home_position_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.x = x; + packet.y = y; + packet.z = z; + packet.approach_x = approach_x; + packet.approach_y = approach_y; + packet.approach_z = approach_z; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HOME_POSITION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif +} + +/** + * @brief Pack a home_position message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param x Local X position of this position in the local coordinate frame + * @param y Local Y position of this position in the local coordinate frame + * @param z Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int32_t latitude,int32_t longitude,int32_t altitude,float x,float y,float z,const float *q,float approach_x,float approach_y,float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_float_array(buf, 24, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#else + mavlink_home_position_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.x = x; + packet.y = y; + packet.z = z; + packet.approach_x = approach_x; + packet.approach_y = approach_y; + packet.approach_z = approach_z; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_HOME_POSITION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif +} + +/** + * @brief Encode a home_position struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param home_position C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_home_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_home_position_t* home_position) +{ + return mavlink_msg_home_position_pack(system_id, component_id, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z); +} + +/** + * @brief Encode a home_position struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param home_position C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_home_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_home_position_t* home_position) +{ + return mavlink_msg_home_position_pack_chan(system_id, component_id, chan, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z); +} + +/** + * @brief Send a home_position message + * @param chan MAVLink channel to send the message + * + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param x Local X position of this position in the local coordinate frame + * @param y Local Y position of this position in the local coordinate frame + * @param z Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_home_position_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_float_array(buf, 24, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif +#else + mavlink_home_position_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.x = x; + packet.y = y; + packet.z = z; + packet.approach_x = approach_x; + packet.approach_y = approach_y; + packet.approach_z = approach_z; + mav_array_memcpy(packet.q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_home_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_float_array(buf, 24, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif +#else + mavlink_home_position_t *packet = (mavlink_home_position_t *)msgbuf; + packet->latitude = latitude; + packet->longitude = longitude; + packet->altitude = altitude; + packet->x = x; + packet->y = y; + packet->z = z; + packet->approach_x = approach_x; + packet->approach_y = approach_y; + packet->approach_z = approach_z; + mav_array_memcpy(packet->q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE HOME_POSITION UNPACKING + + +/** + * @brief Get field latitude from home_position message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_home_position_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from home_position message + * + * @return Longitude (WGS84, in degrees * 1E7 + */ +static inline int32_t mavlink_msg_home_position_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from home_position message + * + * @return Altitude (AMSL), in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_home_position_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field x from home_position message + * + * @return Local X position of this position in the local coordinate frame + */ +static inline float mavlink_msg_home_position_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field y from home_position message + * + * @return Local Y position of this position in the local coordinate frame + */ +static inline float mavlink_msg_home_position_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field z from home_position message + * + * @return Local Z position of this position in the local coordinate frame + */ +static inline float mavlink_msg_home_position_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field q from home_position message + * + * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + */ +static inline uint16_t mavlink_msg_home_position_get_q(const mavlink_message_t* msg, float *q) +{ + return _MAV_RETURN_float_array(msg, q, 4, 24); +} + +/** + * @brief Get field approach_x from home_position message + * + * @return Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +static inline float mavlink_msg_home_position_get_approach_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field approach_y from home_position message + * + * @return Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +static inline float mavlink_msg_home_position_get_approach_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field approach_z from home_position message + * + * @return Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +static inline float mavlink_msg_home_position_get_approach_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 48); +} + +/** + * @brief Decode a home_position message into a struct + * + * @param msg The message to decode + * @param home_position C-struct to decode the message contents into + */ +static inline void mavlink_msg_home_position_decode(const mavlink_message_t* msg, mavlink_home_position_t* home_position) +{ +#if MAVLINK_NEED_BYTE_SWAP + home_position->latitude = mavlink_msg_home_position_get_latitude(msg); + home_position->longitude = mavlink_msg_home_position_get_longitude(msg); + home_position->altitude = mavlink_msg_home_position_get_altitude(msg); + home_position->x = mavlink_msg_home_position_get_x(msg); + home_position->y = mavlink_msg_home_position_get_y(msg); + home_position->z = mavlink_msg_home_position_get_z(msg); + mavlink_msg_home_position_get_q(msg, home_position->q); + home_position->approach_x = mavlink_msg_home_position_get_approach_x(msg); + home_position->approach_y = mavlink_msg_home_position_get_approach_y(msg); + home_position->approach_z = mavlink_msg_home_position_get_approach_z(msg); +#else + memcpy(home_position, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HOME_POSITION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_landing_target.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_landing_target.h new file mode 100644 index 0000000..14b03bf --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_landing_target.h @@ -0,0 +1,377 @@ +// MESSAGE LANDING_TARGET PACKING + +#define MAVLINK_MSG_ID_LANDING_TARGET 149 + +typedef struct __mavlink_landing_target_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float angle_x; /*< X-axis angular offset (in radians) of the target from the center of the image*/ + float angle_y; /*< Y-axis angular offset (in radians) of the target from the center of the image*/ + float distance; /*< Distance to the target from the vehicle in meters*/ + float size_x; /*< Size in radians of target along x-axis*/ + float size_y; /*< Size in radians of target along y-axis*/ + uint8_t target_num; /*< The ID of the target if multiple targets are present*/ + uint8_t frame; /*< MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc.*/ +} mavlink_landing_target_t; + +#define MAVLINK_MSG_ID_LANDING_TARGET_LEN 30 +#define MAVLINK_MSG_ID_149_LEN 30 + +#define MAVLINK_MSG_ID_LANDING_TARGET_CRC 200 +#define MAVLINK_MSG_ID_149_CRC 200 + + + +#define MAVLINK_MESSAGE_INFO_LANDING_TARGET { \ + "LANDING_TARGET", \ + 8, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \ + { "angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_landing_target_t, angle_x) }, \ + { "angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_landing_target_t, angle_y) }, \ + { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \ + { "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \ + { "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \ + { "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \ + } \ +} + + +/** + * @brief Pack a landing_target message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param target_num The ID of the target if multiple targets are present + * @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. + * @param angle_x X-axis angular offset (in radians) of the target from the center of the image + * @param angle_y Y-axis angular offset (in radians) of the target from the center of the image + * @param distance Distance to the target from the vehicle in meters + * @param size_x Size in radians of target along x-axis + * @param size_y Size in radians of target along y-axis + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, angle_x); + _mav_put_float(buf, 12, angle_y); + _mav_put_float(buf, 16, distance); + _mav_put_float(buf, 20, size_x); + _mav_put_float(buf, 24, size_y); + _mav_put_uint8_t(buf, 28, target_num); + _mav_put_uint8_t(buf, 29, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#else + mavlink_landing_target_t packet; + packet.time_usec = time_usec; + packet.angle_x = angle_x; + packet.angle_y = angle_y; + packet.distance = distance; + packet.size_x = size_x; + packet.size_y = size_y; + packet.target_num = target_num; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LANDING_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif +} + +/** + * @brief Pack a landing_target message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param target_num The ID of the target if multiple targets are present + * @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. + * @param angle_x X-axis angular offset (in radians) of the target from the center of the image + * @param angle_y Y-axis angular offset (in radians) of the target from the center of the image + * @param distance Distance to the target from the vehicle in meters + * @param size_x Size in radians of target along x-axis + * @param size_y Size in radians of target along y-axis + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t target_num,uint8_t frame,float angle_x,float angle_y,float distance,float size_x,float size_y) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, angle_x); + _mav_put_float(buf, 12, angle_y); + _mav_put_float(buf, 16, distance); + _mav_put_float(buf, 20, size_x); + _mav_put_float(buf, 24, size_y); + _mav_put_uint8_t(buf, 28, target_num); + _mav_put_uint8_t(buf, 29, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#else + mavlink_landing_target_t packet; + packet.time_usec = time_usec; + packet.angle_x = angle_x; + packet.angle_y = angle_y; + packet.distance = distance; + packet.size_x = size_x; + packet.size_y = size_y; + packet.target_num = target_num; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LANDING_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif +} + +/** + * @brief Encode a landing_target struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param landing_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_landing_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_landing_target_t* landing_target) +{ + return mavlink_msg_landing_target_pack(system_id, component_id, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y); +} + +/** + * @brief Encode a landing_target struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param landing_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_landing_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_landing_target_t* landing_target) +{ + return mavlink_msg_landing_target_pack_chan(system_id, component_id, chan, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y); +} + +/** + * @brief Send a landing_target message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param target_num The ID of the target if multiple targets are present + * @param frame MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. + * @param angle_x X-axis angular offset (in radians) of the target from the center of the image + * @param angle_y Y-axis angular offset (in radians) of the target from the center of the image + * @param distance Distance to the target from the vehicle in meters + * @param size_x Size in radians of target along x-axis + * @param size_y Size in radians of target along y-axis + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, angle_x); + _mav_put_float(buf, 12, angle_y); + _mav_put_float(buf, 16, distance); + _mav_put_float(buf, 20, size_x); + _mav_put_float(buf, 24, size_y); + _mav_put_uint8_t(buf, 28, target_num); + _mav_put_uint8_t(buf, 29, frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif +#else + mavlink_landing_target_t packet; + packet.time_usec = time_usec; + packet.angle_x = angle_x; + packet.angle_y = angle_y; + packet.distance = distance; + packet.size_x = size_x; + packet.size_y = size_y; + packet.target_num = target_num; + packet.frame = frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)&packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)&packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LANDING_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_landing_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, angle_x); + _mav_put_float(buf, 12, angle_y); + _mav_put_float(buf, 16, distance); + _mav_put_float(buf, 20, size_x); + _mav_put_float(buf, 24, size_y); + _mav_put_uint8_t(buf, 28, target_num); + _mav_put_uint8_t(buf, 29, frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif +#else + mavlink_landing_target_t *packet = (mavlink_landing_target_t *)msgbuf; + packet->time_usec = time_usec; + packet->angle_x = angle_x; + packet->angle_y = angle_y; + packet->distance = distance; + packet->size_x = size_x; + packet->size_y = size_y; + packet->target_num = target_num; + packet->frame = frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LANDING_TARGET UNPACKING + + +/** + * @brief Get field time_usec from landing_target message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_landing_target_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field target_num from landing_target message + * + * @return The ID of the target if multiple targets are present + */ +static inline uint8_t mavlink_msg_landing_target_get_target_num(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 28); +} + +/** + * @brief Get field frame from landing_target message + * + * @return MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. + */ +static inline uint8_t mavlink_msg_landing_target_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 29); +} + +/** + * @brief Get field angle_x from landing_target message + * + * @return X-axis angular offset (in radians) of the target from the center of the image + */ +static inline float mavlink_msg_landing_target_get_angle_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field angle_y from landing_target message + * + * @return Y-axis angular offset (in radians) of the target from the center of the image + */ +static inline float mavlink_msg_landing_target_get_angle_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field distance from landing_target message + * + * @return Distance to the target from the vehicle in meters + */ +static inline float mavlink_msg_landing_target_get_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field size_x from landing_target message + * + * @return Size in radians of target along x-axis + */ +static inline float mavlink_msg_landing_target_get_size_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field size_y from landing_target message + * + * @return Size in radians of target along y-axis + */ +static inline float mavlink_msg_landing_target_get_size_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a landing_target message into a struct + * + * @param msg The message to decode + * @param landing_target C-struct to decode the message contents into + */ +static inline void mavlink_msg_landing_target_decode(const mavlink_message_t* msg, mavlink_landing_target_t* landing_target) +{ +#if MAVLINK_NEED_BYTE_SWAP + landing_target->time_usec = mavlink_msg_landing_target_get_time_usec(msg); + landing_target->angle_x = mavlink_msg_landing_target_get_angle_x(msg); + landing_target->angle_y = mavlink_msg_landing_target_get_angle_y(msg); + landing_target->distance = mavlink_msg_landing_target_get_distance(msg); + landing_target->size_x = mavlink_msg_landing_target_get_size_x(msg); + landing_target->size_y = mavlink_msg_landing_target_get_size_y(msg); + landing_target->target_num = mavlink_msg_landing_target_get_target_num(msg); + landing_target->frame = mavlink_msg_landing_target_get_frame(msg); +#else + memcpy(landing_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LANDING_TARGET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_local_position_ned.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_local_position_ned.h new file mode 100644 index 0000000..a15dbce --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_local_position_ned.h @@ -0,0 +1,353 @@ +// MESSAGE LOCAL_POSITION_NED PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED 32 + +typedef struct __mavlink_local_position_ned_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float x; /*< X Position*/ + float y; /*< Y Position*/ + float z; /*< Z Position*/ + float vx; /*< X Speed*/ + float vy; /*< Y Speed*/ + float vz; /*< Z Speed*/ +} mavlink_local_position_ned_t; + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28 +#define MAVLINK_MSG_ID_32_LEN 28 + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC 185 +#define MAVLINK_MSG_ID_32_CRC 185 + + + +#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \ + "LOCAL_POSITION_NED", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \ + } \ +} + + +/** + * @brief Pack a local_position_ned message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#else + mavlink_local_position_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif +} + +/** + * @brief Pack a local_position_ned message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float x,float y,float z,float vx,float vy,float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#else + mavlink_local_position_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif +} + +/** + * @brief Encode a local_position_ned struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param local_position_ned C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned) +{ + return mavlink_msg_local_position_ned_pack(system_id, component_id, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); +} + +/** + * @brief Encode a local_position_ned struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param local_position_ned C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned) +{ + return mavlink_msg_local_position_ned_pack_chan(system_id, component_id, chan, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); +} + +/** + * @brief Send a local_position_ned message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif +#else + mavlink_local_position_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_local_position_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif +#else + mavlink_local_position_ned_t *packet = (mavlink_local_position_ned_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->x = x; + packet->y = y; + packet->z = z; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOCAL_POSITION_NED UNPACKING + + +/** + * @brief Get field time_boot_ms from local_position_ned message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_local_position_ned_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field x from local_position_ned message + * + * @return X Position + */ +static inline float mavlink_msg_local_position_ned_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field y from local_position_ned message + * + * @return Y Position + */ +static inline float mavlink_msg_local_position_ned_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field z from local_position_ned message + * + * @return Z Position + */ +static inline float mavlink_msg_local_position_ned_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vx from local_position_ned message + * + * @return X Speed + */ +static inline float mavlink_msg_local_position_ned_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vy from local_position_ned message + * + * @return Y Speed + */ +static inline float mavlink_msg_local_position_ned_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vz from local_position_ned message + * + * @return Z Speed + */ +static inline float mavlink_msg_local_position_ned_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a local_position_ned message into a struct + * + * @param msg The message to decode + * @param local_position_ned C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_position_ned_decode(const mavlink_message_t* msg, mavlink_local_position_ned_t* local_position_ned) +{ +#if MAVLINK_NEED_BYTE_SWAP + local_position_ned->time_boot_ms = mavlink_msg_local_position_ned_get_time_boot_ms(msg); + local_position_ned->x = mavlink_msg_local_position_ned_get_x(msg); + local_position_ned->y = mavlink_msg_local_position_ned_get_y(msg); + local_position_ned->z = mavlink_msg_local_position_ned_get_z(msg); + local_position_ned->vx = mavlink_msg_local_position_ned_get_vx(msg); + local_position_ned->vy = mavlink_msg_local_position_ned_get_vy(msg); + local_position_ned->vz = mavlink_msg_local_position_ned_get_vz(msg); +#else + memcpy(local_position_ned, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_local_position_ned_cov.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_local_position_ned_cov.h new file mode 100644 index 0000000..59b8369 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_local_position_ned_cov.h @@ -0,0 +1,489 @@ +// MESSAGE LOCAL_POSITION_NED_COV PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV 64 + +typedef struct __mavlink_local_position_ned_cov_t +{ + uint64_t time_utc; /*< Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.*/ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp*/ + float x; /*< X Position*/ + float y; /*< Y Position*/ + float z; /*< Z Position*/ + float vx; /*< X Speed (m/s)*/ + float vy; /*< Y Speed (m/s)*/ + float vz; /*< Z Speed (m/s)*/ + float ax; /*< X Acceleration (m/s^2)*/ + float ay; /*< Y Acceleration (m/s^2)*/ + float az; /*< Z Acceleration (m/s^2)*/ + float covariance[45]; /*< Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)*/ + uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/ +} mavlink_local_position_ned_cov_t; + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN 229 +#define MAVLINK_MSG_ID_64_LEN 229 + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC 59 +#define MAVLINK_MSG_ID_64_CRC 59 + +#define MAVLINK_MSG_LOCAL_POSITION_NED_COV_FIELD_COVARIANCE_LEN 45 + +#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \ + "LOCAL_POSITION_NED_COV", \ + 13, \ + { { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_utc) }, \ + { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_local_position_ned_cov_t, time_boot_ms) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, z) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, vz) }, \ + { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ax) }, \ + { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, ay) }, \ + { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_local_position_ned_cov_t, az) }, \ + { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 48, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \ + { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 228, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \ + } \ +} + + +/** + * @brief Pack a local_position_ned_cov message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp + * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed (m/s) + * @param vy Y Speed (m/s) + * @param vz Z Speed (m/s) + * @param ax X Acceleration (m/s^2) + * @param ay Y Acceleration (m/s^2) + * @param az Z Acceleration (m/s^2) + * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 24, vx); + _mav_put_float(buf, 28, vy); + _mav_put_float(buf, 32, vz); + _mav_put_float(buf, 36, ax); + _mav_put_float(buf, 40, ay); + _mav_put_float(buf, 44, az); + _mav_put_uint8_t(buf, 228, estimator_type); + _mav_put_float_array(buf, 48, covariance, 45); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#else + mavlink_local_position_ned_cov_t packet; + packet.time_utc = time_utc; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ax = ax; + packet.ay = ay; + packet.az = az; + packet.estimator_type = estimator_type; + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif +} + +/** + * @brief Pack a local_position_ned_cov message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp + * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed (m/s) + * @param vy Y Speed (m/s) + * @param vz Z Speed (m/s) + * @param ax X Acceleration (m/s^2) + * @param ay Y Acceleration (m/s^2) + * @param az Z Acceleration (m/s^2) + * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint64_t time_utc,uint8_t estimator_type,float x,float y,float z,float vx,float vy,float vz,float ax,float ay,float az,const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 24, vx); + _mav_put_float(buf, 28, vy); + _mav_put_float(buf, 32, vz); + _mav_put_float(buf, 36, ax); + _mav_put_float(buf, 40, ay); + _mav_put_float(buf, 44, az); + _mav_put_uint8_t(buf, 228, estimator_type); + _mav_put_float_array(buf, 48, covariance, 45); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#else + mavlink_local_position_ned_cov_t packet; + packet.time_utc = time_utc; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ax = ax; + packet.ay = ay; + packet.az = az; + packet.estimator_type = estimator_type; + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif +} + +/** + * @brief Encode a local_position_ned_cov struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param local_position_ned_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_ned_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov) +{ + return mavlink_msg_local_position_ned_cov_pack(system_id, component_id, msg, local_position_ned_cov->time_boot_ms, local_position_ned_cov->time_utc, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance); +} + +/** + * @brief Encode a local_position_ned_cov struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param local_position_ned_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_ned_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov) +{ + return mavlink_msg_local_position_ned_cov_pack_chan(system_id, component_id, chan, msg, local_position_ned_cov->time_boot_ms, local_position_ned_cov->time_utc, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance); +} + +/** + * @brief Send a local_position_ned_cov message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp + * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + * @param estimator_type Class id of the estimator this estimate originated from. + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed (m/s) + * @param vy Y Speed (m/s) + * @param vz Z Speed (m/s) + * @param ax X Acceleration (m/s^2) + * @param ay Y Acceleration (m/s^2) + * @param az Z Acceleration (m/s^2) + * @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_ned_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 24, vx); + _mav_put_float(buf, 28, vy); + _mav_put_float(buf, 32, vz); + _mav_put_float(buf, 36, ax); + _mav_put_float(buf, 40, ay); + _mav_put_float(buf, 44, az); + _mav_put_uint8_t(buf, 228, estimator_type); + _mav_put_float_array(buf, 48, covariance, 45); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif +#else + mavlink_local_position_ned_cov_t packet; + packet.time_utc = time_utc; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ax = ax; + packet.ay = ay; + packet.az = az; + packet.estimator_type = estimator_type; + mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_local_position_ned_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 8, time_boot_ms); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 24, vx); + _mav_put_float(buf, 28, vy); + _mav_put_float(buf, 32, vz); + _mav_put_float(buf, 36, ax); + _mav_put_float(buf, 40, ay); + _mav_put_float(buf, 44, az); + _mav_put_uint8_t(buf, 228, estimator_type); + _mav_put_float_array(buf, 48, covariance, 45); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif +#else + mavlink_local_position_ned_cov_t *packet = (mavlink_local_position_ned_cov_t *)msgbuf; + packet->time_utc = time_utc; + packet->time_boot_ms = time_boot_ms; + packet->x = x; + packet->y = y; + packet->z = z; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->ax = ax; + packet->ay = ay; + packet->az = az; + packet->estimator_type = estimator_type; + mav_array_memcpy(packet->covariance, covariance, sizeof(float)*45); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOCAL_POSITION_NED_COV UNPACKING + + +/** + * @brief Get field time_boot_ms from local_position_ned_cov message + * + * @return Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp + */ +static inline uint32_t mavlink_msg_local_position_ned_cov_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field time_utc from local_position_ned_cov message + * + * @return Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + */ +static inline uint64_t mavlink_msg_local_position_ned_cov_get_time_utc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field estimator_type from local_position_ned_cov message + * + * @return Class id of the estimator this estimate originated from. + */ +static inline uint8_t mavlink_msg_local_position_ned_cov_get_estimator_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 228); +} + +/** + * @brief Get field x from local_position_ned_cov message + * + * @return X Position + */ +static inline float mavlink_msg_local_position_ned_cov_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field y from local_position_ned_cov message + * + * @return Y Position + */ +static inline float mavlink_msg_local_position_ned_cov_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field z from local_position_ned_cov message + * + * @return Z Position + */ +static inline float mavlink_msg_local_position_ned_cov_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vx from local_position_ned_cov message + * + * @return X Speed (m/s) + */ +static inline float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field vy from local_position_ned_cov message + * + * @return Y Speed (m/s) + */ +static inline float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field vz from local_position_ned_cov message + * + * @return Z Speed (m/s) + */ +static inline float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field ax from local_position_ned_cov message + * + * @return X Acceleration (m/s^2) + */ +static inline float mavlink_msg_local_position_ned_cov_get_ax(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field ay from local_position_ned_cov message + * + * @return Y Acceleration (m/s^2) + */ +static inline float mavlink_msg_local_position_ned_cov_get_ay(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field az from local_position_ned_cov message + * + * @return Z Acceleration (m/s^2) + */ +static inline float mavlink_msg_local_position_ned_cov_get_az(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field covariance from local_position_ned_cov message + * + * @return Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + */ +static inline uint16_t mavlink_msg_local_position_ned_cov_get_covariance(const mavlink_message_t* msg, float *covariance) +{ + return _MAV_RETURN_float_array(msg, covariance, 45, 48); +} + +/** + * @brief Decode a local_position_ned_cov message into a struct + * + * @param msg The message to decode + * @param local_position_ned_cov C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_position_ned_cov_decode(const mavlink_message_t* msg, mavlink_local_position_ned_cov_t* local_position_ned_cov) +{ +#if MAVLINK_NEED_BYTE_SWAP + local_position_ned_cov->time_utc = mavlink_msg_local_position_ned_cov_get_time_utc(msg); + local_position_ned_cov->time_boot_ms = mavlink_msg_local_position_ned_cov_get_time_boot_ms(msg); + local_position_ned_cov->x = mavlink_msg_local_position_ned_cov_get_x(msg); + local_position_ned_cov->y = mavlink_msg_local_position_ned_cov_get_y(msg); + local_position_ned_cov->z = mavlink_msg_local_position_ned_cov_get_z(msg); + local_position_ned_cov->vx = mavlink_msg_local_position_ned_cov_get_vx(msg); + local_position_ned_cov->vy = mavlink_msg_local_position_ned_cov_get_vy(msg); + local_position_ned_cov->vz = mavlink_msg_local_position_ned_cov_get_vz(msg); + local_position_ned_cov->ax = mavlink_msg_local_position_ned_cov_get_ax(msg); + local_position_ned_cov->ay = mavlink_msg_local_position_ned_cov_get_ay(msg); + local_position_ned_cov->az = mavlink_msg_local_position_ned_cov_get_az(msg); + mavlink_msg_local_position_ned_cov_get_covariance(msg, local_position_ned_cov->covariance); + local_position_ned_cov->estimator_type = mavlink_msg_local_position_ned_cov_get_estimator_type(msg); +#else + memcpy(local_position_ned_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h new file mode 100644 index 0000000..e6d0766 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h @@ -0,0 +1,353 @@ +// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET 89 + +typedef struct __mavlink_local_position_ned_system_global_offset_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float x; /*< X Position*/ + float y; /*< Y Position*/ + float z; /*< Z Position*/ + float roll; /*< Roll*/ + float pitch; /*< Pitch*/ + float yaw; /*< Yaw*/ +} mavlink_local_position_ned_system_global_offset_t; + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN 28 +#define MAVLINK_MSG_ID_89_LEN 28 + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC 231 +#define MAVLINK_MSG_ID_89_CRC 231 + + + +#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET { \ + "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_system_global_offset_t, time_boot_ms) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_system_global_offset_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_system_global_offset_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_system_global_offset_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_system_global_offset_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_system_global_offset_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_system_global_offset_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a local_position_ned_system_global_offset message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param roll Roll + * @param pitch Pitch + * @param yaw Yaw + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#else + mavlink_local_position_ned_system_global_offset_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif +} + +/** + * @brief Pack a local_position_ned_system_global_offset message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param roll Roll + * @param pitch Pitch + * @param yaw Yaw + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#else + mavlink_local_position_ned_system_global_offset_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif +} + +/** + * @brief Encode a local_position_ned_system_global_offset struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param local_position_ned_system_global_offset C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) +{ + return mavlink_msg_local_position_ned_system_global_offset_pack(system_id, component_id, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); +} + +/** + * @brief Encode a local_position_ned_system_global_offset struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param local_position_ned_system_global_offset C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) +{ + return mavlink_msg_local_position_ned_system_global_offset_pack_chan(system_id, component_id, chan, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); +} + +/** + * @brief Send a local_position_ned_system_global_offset message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param roll Roll + * @param pitch Pitch + * @param yaw Yaw + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_ned_system_global_offset_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif +#else + mavlink_local_position_ned_system_global_offset_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_local_position_ned_system_global_offset_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif +#else + mavlink_local_position_ned_system_global_offset_t *packet = (mavlink_local_position_ned_system_global_offset_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->x = x; + packet->y = y; + packet->z = z; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET UNPACKING + + +/** + * @brief Get field time_boot_ms from local_position_ned_system_global_offset message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field x from local_position_ned_system_global_offset message + * + * @return X Position + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field y from local_position_ned_system_global_offset message + * + * @return Y Position + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field z from local_position_ned_system_global_offset message + * + * @return Z Position + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field roll from local_position_ned_system_global_offset message + * + * @return Roll + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field pitch from local_position_ned_system_global_offset message + * + * @return Pitch + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field yaw from local_position_ned_system_global_offset message + * + * @return Yaw + */ +static inline float mavlink_msg_local_position_ned_system_global_offset_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a local_position_ned_system_global_offset message into a struct + * + * @param msg The message to decode + * @param local_position_ned_system_global_offset C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_position_ned_system_global_offset_decode(const mavlink_message_t* msg, mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) +{ +#if MAVLINK_NEED_BYTE_SWAP + local_position_ned_system_global_offset->time_boot_ms = mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(msg); + local_position_ned_system_global_offset->x = mavlink_msg_local_position_ned_system_global_offset_get_x(msg); + local_position_ned_system_global_offset->y = mavlink_msg_local_position_ned_system_global_offset_get_y(msg); + local_position_ned_system_global_offset->z = mavlink_msg_local_position_ned_system_global_offset_get_z(msg); + local_position_ned_system_global_offset->roll = mavlink_msg_local_position_ned_system_global_offset_get_roll(msg); + local_position_ned_system_global_offset->pitch = mavlink_msg_local_position_ned_system_global_offset_get_pitch(msg); + local_position_ned_system_global_offset->yaw = mavlink_msg_local_position_ned_system_global_offset_get_yaw(msg); +#else + memcpy(local_position_ned_system_global_offset, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_data.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_data.h new file mode 100644 index 0000000..9caae57 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_data.h @@ -0,0 +1,273 @@ +// MESSAGE LOG_DATA PACKING + +#define MAVLINK_MSG_ID_LOG_DATA 120 + +typedef struct __mavlink_log_data_t +{ + uint32_t ofs; /*< Offset into the log*/ + uint16_t id; /*< Log id (from LOG_ENTRY reply)*/ + uint8_t count; /*< Number of bytes (zero for end of log)*/ + uint8_t data[90]; /*< log data*/ +} mavlink_log_data_t; + +#define MAVLINK_MSG_ID_LOG_DATA_LEN 97 +#define MAVLINK_MSG_ID_120_LEN 97 + +#define MAVLINK_MSG_ID_LOG_DATA_CRC 134 +#define MAVLINK_MSG_ID_120_CRC 134 + +#define MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN 90 + +#define MAVLINK_MESSAGE_INFO_LOG_DATA { \ + "LOG_DATA", \ + 4, \ + { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \ + { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \ + { "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \ + } \ +} + + +/** + * @brief Pack a log_data message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes (zero for end of log) + * @param data log data + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint16_t(buf, 4, id); + _mav_put_uint8_t(buf, 6, count); + _mav_put_uint8_t_array(buf, 7, data, 90); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN); +#else + mavlink_log_data_t packet; + packet.ofs = ofs; + packet.id = id; + packet.count = count; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +} + +/** + * @brief Pack a log_data message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes (zero for end of log) + * @param data log data + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t id,uint32_t ofs,uint8_t count,const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint16_t(buf, 4, id); + _mav_put_uint8_t(buf, 6, count); + _mav_put_uint8_t_array(buf, 7, data, 90); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN); +#else + mavlink_log_data_t packet; + packet.ofs = ofs; + packet.id = id; + packet.count = count; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +} + +/** + * @brief Encode a log_data struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param log_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_data_t* log_data) +{ + return mavlink_msg_log_data_pack(system_id, component_id, msg, log_data->id, log_data->ofs, log_data->count, log_data->data); +} + +/** + * @brief Encode a log_data struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param log_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_data_t* log_data) +{ + return mavlink_msg_log_data_pack_chan(system_id, component_id, chan, msg, log_data->id, log_data->ofs, log_data->count, log_data->data); +} + +/** + * @brief Send a log_data message + * @param chan MAVLink channel to send the message + * + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes (zero for end of log) + * @param data log data + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_data_send(mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint16_t(buf, 4, id); + _mav_put_uint8_t(buf, 6, count); + _mav_put_uint8_t_array(buf, 7, data, 90); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +#else + mavlink_log_data_t packet; + packet.ofs = ofs; + packet.id = id; + packet.count = count; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOG_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_log_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint16_t(buf, 4, id); + _mav_put_uint8_t(buf, 6, count); + _mav_put_uint8_t_array(buf, 7, data, 90); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +#else + mavlink_log_data_t *packet = (mavlink_log_data_t *)msgbuf; + packet->ofs = ofs; + packet->id = id; + packet->count = count; + mav_array_memcpy(packet->data, data, sizeof(uint8_t)*90); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOG_DATA UNPACKING + + +/** + * @brief Get field id from log_data message + * + * @return Log id (from LOG_ENTRY reply) + */ +static inline uint16_t mavlink_msg_log_data_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field ofs from log_data message + * + * @return Offset into the log + */ +static inline uint32_t mavlink_msg_log_data_get_ofs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field count from log_data message + * + * @return Number of bytes (zero for end of log) + */ +static inline uint8_t mavlink_msg_log_data_get_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field data from log_data message + * + * @return log data + */ +static inline uint16_t mavlink_msg_log_data_get_data(const mavlink_message_t* msg, uint8_t *data) +{ + return _MAV_RETURN_uint8_t_array(msg, data, 90, 7); +} + +/** + * @brief Decode a log_data message into a struct + * + * @param msg The message to decode + * @param log_data C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_data_decode(const mavlink_message_t* msg, mavlink_log_data_t* log_data) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_data->ofs = mavlink_msg_log_data_get_ofs(msg); + log_data->id = mavlink_msg_log_data_get_id(msg); + log_data->count = mavlink_msg_log_data_get_count(msg); + mavlink_msg_log_data_get_data(msg, log_data->data); +#else + memcpy(log_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_DATA_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_entry.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_entry.h new file mode 100644 index 0000000..4523516 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_entry.h @@ -0,0 +1,305 @@ +// MESSAGE LOG_ENTRY PACKING + +#define MAVLINK_MSG_ID_LOG_ENTRY 118 + +typedef struct __mavlink_log_entry_t +{ + uint32_t time_utc; /*< UTC timestamp of log in seconds since 1970, or 0 if not available*/ + uint32_t size; /*< Size of the log (may be approximate) in bytes*/ + uint16_t id; /*< Log id*/ + uint16_t num_logs; /*< Total number of logs*/ + uint16_t last_log_num; /*< High log number*/ +} mavlink_log_entry_t; + +#define MAVLINK_MSG_ID_LOG_ENTRY_LEN 14 +#define MAVLINK_MSG_ID_118_LEN 14 + +#define MAVLINK_MSG_ID_LOG_ENTRY_CRC 56 +#define MAVLINK_MSG_ID_118_CRC 56 + + + +#define MAVLINK_MESSAGE_INFO_LOG_ENTRY { \ + "LOG_ENTRY", \ + 5, \ + { { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ + { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ + { "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \ + { "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \ + } \ +} + + +/** + * @brief Pack a log_entry message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param id Log id + * @param num_logs Total number of logs + * @param last_log_num High log number + * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available + * @param size Size of the log (may be approximate) in bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_entry_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; + _mav_put_uint32_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 4, size); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint16_t(buf, 10, num_logs); + _mav_put_uint16_t(buf, 12, last_log_num); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#else + mavlink_log_entry_t packet; + packet.time_utc = time_utc; + packet.size = size; + packet.id = id; + packet.num_logs = num_logs; + packet.last_log_num = last_log_num; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +} + +/** + * @brief Pack a log_entry message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param id Log id + * @param num_logs Total number of logs + * @param last_log_num High log number + * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available + * @param size Size of the log (may be approximate) in bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_entry_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t id,uint16_t num_logs,uint16_t last_log_num,uint32_t time_utc,uint32_t size) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; + _mav_put_uint32_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 4, size); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint16_t(buf, 10, num_logs); + _mav_put_uint16_t(buf, 12, last_log_num); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#else + mavlink_log_entry_t packet; + packet.time_utc = time_utc; + packet.size = size; + packet.id = id; + packet.num_logs = num_logs; + packet.last_log_num = last_log_num; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +} + +/** + * @brief Encode a log_entry struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param log_entry C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_entry_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry) +{ + return mavlink_msg_log_entry_pack(system_id, component_id, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); +} + +/** + * @brief Encode a log_entry struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param log_entry C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_entry_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry) +{ + return mavlink_msg_log_entry_pack_chan(system_id, component_id, chan, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); +} + +/** + * @brief Send a log_entry message + * @param chan MAVLink channel to send the message + * + * @param id Log id + * @param num_logs Total number of logs + * @param last_log_num High log number + * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available + * @param size Size of the log (may be approximate) in bytes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_entry_send(mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; + _mav_put_uint32_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 4, size); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint16_t(buf, 10, num_logs); + _mav_put_uint16_t(buf, 12, last_log_num); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +#else + mavlink_log_entry_t packet; + packet.time_utc = time_utc; + packet.size = size; + packet.id = id; + packet.num_logs = num_logs; + packet.last_log_num = last_log_num; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)&packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)&packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOG_ENTRY_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_log_entry_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_utc); + _mav_put_uint32_t(buf, 4, size); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint16_t(buf, 10, num_logs); + _mav_put_uint16_t(buf, 12, last_log_num); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +#else + mavlink_log_entry_t *packet = (mavlink_log_entry_t *)msgbuf; + packet->time_utc = time_utc; + packet->size = size; + packet->id = id; + packet->num_logs = num_logs; + packet->last_log_num = last_log_num; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOG_ENTRY UNPACKING + + +/** + * @brief Get field id from log_entry message + * + * @return Log id + */ +static inline uint16_t mavlink_msg_log_entry_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field num_logs from log_entry message + * + * @return Total number of logs + */ +static inline uint16_t mavlink_msg_log_entry_get_num_logs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field last_log_num from log_entry message + * + * @return High log number + */ +static inline uint16_t mavlink_msg_log_entry_get_last_log_num(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field time_utc from log_entry message + * + * @return UTC timestamp of log in seconds since 1970, or 0 if not available + */ +static inline uint32_t mavlink_msg_log_entry_get_time_utc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field size from log_entry message + * + * @return Size of the log (may be approximate) in bytes + */ +static inline uint32_t mavlink_msg_log_entry_get_size(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Decode a log_entry message into a struct + * + * @param msg The message to decode + * @param log_entry C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_entry_decode(const mavlink_message_t* msg, mavlink_log_entry_t* log_entry) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_entry->time_utc = mavlink_msg_log_entry_get_time_utc(msg); + log_entry->size = mavlink_msg_log_entry_get_size(msg); + log_entry->id = mavlink_msg_log_entry_get_id(msg); + log_entry->num_logs = mavlink_msg_log_entry_get_num_logs(msg); + log_entry->last_log_num = mavlink_msg_log_entry_get_last_log_num(msg); +#else + memcpy(log_entry, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_ENTRY_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_erase.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_erase.h new file mode 100644 index 0000000..06c58be --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_erase.h @@ -0,0 +1,233 @@ +// MESSAGE LOG_ERASE PACKING + +#define MAVLINK_MSG_ID_LOG_ERASE 121 + +typedef struct __mavlink_log_erase_t +{ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_log_erase_t; + +#define MAVLINK_MSG_ID_LOG_ERASE_LEN 2 +#define MAVLINK_MSG_ID_121_LEN 2 + +#define MAVLINK_MSG_ID_LOG_ERASE_CRC 237 +#define MAVLINK_MSG_ID_121_CRC 237 + + + +#define MAVLINK_MESSAGE_INFO_LOG_ERASE { \ + "LOG_ERASE", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_erase_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_erase_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a log_erase message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_erase_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#else + mavlink_log_erase_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_ERASE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +} + +/** + * @brief Pack a log_erase message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_erase_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#else + mavlink_log_erase_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_ERASE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +} + +/** + * @brief Encode a log_erase struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param log_erase C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_erase_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase) +{ + return mavlink_msg_log_erase_pack(system_id, component_id, msg, log_erase->target_system, log_erase->target_component); +} + +/** + * @brief Encode a log_erase struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param log_erase C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_erase_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase) +{ + return mavlink_msg_log_erase_pack_chan(system_id, component_id, chan, msg, log_erase->target_system, log_erase->target_component); +} + +/** + * @brief Send a log_erase message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_erase_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +#else + mavlink_log_erase_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)&packet, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)&packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOG_ERASE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_log_erase_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +#else + mavlink_log_erase_t *packet = (mavlink_log_erase_t *)msgbuf; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)packet, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOG_ERASE UNPACKING + + +/** + * @brief Get field target_system from log_erase message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_log_erase_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from log_erase message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_log_erase_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a log_erase message into a struct + * + * @param msg The message to decode + * @param log_erase C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_erase_decode(const mavlink_message_t* msg, mavlink_log_erase_t* log_erase) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_erase->target_system = mavlink_msg_log_erase_get_target_system(msg); + log_erase->target_component = mavlink_msg_log_erase_get_target_component(msg); +#else + memcpy(log_erase, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_ERASE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_request_data.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_request_data.h new file mode 100644 index 0000000..0b52ea2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_request_data.h @@ -0,0 +1,305 @@ +// MESSAGE LOG_REQUEST_DATA PACKING + +#define MAVLINK_MSG_ID_LOG_REQUEST_DATA 119 + +typedef struct __mavlink_log_request_data_t +{ + uint32_t ofs; /*< Offset into the log*/ + uint32_t count; /*< Number of bytes*/ + uint16_t id; /*< Log id (from LOG_ENTRY reply)*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_log_request_data_t; + +#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN 12 +#define MAVLINK_MSG_ID_119_LEN 12 + +#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC 116 +#define MAVLINK_MSG_ID_119_CRC 116 + + + +#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \ + "LOG_REQUEST_DATA", \ + 5, \ + { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \ + { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a log_request_data message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint32_t(buf, 4, count); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint8_t(buf, 10, target_system); + _mav_put_uint8_t(buf, 11, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#else + mavlink_log_request_data_t packet; + packet.ofs = ofs; + packet.count = count; + packet.id = id; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +} + +/** + * @brief Pack a log_request_data message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t id,uint32_t ofs,uint32_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint32_t(buf, 4, count); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint8_t(buf, 10, target_system); + _mav_put_uint8_t(buf, 11, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#else + mavlink_log_request_data_t packet; + packet.ofs = ofs; + packet.count = count; + packet.id = id; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +} + +/** + * @brief Encode a log_request_data struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param log_request_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data) +{ + return mavlink_msg_log_request_data_pack(system_id, component_id, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); +} + +/** + * @brief Encode a log_request_data struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param log_request_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data) +{ + return mavlink_msg_log_request_data_pack_chan(system_id, component_id, chan, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); +} + +/** + * @brief Send a log_request_data message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param id Log id (from LOG_ENTRY reply) + * @param ofs Offset into the log + * @param count Number of bytes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_request_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint32_t(buf, 4, count); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint8_t(buf, 10, target_system); + _mav_put_uint8_t(buf, 11, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +#else + mavlink_log_request_data_t packet; + packet.ofs = ofs; + packet.count = count; + packet.id = id; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_log_request_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, ofs); + _mav_put_uint32_t(buf, 4, count); + _mav_put_uint16_t(buf, 8, id); + _mav_put_uint8_t(buf, 10, target_system); + _mav_put_uint8_t(buf, 11, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +#else + mavlink_log_request_data_t *packet = (mavlink_log_request_data_t *)msgbuf; + packet->ofs = ofs; + packet->count = count; + packet->id = id; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOG_REQUEST_DATA UNPACKING + + +/** + * @brief Get field target_system from log_request_data message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_log_request_data_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 10); +} + +/** + * @brief Get field target_component from log_request_data message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_log_request_data_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 11); +} + +/** + * @brief Get field id from log_request_data message + * + * @return Log id (from LOG_ENTRY reply) + */ +static inline uint16_t mavlink_msg_log_request_data_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field ofs from log_request_data message + * + * @return Offset into the log + */ +static inline uint32_t mavlink_msg_log_request_data_get_ofs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field count from log_request_data message + * + * @return Number of bytes + */ +static inline uint32_t mavlink_msg_log_request_data_get_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Decode a log_request_data message into a struct + * + * @param msg The message to decode + * @param log_request_data C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_request_data_decode(const mavlink_message_t* msg, mavlink_log_request_data_t* log_request_data) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_request_data->ofs = mavlink_msg_log_request_data_get_ofs(msg); + log_request_data->count = mavlink_msg_log_request_data_get_count(msg); + log_request_data->id = mavlink_msg_log_request_data_get_id(msg); + log_request_data->target_system = mavlink_msg_log_request_data_get_target_system(msg); + log_request_data->target_component = mavlink_msg_log_request_data_get_target_component(msg); +#else + memcpy(log_request_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_request_end.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_request_end.h new file mode 100644 index 0000000..e4da542 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_request_end.h @@ -0,0 +1,233 @@ +// MESSAGE LOG_REQUEST_END PACKING + +#define MAVLINK_MSG_ID_LOG_REQUEST_END 122 + +typedef struct __mavlink_log_request_end_t +{ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_log_request_end_t; + +#define MAVLINK_MSG_ID_LOG_REQUEST_END_LEN 2 +#define MAVLINK_MSG_ID_122_LEN 2 + +#define MAVLINK_MSG_ID_LOG_REQUEST_END_CRC 203 +#define MAVLINK_MSG_ID_122_CRC 203 + + + +#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_END { \ + "LOG_REQUEST_END", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_request_end_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_request_end_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a log_request_end message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_end_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#else + mavlink_log_request_end_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +} + +/** + * @brief Pack a log_request_end message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_end_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#else + mavlink_log_request_end_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +} + +/** + * @brief Encode a log_request_end struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param log_request_end C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_end_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end) +{ + return mavlink_msg_log_request_end_pack(system_id, component_id, msg, log_request_end->target_system, log_request_end->target_component); +} + +/** + * @brief Encode a log_request_end struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param log_request_end C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_end_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end) +{ + return mavlink_msg_log_request_end_pack_chan(system_id, component_id, chan, msg, log_request_end->target_system, log_request_end->target_component); +} + +/** + * @brief Send a log_request_end message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_request_end_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +#else + mavlink_log_request_end_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOG_REQUEST_END_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_log_request_end_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +#else + mavlink_log_request_end_t *packet = (mavlink_log_request_end_t *)msgbuf; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOG_REQUEST_END UNPACKING + + +/** + * @brief Get field target_system from log_request_end message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_log_request_end_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from log_request_end message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_log_request_end_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a log_request_end message into a struct + * + * @param msg The message to decode + * @param log_request_end C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_request_end_decode(const mavlink_message_t* msg, mavlink_log_request_end_t* log_request_end) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_request_end->target_system = mavlink_msg_log_request_end_get_target_system(msg); + log_request_end->target_component = mavlink_msg_log_request_end_get_target_component(msg); +#else + memcpy(log_request_end, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_request_list.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_request_list.h new file mode 100644 index 0000000..a4d5ea0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_log_request_list.h @@ -0,0 +1,281 @@ +// MESSAGE LOG_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_LOG_REQUEST_LIST 117 + +typedef struct __mavlink_log_request_list_t +{ + uint16_t start; /*< First log id (0 for first available)*/ + uint16_t end; /*< Last log id (0xffff for last available)*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_log_request_list_t; + +#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN 6 +#define MAVLINK_MSG_ID_117_LEN 6 + +#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC 128 +#define MAVLINK_MSG_ID_117_CRC 128 + + + +#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST { \ + "LOG_REQUEST_LIST", \ + 4, \ + { { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \ + { "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a log_request_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param start First log id (0 for first available) + * @param end Last log id (0xffff for last available) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; + _mav_put_uint16_t(buf, 0, start); + _mav_put_uint16_t(buf, 2, end); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#else + mavlink_log_request_list_t packet; + packet.start = start; + packet.end = end; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +} + +/** + * @brief Pack a log_request_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param start First log id (0 for first available) + * @param end Last log id (0xffff for last available) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_log_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t start,uint16_t end) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; + _mav_put_uint16_t(buf, 0, start); + _mav_put_uint16_t(buf, 2, end); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#else + mavlink_log_request_list_t packet; + packet.start = start; + packet.end = end; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +} + +/** + * @brief Encode a log_request_list struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param log_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list) +{ + return mavlink_msg_log_request_list_pack(system_id, component_id, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); +} + +/** + * @brief Encode a log_request_list struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param log_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_log_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list) +{ + return mavlink_msg_log_request_list_pack_chan(system_id, component_id, chan, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); +} + +/** + * @brief Send a log_request_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param start First log id (0 for first available) + * @param end Last log id (0xffff for last available) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_log_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; + _mav_put_uint16_t(buf, 0, start); + _mav_put_uint16_t(buf, 2, end); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +#else + mavlink_log_request_list_t packet; + packet.start = start; + packet.end = end; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_log_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, start); + _mav_put_uint16_t(buf, 2, end); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +#else + mavlink_log_request_list_t *packet = (mavlink_log_request_list_t *)msgbuf; + packet->start = start; + packet->end = end; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOG_REQUEST_LIST UNPACKING + + +/** + * @brief Get field target_system from log_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_log_request_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from log_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_log_request_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field start from log_request_list message + * + * @return First log id (0 for first available) + */ +static inline uint16_t mavlink_msg_log_request_list_get_start(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field end from log_request_list message + * + * @return Last log id (0xffff for last available) + */ +static inline uint16_t mavlink_msg_log_request_list_get_end(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Decode a log_request_list message into a struct + * + * @param msg The message to decode + * @param log_request_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_log_request_list_decode(const mavlink_message_t* msg, mavlink_log_request_list_t* log_request_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + log_request_list->start = mavlink_msg_log_request_list_get_start(msg); + log_request_list->end = mavlink_msg_log_request_list_get_end(msg); + log_request_list->target_system = mavlink_msg_log_request_list_get_target_system(msg); + log_request_list->target_component = mavlink_msg_log_request_list_get_target_component(msg); +#else + memcpy(log_request_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_manual_control.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_manual_control.h new file mode 100644 index 0000000..69802bc --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_manual_control.h @@ -0,0 +1,329 @@ +// MESSAGE MANUAL_CONTROL PACKING + +#define MAVLINK_MSG_ID_MANUAL_CONTROL 69 + +typedef struct __mavlink_manual_control_t +{ + int16_t x; /*< X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.*/ + int16_t y; /*< Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.*/ + int16_t z; /*< Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.*/ + int16_t r; /*< R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.*/ + uint16_t buttons; /*< A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.*/ + uint8_t target; /*< The system to be controlled.*/ +} mavlink_manual_control_t; + +#define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 11 +#define MAVLINK_MSG_ID_69_LEN 11 + +#define MAVLINK_MSG_ID_MANUAL_CONTROL_CRC 243 +#define MAVLINK_MSG_ID_69_CRC 243 + + + +#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \ + "MANUAL_CONTROL", \ + 6, \ + { { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \ + { "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \ + { "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \ + { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \ + } \ +} + + +/** + * @brief Pack a manual_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target The system to be controlled. + * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN]; + _mav_put_int16_t(buf, 0, x); + _mav_put_int16_t(buf, 2, y); + _mav_put_int16_t(buf, 4, z); + _mav_put_int16_t(buf, 6, r); + _mav_put_uint16_t(buf, 8, buttons); + _mav_put_uint8_t(buf, 10, target); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#else + mavlink_manual_control_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.r = r; + packet.buttons = buttons; + packet.target = target; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif +} + +/** + * @brief Pack a manual_control message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target The system to be controlled. + * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target,int16_t x,int16_t y,int16_t z,int16_t r,uint16_t buttons) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN]; + _mav_put_int16_t(buf, 0, x); + _mav_put_int16_t(buf, 2, y); + _mav_put_int16_t(buf, 4, z); + _mav_put_int16_t(buf, 6, r); + _mav_put_uint16_t(buf, 8, buttons); + _mav_put_uint8_t(buf, 10, target); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#else + mavlink_manual_control_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.r = r; + packet.buttons = buttons; + packet.target = target; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif +} + +/** + * @brief Encode a manual_control struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param manual_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) +{ + return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons); +} + +/** + * @brief Encode a manual_control struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param manual_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_manual_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) +{ + return mavlink_msg_manual_control_pack_chan(system_id, component_id, chan, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons); +} + +/** + * @brief Send a manual_control message + * @param chan MAVLink channel to send the message + * + * @param target The system to be controlled. + * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN]; + _mav_put_int16_t(buf, 0, x); + _mav_put_int16_t(buf, 2, y); + _mav_put_int16_t(buf, 4, z); + _mav_put_int16_t(buf, 6, r); + _mav_put_uint16_t(buf, 8, buttons); + _mav_put_uint8_t(buf, 10, target); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif +#else + mavlink_manual_control_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.r = r; + packet.buttons = buttons; + packet.target = target; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MANUAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_manual_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int16_t(buf, 0, x); + _mav_put_int16_t(buf, 2, y); + _mav_put_int16_t(buf, 4, z); + _mav_put_int16_t(buf, 6, r); + _mav_put_uint16_t(buf, 8, buttons); + _mav_put_uint8_t(buf, 10, target); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif +#else + mavlink_manual_control_t *packet = (mavlink_manual_control_t *)msgbuf; + packet->x = x; + packet->y = y; + packet->z = z; + packet->r = r; + packet->buttons = buttons; + packet->target = target; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MANUAL_CONTROL UNPACKING + + +/** + * @brief Get field target from manual_control message + * + * @return The system to be controlled. + */ +static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 10); +} + +/** + * @brief Get field x from manual_control message + * + * @return X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + */ +static inline int16_t mavlink_msg_manual_control_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Get field y from manual_control message + * + * @return Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + */ +static inline int16_t mavlink_msg_manual_control_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 2); +} + +/** + * @brief Get field z from manual_control message + * + * @return Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + */ +static inline int16_t mavlink_msg_manual_control_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Get field r from manual_control message + * + * @return R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + */ +static inline int16_t mavlink_msg_manual_control_get_r(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 6); +} + +/** + * @brief Get field buttons from manual_control message + * + * @return A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + */ +static inline uint16_t mavlink_msg_manual_control_get_buttons(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Decode a manual_control message into a struct + * + * @param msg The message to decode + * @param manual_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + manual_control->x = mavlink_msg_manual_control_get_x(msg); + manual_control->y = mavlink_msg_manual_control_get_y(msg); + manual_control->z = mavlink_msg_manual_control_get_z(msg); + manual_control->r = mavlink_msg_manual_control_get_r(msg); + manual_control->buttons = mavlink_msg_manual_control_get_buttons(msg); + manual_control->target = mavlink_msg_manual_control_get_target(msg); +#else + memcpy(manual_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h new file mode 100644 index 0000000..dcb0ed0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h @@ -0,0 +1,353 @@ +// MESSAGE MANUAL_SETPOINT PACKING + +#define MAVLINK_MSG_ID_MANUAL_SETPOINT 81 + +typedef struct __mavlink_manual_setpoint_t +{ + uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ + float roll; /*< Desired roll rate in radians per second*/ + float pitch; /*< Desired pitch rate in radians per second*/ + float yaw; /*< Desired yaw rate in radians per second*/ + float thrust; /*< Collective thrust, normalized to 0 .. 1*/ + uint8_t mode_switch; /*< Flight mode switch position, 0.. 255*/ + uint8_t manual_override_switch; /*< Override mode switch position, 0.. 255*/ +} mavlink_manual_setpoint_t; + +#define MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22 +#define MAVLINK_MSG_ID_81_LEN 22 + +#define MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC 106 +#define MAVLINK_MSG_ID_81_CRC 106 + + + +#define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT { \ + "MANUAL_SETPOINT", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_manual_setpoint_t, time_boot_ms) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_setpoint_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_setpoint_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_setpoint_t, yaw) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_manual_setpoint_t, thrust) }, \ + { "mode_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_setpoint_t, mode_switch) }, \ + { "manual_override_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_manual_setpoint_t, manual_override_switch) }, \ + } \ +} + + +/** + * @brief Pack a manual_setpoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll Desired roll rate in radians per second + * @param pitch Desired pitch rate in radians per second + * @param yaw Desired yaw rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 + * @param mode_switch Flight mode switch position, 0.. 255 + * @param manual_override_switch Override mode switch position, 0.. 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + _mav_put_uint8_t(buf, 20, mode_switch); + _mav_put_uint8_t(buf, 21, manual_override_switch); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#else + mavlink_manual_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.mode_switch = mode_switch; + packet.manual_override_switch = manual_override_switch; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif +} + +/** + * @brief Pack a manual_setpoint message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll Desired roll rate in radians per second + * @param pitch Desired pitch rate in radians per second + * @param yaw Desired yaw rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 + * @param mode_switch Flight mode switch position, 0.. 255 + * @param manual_override_switch Override mode switch position, 0.. 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float roll,float pitch,float yaw,float thrust,uint8_t mode_switch,uint8_t manual_override_switch) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + _mav_put_uint8_t(buf, 20, mode_switch); + _mav_put_uint8_t(buf, 21, manual_override_switch); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#else + mavlink_manual_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.mode_switch = mode_switch; + packet.manual_override_switch = manual_override_switch; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif +} + +/** + * @brief Encode a manual_setpoint struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param manual_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_manual_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint) +{ + return mavlink_msg_manual_setpoint_pack(system_id, component_id, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); +} + +/** + * @brief Encode a manual_setpoint struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param manual_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_manual_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint) +{ + return mavlink_msg_manual_setpoint_pack_chan(system_id, component_id, chan, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); +} + +/** + * @brief Send a manual_setpoint message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll Desired roll rate in radians per second + * @param pitch Desired pitch rate in radians per second + * @param yaw Desired yaw rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 + * @param mode_switch Flight mode switch position, 0.. 255 + * @param manual_override_switch Override mode switch position, 0.. 255 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_manual_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + _mav_put_uint8_t(buf, 20, mode_switch); + _mav_put_uint8_t(buf, 21, manual_override_switch); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif +#else + mavlink_manual_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.mode_switch = mode_switch; + packet.manual_override_switch = manual_override_switch; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_manual_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + _mav_put_uint8_t(buf, 20, mode_switch); + _mav_put_uint8_t(buf, 21, manual_override_switch); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif +#else + mavlink_manual_setpoint_t *packet = (mavlink_manual_setpoint_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + packet->thrust = thrust; + packet->mode_switch = mode_switch; + packet->manual_override_switch = manual_override_switch; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MANUAL_SETPOINT UNPACKING + + +/** + * @brief Get field time_boot_ms from manual_setpoint message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field roll from manual_setpoint message + * + * @return Desired roll rate in radians per second + */ +static inline float mavlink_msg_manual_setpoint_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field pitch from manual_setpoint message + * + * @return Desired pitch rate in radians per second + */ +static inline float mavlink_msg_manual_setpoint_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from manual_setpoint message + * + * @return Desired yaw rate in radians per second + */ +static inline float mavlink_msg_manual_setpoint_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field thrust from manual_setpoint message + * + * @return Collective thrust, normalized to 0 .. 1 + */ +static inline float mavlink_msg_manual_setpoint_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field mode_switch from manual_setpoint message + * + * @return Flight mode switch position, 0.. 255 + */ +static inline uint8_t mavlink_msg_manual_setpoint_get_mode_switch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field manual_override_switch from manual_setpoint message + * + * @return Override mode switch position, 0.. 255 + */ +static inline uint8_t mavlink_msg_manual_setpoint_get_manual_override_switch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 21); +} + +/** + * @brief Decode a manual_setpoint message into a struct + * + * @param msg The message to decode + * @param manual_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_manual_setpoint_decode(const mavlink_message_t* msg, mavlink_manual_setpoint_t* manual_setpoint) +{ +#if MAVLINK_NEED_BYTE_SWAP + manual_setpoint->time_boot_ms = mavlink_msg_manual_setpoint_get_time_boot_ms(msg); + manual_setpoint->roll = mavlink_msg_manual_setpoint_get_roll(msg); + manual_setpoint->pitch = mavlink_msg_manual_setpoint_get_pitch(msg); + manual_setpoint->yaw = mavlink_msg_manual_setpoint_get_yaw(msg); + manual_setpoint->thrust = mavlink_msg_manual_setpoint_get_thrust(msg); + manual_setpoint->mode_switch = mavlink_msg_manual_setpoint_get_mode_switch(msg); + manual_setpoint->manual_override_switch = mavlink_msg_manual_setpoint_get_manual_override_switch(msg); +#else + memcpy(manual_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_memory_vect.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_memory_vect.h new file mode 100644 index 0000000..bf63bc5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_memory_vect.h @@ -0,0 +1,273 @@ +// MESSAGE MEMORY_VECT PACKING + +#define MAVLINK_MSG_ID_MEMORY_VECT 249 + +typedef struct __mavlink_memory_vect_t +{ + uint16_t address; /*< Starting address of the debug variables*/ + uint8_t ver; /*< Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below*/ + uint8_t type; /*< Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14*/ + int8_t value[32]; /*< Memory contents at specified address*/ +} mavlink_memory_vect_t; + +#define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36 +#define MAVLINK_MSG_ID_249_LEN 36 + +#define MAVLINK_MSG_ID_MEMORY_VECT_CRC 204 +#define MAVLINK_MSG_ID_249_CRC 204 + +#define MAVLINK_MSG_MEMORY_VECT_FIELD_VALUE_LEN 32 + +#define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \ + "MEMORY_VECT", \ + 4, \ + { { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \ + { "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \ + { "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \ + } \ +} + + +/** + * @brief Pack a memory_vect message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param address Starting address of the debug variables + * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @param value Memory contents at specified address + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN]; + _mav_put_uint16_t(buf, 0, address); + _mav_put_uint8_t(buf, 2, ver); + _mav_put_uint8_t(buf, 3, type); + _mav_put_int8_t_array(buf, 4, value, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#else + mavlink_memory_vect_t packet; + packet.address = address; + packet.ver = ver; + packet.type = type; + mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif +} + +/** + * @brief Pack a memory_vect message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param address Starting address of the debug variables + * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @param value Memory contents at specified address + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t address,uint8_t ver,uint8_t type,const int8_t *value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN]; + _mav_put_uint16_t(buf, 0, address); + _mav_put_uint8_t(buf, 2, ver); + _mav_put_uint8_t(buf, 3, type); + _mav_put_int8_t_array(buf, 4, value, 32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#else + mavlink_memory_vect_t packet; + packet.address = address; + packet.ver = ver; + packet.type = type; + mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif +} + +/** + * @brief Encode a memory_vect struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param memory_vect C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_memory_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect) +{ + return mavlink_msg_memory_vect_pack(system_id, component_id, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); +} + +/** + * @brief Encode a memory_vect struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param memory_vect C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_memory_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect) +{ + return mavlink_msg_memory_vect_pack_chan(system_id, component_id, chan, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); +} + +/** + * @brief Send a memory_vect message + * @param chan MAVLink channel to send the message + * + * @param address Starting address of the debug variables + * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @param value Memory contents at specified address + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_memory_vect_send(mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN]; + _mav_put_uint16_t(buf, 0, address); + _mav_put_uint8_t(buf, 2, ver); + _mav_put_uint8_t(buf, 3, type); + _mav_put_int8_t_array(buf, 4, value, 32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif +#else + mavlink_memory_vect_t packet; + packet.address = address; + packet.ver = ver; + packet.type = type; + mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MEMORY_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_memory_vect_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, address); + _mav_put_uint8_t(buf, 2, ver); + _mav_put_uint8_t(buf, 3, type); + _mav_put_int8_t_array(buf, 4, value, 32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif +#else + mavlink_memory_vect_t *packet = (mavlink_memory_vect_t *)msgbuf; + packet->address = address; + packet->ver = ver; + packet->type = type; + mav_array_memcpy(packet->value, value, sizeof(int8_t)*32); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MEMORY_VECT UNPACKING + + +/** + * @brief Get field address from memory_vect message + * + * @return Starting address of the debug variables + */ +static inline uint16_t mavlink_msg_memory_vect_get_address(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field ver from memory_vect message + * + * @return Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + */ +static inline uint8_t mavlink_msg_memory_vect_get_ver(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field type from memory_vect message + * + * @return Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + */ +static inline uint8_t mavlink_msg_memory_vect_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field value from memory_vect message + * + * @return Memory contents at specified address + */ +static inline uint16_t mavlink_msg_memory_vect_get_value(const mavlink_message_t* msg, int8_t *value) +{ + return _MAV_RETURN_int8_t_array(msg, value, 32, 4); +} + +/** + * @brief Decode a memory_vect message into a struct + * + * @param msg The message to decode + * @param memory_vect C-struct to decode the message contents into + */ +static inline void mavlink_msg_memory_vect_decode(const mavlink_message_t* msg, mavlink_memory_vect_t* memory_vect) +{ +#if MAVLINK_NEED_BYTE_SWAP + memory_vect->address = mavlink_msg_memory_vect_get_address(msg); + memory_vect->ver = mavlink_msg_memory_vect_get_ver(msg); + memory_vect->type = mavlink_msg_memory_vect_get_type(msg); + mavlink_msg_memory_vect_get_value(msg, memory_vect->value); +#else + memcpy(memory_vect, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MEMORY_VECT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_message_interval.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_message_interval.h new file mode 100644 index 0000000..32c26be --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_message_interval.h @@ -0,0 +1,233 @@ +// MESSAGE MESSAGE_INTERVAL PACKING + +#define MAVLINK_MSG_ID_MESSAGE_INTERVAL 244 + +typedef struct __mavlink_message_interval_t +{ + int32_t interval_us; /*< The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.*/ + uint16_t message_id; /*< The ID of the requested MAVLink message. v1.0 is limited to 254 messages.*/ +} mavlink_message_interval_t; + +#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN 6 +#define MAVLINK_MSG_ID_244_LEN 6 + +#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC 95 +#define MAVLINK_MSG_ID_244_CRC 95 + + + +#define MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL { \ + "MESSAGE_INTERVAL", \ + 2, \ + { { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \ + { "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \ + } \ +} + + +/** + * @brief Pack a message_interval message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + * @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_message_interval_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t message_id, int32_t interval_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN]; + _mav_put_int32_t(buf, 0, interval_us); + _mav_put_uint16_t(buf, 4, message_id); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#else + mavlink_message_interval_t packet; + packet.interval_us = interval_us; + packet.message_id = message_id; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MESSAGE_INTERVAL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif +} + +/** + * @brief Pack a message_interval message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + * @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_message_interval_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t message_id,int32_t interval_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN]; + _mav_put_int32_t(buf, 0, interval_us); + _mav_put_uint16_t(buf, 4, message_id); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#else + mavlink_message_interval_t packet; + packet.interval_us = interval_us; + packet.message_id = message_id; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MESSAGE_INTERVAL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif +} + +/** + * @brief Encode a message_interval struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param message_interval C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_message_interval_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_message_interval_t* message_interval) +{ + return mavlink_msg_message_interval_pack(system_id, component_id, msg, message_interval->message_id, message_interval->interval_us); +} + +/** + * @brief Encode a message_interval struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param message_interval C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_message_interval_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_message_interval_t* message_interval) +{ + return mavlink_msg_message_interval_pack_chan(system_id, component_id, chan, msg, message_interval->message_id, message_interval->interval_us); +} + +/** + * @brief Send a message_interval message + * @param chan MAVLink channel to send the message + * + * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + * @param interval_us The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_message_interval_send(mavlink_channel_t chan, uint16_t message_id, int32_t interval_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN]; + _mav_put_int32_t(buf, 0, interval_us); + _mav_put_uint16_t(buf, 4, message_id); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif +#else + mavlink_message_interval_t packet; + packet.interval_us = interval_us; + packet.message_id = message_id; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)&packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)&packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_message_interval_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t message_id, int32_t interval_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, interval_us); + _mav_put_uint16_t(buf, 4, message_id); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif +#else + mavlink_message_interval_t *packet = (mavlink_message_interval_t *)msgbuf; + packet->interval_us = interval_us; + packet->message_id = message_id; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MESSAGE_INTERVAL UNPACKING + + +/** + * @brief Get field message_id from message_interval message + * + * @return The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + */ +static inline uint16_t mavlink_msg_message_interval_get_message_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field interval_us from message_interval message + * + * @return The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + */ +static inline int32_t mavlink_msg_message_interval_get_interval_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Decode a message_interval message into a struct + * + * @param msg The message to decode + * @param message_interval C-struct to decode the message contents into + */ +static inline void mavlink_msg_message_interval_decode(const mavlink_message_t* msg, mavlink_message_interval_t* message_interval) +{ +#if MAVLINK_NEED_BYTE_SWAP + message_interval->interval_us = mavlink_msg_message_interval_get_interval_us(msg); + message_interval->message_id = mavlink_msg_message_interval_get_message_id(msg); +#else + memcpy(message_interval, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_ack.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_ack.h new file mode 100644 index 0000000..357b3aa --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_ack.h @@ -0,0 +1,257 @@ +// MESSAGE MISSION_ACK PACKING + +#define MAVLINK_MSG_ID_MISSION_ACK 47 + +typedef struct __mavlink_mission_ack_t +{ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t type; /*< See MAV_MISSION_RESULT enum*/ +} mavlink_mission_ack_t; + +#define MAVLINK_MSG_ID_MISSION_ACK_LEN 3 +#define MAVLINK_MSG_ID_47_LEN 3 + +#define MAVLINK_MSG_ID_MISSION_ACK_CRC 153 +#define MAVLINK_MSG_ID_47_CRC 153 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_ACK { \ + "MISSION_ACK", \ + 3, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_ack_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_ack_t, target_component) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_ack_t, type) }, \ + } \ +} + + +/** + * @brief Pack a mission_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param type See MAV_MISSION_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ACK_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#else + mavlink_mission_ack_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type = type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif +} + +/** + * @brief Pack a mission_ack message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param type See MAV_MISSION_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ACK_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#else + mavlink_mission_ack_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type = type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif +} + +/** + * @brief Encode a mission_ack struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack) +{ + return mavlink_msg_mission_ack_pack(system_id, component_id, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type); +} + +/** + * @brief Encode a mission_ack struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack) +{ + return mavlink_msg_mission_ack_pack_chan(system_id, component_id, chan, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type); +} + +/** + * @brief Send a mission_ack message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param type See MAV_MISSION_RESULT enum + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ACK_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif +#else + mavlink_mission_ack_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type = type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif +#else + mavlink_mission_ack_t *packet = (mavlink_mission_ack_t *)msgbuf; + packet->target_system = target_system; + packet->target_component = target_component; + packet->type = type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)packet, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_ACK UNPACKING + + +/** + * @brief Get field target_system from mission_ack message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_ack_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from mission_ack message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_ack_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field type from mission_ack message + * + * @return See MAV_MISSION_RESULT enum + */ +static inline uint8_t mavlink_msg_mission_ack_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a mission_ack message into a struct + * + * @param msg The message to decode + * @param mission_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_ack_decode(const mavlink_message_t* msg, mavlink_mission_ack_t* mission_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_ack->target_system = mavlink_msg_mission_ack_get_target_system(msg); + mission_ack->target_component = mavlink_msg_mission_ack_get_target_component(msg); + mission_ack->type = mavlink_msg_mission_ack_get_type(msg); +#else + memcpy(mission_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ACK_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h new file mode 100644 index 0000000..32c065a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h @@ -0,0 +1,233 @@ +// MESSAGE MISSION_CLEAR_ALL PACKING + +#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL 45 + +typedef struct __mavlink_mission_clear_all_t +{ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_clear_all_t; + +#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 2 +#define MAVLINK_MSG_ID_45_LEN 2 + +#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC 232 +#define MAVLINK_MSG_ID_45_CRC 232 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \ + "MISSION_CLEAR_ALL", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_clear_all_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_clear_all_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_clear_all message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#else + mavlink_mission_clear_all_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif +} + +/** + * @brief Pack a mission_clear_all message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_clear_all_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#else + mavlink_mission_clear_all_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif +} + +/** + * @brief Encode a mission_clear_all struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_clear_all C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all) +{ + return mavlink_msg_mission_clear_all_pack(system_id, component_id, msg, mission_clear_all->target_system, mission_clear_all->target_component); +} + +/** + * @brief Encode a mission_clear_all struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_clear_all C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_clear_all_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all) +{ + return mavlink_msg_mission_clear_all_pack_chan(system_id, component_id, chan, msg, mission_clear_all->target_system, mission_clear_all->target_component); +} + +/** + * @brief Send a mission_clear_all message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif +#else + mavlink_mission_clear_all_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_clear_all_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif +#else + mavlink_mission_clear_all_t *packet = (mavlink_mission_clear_all_t *)msgbuf; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_CLEAR_ALL UNPACKING + + +/** + * @brief Get field target_system from mission_clear_all message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_clear_all_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from mission_clear_all message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_clear_all_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a mission_clear_all message into a struct + * + * @param msg The message to decode + * @param mission_clear_all C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_clear_all_decode(const mavlink_message_t* msg, mavlink_mission_clear_all_t* mission_clear_all) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_clear_all->target_system = mavlink_msg_mission_clear_all_get_target_system(msg); + mission_clear_all->target_component = mavlink_msg_mission_clear_all_get_target_component(msg); +#else + memcpy(mission_clear_all, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_count.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_count.h new file mode 100644 index 0000000..991a2c2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_count.h @@ -0,0 +1,257 @@ +// MESSAGE MISSION_COUNT PACKING + +#define MAVLINK_MSG_ID_MISSION_COUNT 44 + +typedef struct __mavlink_mission_count_t +{ + uint16_t count; /*< Number of mission items in the sequence*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_count_t; + +#define MAVLINK_MSG_ID_MISSION_COUNT_LEN 4 +#define MAVLINK_MSG_ID_44_LEN 4 + +#define MAVLINK_MSG_ID_MISSION_COUNT_CRC 221 +#define MAVLINK_MSG_ID_44_CRC 221 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \ + "MISSION_COUNT", \ + 3, \ + { { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_count message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param count Number of mission items in the sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN]; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#else + mavlink_mission_count_t packet; + packet.count = count; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif +} + +/** + * @brief Pack a mission_count message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param count Number of mission items in the sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN]; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#else + mavlink_mission_count_t packet; + packet.count = count; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif +} + +/** + * @brief Encode a mission_count struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_count C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count) +{ + return mavlink_msg_mission_count_pack(system_id, component_id, msg, mission_count->target_system, mission_count->target_component, mission_count->count); +} + +/** + * @brief Encode a mission_count struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_count C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_count_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count) +{ + return mavlink_msg_mission_count_pack_chan(system_id, component_id, chan, msg, mission_count->target_system, mission_count->target_component, mission_count->count); +} + +/** + * @brief Send a mission_count message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param count Number of mission items in the sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN]; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif +#else + mavlink_mission_count_t packet; + packet.count = count; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_COUNT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_count_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif +#else + mavlink_mission_count_t *packet = (mavlink_mission_count_t *)msgbuf; + packet->count = count; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_COUNT UNPACKING + + +/** + * @brief Get field target_system from mission_count message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_count_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from mission_count message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_count_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field count from mission_count message + * + * @return Number of mission items in the sequence + */ +static inline uint16_t mavlink_msg_mission_count_get_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_count message into a struct + * + * @param msg The message to decode + * @param mission_count C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_count_decode(const mavlink_message_t* msg, mavlink_mission_count_t* mission_count) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_count->count = mavlink_msg_mission_count_get_count(msg); + mission_count->target_system = mavlink_msg_mission_count_get_target_system(msg); + mission_count->target_component = mavlink_msg_mission_count_get_target_component(msg); +#else + memcpy(mission_count, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_COUNT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_current.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_current.h new file mode 100644 index 0000000..942d02f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_current.h @@ -0,0 +1,209 @@ +// MESSAGE MISSION_CURRENT PACKING + +#define MAVLINK_MSG_ID_MISSION_CURRENT 42 + +typedef struct __mavlink_mission_current_t +{ + uint16_t seq; /*< Sequence*/ +} mavlink_mission_current_t; + +#define MAVLINK_MSG_ID_MISSION_CURRENT_LEN 2 +#define MAVLINK_MSG_ID_42_LEN 2 + +#define MAVLINK_MSG_ID_MISSION_CURRENT_CRC 28 +#define MAVLINK_MSG_ID_42_CRC 28 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \ + "MISSION_CURRENT", \ + 1, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \ + } \ +} + + +/** + * @brief Pack a mission_current message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#else + mavlink_mission_current_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif +} + +/** + * @brief Pack a mission_current message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#else + mavlink_mission_current_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif +} + +/** + * @brief Encode a mission_current struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current) +{ + return mavlink_msg_mission_current_pack(system_id, component_id, msg, mission_current->seq); +} + +/** + * @brief Encode a mission_current struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current) +{ + return mavlink_msg_mission_current_pack_chan(system_id, component_id, chan, msg, mission_current->seq); +} + +/** + * @brief Send a mission_current message + * @param chan MAVLink channel to send the message + * + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_current_send(mavlink_channel_t chan, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif +#else + mavlink_mission_current_t packet; + packet.seq = seq; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_current_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, seq); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif +#else + mavlink_mission_current_t *packet = (mavlink_mission_current_t *)msgbuf; + packet->seq = seq; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_CURRENT UNPACKING + + +/** + * @brief Get field seq from mission_current message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_current_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_current message into a struct + * + * @param msg The message to decode + * @param mission_current C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_current_decode(const mavlink_message_t* msg, mavlink_mission_current_t* mission_current) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_current->seq = mavlink_msg_mission_current_get_seq(msg); +#else + memcpy(mission_current, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_CURRENT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_item.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_item.h new file mode 100644 index 0000000..367c265 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_item.h @@ -0,0 +1,521 @@ +// MESSAGE MISSION_ITEM PACKING + +#define MAVLINK_MSG_ID_MISSION_ITEM 39 + +typedef struct __mavlink_mission_item_t +{ + float param1; /*< PARAM1, see MAV_CMD enum*/ + float param2; /*< PARAM2, see MAV_CMD enum*/ + float param3; /*< PARAM3, see MAV_CMD enum*/ + float param4; /*< PARAM4, see MAV_CMD enum*/ + float x; /*< PARAM5 / local: x position, global: latitude*/ + float y; /*< PARAM6 / y position: global: longitude*/ + float z; /*< PARAM7 / z position: global: altitude (relative or absolute, depending on frame.*/ + uint16_t seq; /*< Sequence*/ + uint16_t command; /*< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t frame; /*< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h*/ + uint8_t current; /*< false:0, true:1*/ + uint8_t autocontinue; /*< autocontinue to next wp*/ +} mavlink_mission_item_t; + +#define MAVLINK_MSG_ID_MISSION_ITEM_LEN 37 +#define MAVLINK_MSG_ID_39_LEN 37 + +#define MAVLINK_MSG_ID_MISSION_ITEM_CRC 254 +#define MAVLINK_MSG_ID_39_CRC 254 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \ + "MISSION_ITEM", \ + 14, \ + { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \ + } \ +} + + +/** + * @brief Pack a mission_item message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#else + mavlink_mission_item_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif +} + +/** + * @brief Pack a mission_item message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,float x,float y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#else + mavlink_mission_item_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif +} + +/** + * @brief Encode a mission_item struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_item C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item) +{ + return mavlink_msg_mission_item_pack(system_id, component_id, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z); +} + +/** + * @brief Encode a mission_item struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_item C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item) +{ + return mavlink_msg_mission_item_pack_chan(system_id, component_id, chan, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z); +} + +/** + * @brief Send a mission_item message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_item_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif +#else + mavlink_mission_item_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_ITEM_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_item_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif +#else + mavlink_mission_item_t *packet = (mavlink_mission_item_t *)msgbuf; + packet->param1 = param1; + packet->param2 = param2; + packet->param3 = param3; + packet->param4 = param4; + packet->x = x; + packet->y = y; + packet->z = z; + packet->seq = seq; + packet->command = command; + packet->target_system = target_system; + packet->target_component = target_component; + packet->frame = frame; + packet->current = current; + packet->autocontinue = autocontinue; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_ITEM UNPACKING + + +/** + * @brief Get field target_system from mission_item message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_item_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field target_component from mission_item message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_item_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field seq from mission_item message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_item_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field frame from mission_item message + * + * @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + */ +static inline uint8_t mavlink_msg_mission_item_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field command from mission_item message + * + * @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + */ +static inline uint16_t mavlink_msg_mission_item_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 30); +} + +/** + * @brief Get field current from mission_item message + * + * @return false:0, true:1 + */ +static inline uint8_t mavlink_msg_mission_item_get_current(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 35); +} + +/** + * @brief Get field autocontinue from mission_item message + * + * @return autocontinue to next wp + */ +static inline uint8_t mavlink_msg_mission_item_get_autocontinue(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Get field param1 from mission_item message + * + * @return PARAM1, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_get_param1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param2 from mission_item message + * + * @return PARAM2, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_get_param2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param3 from mission_item message + * + * @return PARAM3, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_get_param3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param4 from mission_item message + * + * @return PARAM4, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_get_param4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field x from mission_item message + * + * @return PARAM5 / local: x position, global: latitude + */ +static inline float mavlink_msg_mission_item_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field y from mission_item message + * + * @return PARAM6 / y position: global: longitude + */ +static inline float mavlink_msg_mission_item_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field z from mission_item message + * + * @return PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + */ +static inline float mavlink_msg_mission_item_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a mission_item message into a struct + * + * @param msg The message to decode + * @param mission_item C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_item_decode(const mavlink_message_t* msg, mavlink_mission_item_t* mission_item) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_item->param1 = mavlink_msg_mission_item_get_param1(msg); + mission_item->param2 = mavlink_msg_mission_item_get_param2(msg); + mission_item->param3 = mavlink_msg_mission_item_get_param3(msg); + mission_item->param4 = mavlink_msg_mission_item_get_param4(msg); + mission_item->x = mavlink_msg_mission_item_get_x(msg); + mission_item->y = mavlink_msg_mission_item_get_y(msg); + mission_item->z = mavlink_msg_mission_item_get_z(msg); + mission_item->seq = mavlink_msg_mission_item_get_seq(msg); + mission_item->command = mavlink_msg_mission_item_get_command(msg); + mission_item->target_system = mavlink_msg_mission_item_get_target_system(msg); + mission_item->target_component = mavlink_msg_mission_item_get_target_component(msg); + mission_item->frame = mavlink_msg_mission_item_get_frame(msg); + mission_item->current = mavlink_msg_mission_item_get_current(msg); + mission_item->autocontinue = mavlink_msg_mission_item_get_autocontinue(msg); +#else + memcpy(mission_item, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ITEM_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_item_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_item_int.h new file mode 100644 index 0000000..8d824be --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_item_int.h @@ -0,0 +1,521 @@ +// MESSAGE MISSION_ITEM_INT PACKING + +#define MAVLINK_MSG_ID_MISSION_ITEM_INT 73 + +typedef struct __mavlink_mission_item_int_t +{ + float param1; /*< PARAM1, see MAV_CMD enum*/ + float param2; /*< PARAM2, see MAV_CMD enum*/ + float param3; /*< PARAM3, see MAV_CMD enum*/ + float param4; /*< PARAM4, see MAV_CMD enum*/ + int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/ + int32_t y; /*< PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7*/ + float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/ + uint16_t seq; /*< Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).*/ + uint16_t command; /*< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t frame; /*< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h*/ + uint8_t current; /*< false:0, true:1*/ + uint8_t autocontinue; /*< autocontinue to next wp*/ +} mavlink_mission_item_int_t; + +#define MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN 37 +#define MAVLINK_MSG_ID_73_LEN 37 + +#define MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC 38 +#define MAVLINK_MSG_ID_73_CRC 38 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \ + "MISSION_ITEM_INT", \ + 14, \ + { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \ + { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \ + { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \ + } \ +} + + +/** + * @brief Pack a mission_item_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#else + mavlink_mission_item_int_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif +} + +/** + * @brief Pack a mission_item_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,int32_t x,int32_t y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#else + mavlink_mission_item_int_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif +} + +/** + * @brief Encode a mission_item_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_item_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int) +{ + return mavlink_msg_mission_item_int_pack(system_id, component_id, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z); +} + +/** + * @brief Encode a mission_item_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_item_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int) +{ + return mavlink_msg_mission_item_int_pack_chan(system_id, component_id, chan, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z); +} + +/** + * @brief Send a mission_item_int message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1, see MAV_CMD enum + * @param param2 PARAM2, see MAV_CMD enum + * @param param3 PARAM3, see MAV_CMD enum + * @param param4 PARAM4, see MAV_CMD enum + * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_item_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif +#else + mavlink_mission_item_int_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.command = command; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.current = current; + packet.autocontinue = autocontinue; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_item_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_int32_t(buf, 16, x); + _mav_put_int32_t(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint16_t(buf, 30, command); + _mav_put_uint8_t(buf, 32, target_system); + _mav_put_uint8_t(buf, 33, target_component); + _mav_put_uint8_t(buf, 34, frame); + _mav_put_uint8_t(buf, 35, current); + _mav_put_uint8_t(buf, 36, autocontinue); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif +#else + mavlink_mission_item_int_t *packet = (mavlink_mission_item_int_t *)msgbuf; + packet->param1 = param1; + packet->param2 = param2; + packet->param3 = param3; + packet->param4 = param4; + packet->x = x; + packet->y = y; + packet->z = z; + packet->seq = seq; + packet->command = command; + packet->target_system = target_system; + packet->target_component = target_component; + packet->frame = frame; + packet->current = current; + packet->autocontinue = autocontinue; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_ITEM_INT UNPACKING + + +/** + * @brief Get field target_system from mission_item_int message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_item_int_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field target_component from mission_item_int message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_item_int_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field seq from mission_item_int message + * + * @return Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + */ +static inline uint16_t mavlink_msg_mission_item_int_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field frame from mission_item_int message + * + * @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + */ +static inline uint8_t mavlink_msg_mission_item_int_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field command from mission_item_int message + * + * @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + */ +static inline uint16_t mavlink_msg_mission_item_int_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 30); +} + +/** + * @brief Get field current from mission_item_int message + * + * @return false:0, true:1 + */ +static inline uint8_t mavlink_msg_mission_item_int_get_current(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 35); +} + +/** + * @brief Get field autocontinue from mission_item_int message + * + * @return autocontinue to next wp + */ +static inline uint8_t mavlink_msg_mission_item_int_get_autocontinue(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Get field param1 from mission_item_int message + * + * @return PARAM1, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_int_get_param1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param2 from mission_item_int message + * + * @return PARAM2, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_int_get_param2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param3 from mission_item_int message + * + * @return PARAM3, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_int_get_param3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param4 from mission_item_int message + * + * @return PARAM4, see MAV_CMD enum + */ +static inline float mavlink_msg_mission_item_int_get_param4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field x from mission_item_int message + * + * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + */ +static inline int32_t mavlink_msg_mission_item_int_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field y from mission_item_int message + * + * @return PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + */ +static inline int32_t mavlink_msg_mission_item_int_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 20); +} + +/** + * @brief Get field z from mission_item_int message + * + * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + */ +static inline float mavlink_msg_mission_item_int_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a mission_item_int message into a struct + * + * @param msg The message to decode + * @param mission_item_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_item_int_decode(const mavlink_message_t* msg, mavlink_mission_item_int_t* mission_item_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_item_int->param1 = mavlink_msg_mission_item_int_get_param1(msg); + mission_item_int->param2 = mavlink_msg_mission_item_int_get_param2(msg); + mission_item_int->param3 = mavlink_msg_mission_item_int_get_param3(msg); + mission_item_int->param4 = mavlink_msg_mission_item_int_get_param4(msg); + mission_item_int->x = mavlink_msg_mission_item_int_get_x(msg); + mission_item_int->y = mavlink_msg_mission_item_int_get_y(msg); + mission_item_int->z = mavlink_msg_mission_item_int_get_z(msg); + mission_item_int->seq = mavlink_msg_mission_item_int_get_seq(msg); + mission_item_int->command = mavlink_msg_mission_item_int_get_command(msg); + mission_item_int->target_system = mavlink_msg_mission_item_int_get_target_system(msg); + mission_item_int->target_component = mavlink_msg_mission_item_int_get_target_component(msg); + mission_item_int->frame = mavlink_msg_mission_item_int_get_frame(msg); + mission_item_int->current = mavlink_msg_mission_item_int_get_current(msg); + mission_item_int->autocontinue = mavlink_msg_mission_item_int_get_autocontinue(msg); +#else + memcpy(mission_item_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h new file mode 100644 index 0000000..88aa14c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h @@ -0,0 +1,209 @@ +// MESSAGE MISSION_ITEM_REACHED PACKING + +#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED 46 + +typedef struct __mavlink_mission_item_reached_t +{ + uint16_t seq; /*< Sequence*/ +} mavlink_mission_item_reached_t; + +#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN 2 +#define MAVLINK_MSG_ID_46_LEN 2 + +#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC 11 +#define MAVLINK_MSG_ID_46_CRC 11 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED { \ + "MISSION_ITEM_REACHED", \ + 1, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_item_reached_t, seq) }, \ + } \ +} + + +/** + * @brief Pack a mission_item_reached message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_reached_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#else + mavlink_mission_item_reached_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif +} + +/** + * @brief Pack a mission_item_reached message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#else + mavlink_mission_item_reached_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif +} + +/** + * @brief Encode a mission_item_reached struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_item_reached C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached) +{ + return mavlink_msg_mission_item_reached_pack(system_id, component_id, msg, mission_item_reached->seq); +} + +/** + * @brief Encode a mission_item_reached struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_item_reached C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_reached_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached) +{ + return mavlink_msg_mission_item_reached_pack_chan(system_id, component_id, chan, msg, mission_item_reached->seq); +} + +/** + * @brief Send a mission_item_reached message + * @param chan MAVLink channel to send the message + * + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_item_reached_send(mavlink_channel_t chan, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; + _mav_put_uint16_t(buf, 0, seq); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif +#else + mavlink_mission_item_reached_t packet; + packet.seq = seq; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_item_reached_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, seq); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif +#else + mavlink_mission_item_reached_t *packet = (mavlink_mission_item_reached_t *)msgbuf; + packet->seq = seq; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_ITEM_REACHED UNPACKING + + +/** + * @brief Get field seq from mission_item_reached message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_item_reached_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_item_reached message into a struct + * + * @param msg The message to decode + * @param mission_item_reached C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_item_reached_decode(const mavlink_message_t* msg, mavlink_mission_item_reached_t* mission_item_reached) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_item_reached->seq = mavlink_msg_mission_item_reached_get_seq(msg); +#else + memcpy(mission_item_reached, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_request.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_request.h new file mode 100644 index 0000000..d034047 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_request.h @@ -0,0 +1,257 @@ +// MESSAGE MISSION_REQUEST PACKING + +#define MAVLINK_MSG_ID_MISSION_REQUEST 40 + +typedef struct __mavlink_mission_request_t +{ + uint16_t seq; /*< Sequence*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_request_t; + +#define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4 +#define MAVLINK_MSG_ID_40_LEN 4 + +#define MAVLINK_MSG_ID_MISSION_REQUEST_CRC 230 +#define MAVLINK_MSG_ID_40_CRC 230 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \ + "MISSION_REQUEST", \ + 3, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_request message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#else + mavlink_mission_request_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif +} + +/** + * @brief Pack a mission_request message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#else + mavlink_mission_request_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif +} + +/** + * @brief Encode a mission_request struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request) +{ + return mavlink_msg_mission_request_pack(system_id, component_id, msg, mission_request->target_system, mission_request->target_component, mission_request->seq); +} + +/** + * @brief Encode a mission_request struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request) +{ + return mavlink_msg_mission_request_pack_chan(system_id, component_id, chan, msg, mission_request->target_system, mission_request->target_component, mission_request->seq); +} + +/** + * @brief Send a mission_request message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif +#else + mavlink_mission_request_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif +#else + mavlink_mission_request_t *packet = (mavlink_mission_request_t *)msgbuf; + packet->seq = seq; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_REQUEST UNPACKING + + +/** + * @brief Get field target_system from mission_request message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_request_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from mission_request message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_request_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field seq from mission_request message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_request_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_request message into a struct + * + * @param msg The message to decode + * @param mission_request C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_request_decode(const mavlink_message_t* msg, mavlink_mission_request_t* mission_request) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_request->seq = mavlink_msg_mission_request_get_seq(msg); + mission_request->target_system = mavlink_msg_mission_request_get_target_system(msg); + mission_request->target_component = mavlink_msg_mission_request_get_target_component(msg); +#else + memcpy(mission_request, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_REQUEST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_request_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_request_int.h new file mode 100644 index 0000000..b44a486 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_request_int.h @@ -0,0 +1,257 @@ +// MESSAGE MISSION_REQUEST_INT PACKING + +#define MAVLINK_MSG_ID_MISSION_REQUEST_INT 51 + +typedef struct __mavlink_mission_request_int_t +{ + uint16_t seq; /*< Sequence*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_request_int_t; + +#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN 4 +#define MAVLINK_MSG_ID_51_LEN 4 + +#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC 196 +#define MAVLINK_MSG_ID_51_CRC 196 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT { \ + "MISSION_REQUEST_INT", \ + 3, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_request_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#else + mavlink_mission_request_int_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif +} + +/** + * @brief Pack a mission_request_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#else + mavlink_mission_request_int_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif +} + +/** + * @brief Encode a mission_request_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_request_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_int_t* mission_request_int) +{ + return mavlink_msg_mission_request_int_pack(system_id, component_id, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq); +} + +/** + * @brief Encode a mission_request_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_request_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_int_t* mission_request_int) +{ + return mavlink_msg_mission_request_int_pack_chan(system_id, component_id, chan, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq); +} + +/** + * @brief Send a mission_request_int message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_request_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif +#else + mavlink_mission_request_int_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_request_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif +#else + mavlink_mission_request_int_t *packet = (mavlink_mission_request_int_t *)msgbuf; + packet->seq = seq; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_REQUEST_INT UNPACKING + + +/** + * @brief Get field target_system from mission_request_int message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_request_int_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from mission_request_int message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_request_int_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field seq from mission_request_int message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_request_int_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_request_int message into a struct + * + * @param msg The message to decode + * @param mission_request_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_request_int_decode(const mavlink_message_t* msg, mavlink_mission_request_int_t* mission_request_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_request_int->seq = mavlink_msg_mission_request_int_get_seq(msg); + mission_request_int->target_system = mavlink_msg_mission_request_int_get_target_system(msg); + mission_request_int->target_component = mavlink_msg_mission_request_int_get_target_component(msg); +#else + memcpy(mission_request_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_request_list.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_request_list.h new file mode 100644 index 0000000..8ab2929 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_request_list.h @@ -0,0 +1,233 @@ +// MESSAGE MISSION_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST 43 + +typedef struct __mavlink_mission_request_list_t +{ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_request_list_t; + +#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 2 +#define MAVLINK_MSG_ID_43_LEN 2 + +#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC 132 +#define MAVLINK_MSG_ID_43_CRC 132 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST { \ + "MISSION_REQUEST_LIST", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_request_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_request_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_request_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#else + mavlink_mission_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif +} + +/** + * @brief Pack a mission_request_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#else + mavlink_mission_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif +} + +/** + * @brief Encode a mission_request_list struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list) +{ + return mavlink_msg_mission_request_list_pack(system_id, component_id, msg, mission_request_list->target_system, mission_request_list->target_component); +} + +/** + * @brief Encode a mission_request_list struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list) +{ + return mavlink_msg_mission_request_list_pack_chan(system_id, component_id, chan, msg, mission_request_list->target_system, mission_request_list->target_component); +} + +/** + * @brief Send a mission_request_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif +#else + mavlink_mission_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif +#else + mavlink_mission_request_list_t *packet = (mavlink_mission_request_list_t *)msgbuf; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_REQUEST_LIST UNPACKING + + +/** + * @brief Get field target_system from mission_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_request_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from mission_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_request_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a mission_request_list message into a struct + * + * @param msg The message to decode + * @param mission_request_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_request_list_decode(const mavlink_message_t* msg, mavlink_mission_request_list_t* mission_request_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_request_list->target_system = mavlink_msg_mission_request_list_get_target_system(msg); + mission_request_list->target_component = mavlink_msg_mission_request_list_get_target_component(msg); +#else + memcpy(mission_request_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h new file mode 100644 index 0000000..39d3cdf --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h @@ -0,0 +1,281 @@ +// MESSAGE MISSION_REQUEST_PARTIAL_LIST PACKING + +#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST 37 + +typedef struct __mavlink_mission_request_partial_list_t +{ + int16_t start_index; /*< Start index, 0 by default*/ + int16_t end_index; /*< End index, -1 by default (-1: send list to end). Else a valid index of the list*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_request_partial_list_t; + +#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 6 +#define MAVLINK_MSG_ID_37_LEN 6 + +#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC 212 +#define MAVLINK_MSG_ID_37_CRC 212 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \ + "MISSION_REQUEST_PARTIAL_LIST", \ + 4, \ + { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \ + { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_request_partial_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default + * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#else + mavlink_mission_request_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif +} + +/** + * @brief Pack a mission_request_partial_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default + * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#else + mavlink_mission_request_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif +} + +/** + * @brief Encode a mission_request_partial_list struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_request_partial_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list) +{ + return mavlink_msg_mission_request_partial_list_pack(system_id, component_id, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index); +} + +/** + * @brief Encode a mission_request_partial_list struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_request_partial_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list) +{ + return mavlink_msg_mission_request_partial_list_pack_chan(system_id, component_id, chan, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index); +} + +/** + * @brief Send a mission_request_partial_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default + * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_request_partial_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif +#else + mavlink_mission_request_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_request_partial_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif +#else + mavlink_mission_request_partial_list_t *packet = (mavlink_mission_request_partial_list_t *)msgbuf; + packet->start_index = start_index; + packet->end_index = end_index; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_REQUEST_PARTIAL_LIST UNPACKING + + +/** + * @brief Get field target_system from mission_request_partial_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from mission_request_partial_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field start_index from mission_request_partial_list message + * + * @return Start index, 0 by default + */ +static inline int16_t mavlink_msg_mission_request_partial_list_get_start_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Get field end_index from mission_request_partial_list message + * + * @return End index, -1 by default (-1: send list to end). Else a valid index of the list + */ +static inline int16_t mavlink_msg_mission_request_partial_list_get_end_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 2); +} + +/** + * @brief Decode a mission_request_partial_list message into a struct + * + * @param msg The message to decode + * @param mission_request_partial_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_request_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_request_partial_list_t* mission_request_partial_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_request_partial_list->start_index = mavlink_msg_mission_request_partial_list_get_start_index(msg); + mission_request_partial_list->end_index = mavlink_msg_mission_request_partial_list_get_end_index(msg); + mission_request_partial_list->target_system = mavlink_msg_mission_request_partial_list_get_target_system(msg); + mission_request_partial_list->target_component = mavlink_msg_mission_request_partial_list_get_target_component(msg); +#else + memcpy(mission_request_partial_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_set_current.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_set_current.h new file mode 100644 index 0000000..0934dad --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_set_current.h @@ -0,0 +1,257 @@ +// MESSAGE MISSION_SET_CURRENT PACKING + +#define MAVLINK_MSG_ID_MISSION_SET_CURRENT 41 + +typedef struct __mavlink_mission_set_current_t +{ + uint16_t seq; /*< Sequence*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_set_current_t; + +#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN 4 +#define MAVLINK_MSG_ID_41_LEN 4 + +#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC 28 +#define MAVLINK_MSG_ID_41_CRC 28 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT { \ + "MISSION_SET_CURRENT", \ + 3, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_set_current message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_set_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#else + mavlink_mission_set_current_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif +} + +/** + * @brief Pack a mission_set_current message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_set_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#else + mavlink_mission_set_current_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif +} + +/** + * @brief Encode a mission_set_current struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_set_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current) +{ + return mavlink_msg_mission_set_current_pack(system_id, component_id, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); +} + +/** + * @brief Encode a mission_set_current struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_set_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_set_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current) +{ + return mavlink_msg_mission_set_current_pack_chan(system_id, component_id, chan, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); +} + +/** + * @brief Send a mission_set_current message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_set_current_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif +#else + mavlink_mission_set_current_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_set_current_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif +#else + mavlink_mission_set_current_t *packet = (mavlink_mission_set_current_t *)msgbuf; + packet->seq = seq; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_SET_CURRENT UNPACKING + + +/** + * @brief Get field target_system from mission_set_current message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_set_current_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from mission_set_current message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_set_current_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field seq from mission_set_current message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_set_current_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_set_current message into a struct + * + * @param msg The message to decode + * @param mission_set_current C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_set_current_decode(const mavlink_message_t* msg, mavlink_mission_set_current_t* mission_set_current) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_set_current->seq = mavlink_msg_mission_set_current_get_seq(msg); + mission_set_current->target_system = mavlink_msg_mission_set_current_get_target_system(msg); + mission_set_current->target_component = mavlink_msg_mission_set_current_get_target_component(msg); +#else + memcpy(mission_set_current, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h new file mode 100644 index 0000000..8568c2b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h @@ -0,0 +1,281 @@ +// MESSAGE MISSION_WRITE_PARTIAL_LIST PACKING + +#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST 38 + +typedef struct __mavlink_mission_write_partial_list_t +{ + int16_t start_index; /*< Start index, 0 by default and smaller / equal to the largest index of the current onboard list.*/ + int16_t end_index; /*< End index, equal or greater than start index.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_mission_write_partial_list_t; + +#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 6 +#define MAVLINK_MSG_ID_38_LEN 6 + +#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC 9 +#define MAVLINK_MSG_ID_38_CRC 9 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \ + "MISSION_WRITE_PARTIAL_LIST", \ + 4, \ + { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \ + { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_write_partial_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_write_partial_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + * @param end_index End index, equal or greater than start index. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#else + mavlink_mission_write_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif +} + +/** + * @brief Pack a mission_write_partial_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + * @param end_index End index, equal or greater than start index. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_write_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#else + mavlink_mission_write_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif +} + +/** + * @brief Encode a mission_write_partial_list struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_write_partial_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_write_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list) +{ + return mavlink_msg_mission_write_partial_list_pack(system_id, component_id, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index); +} + +/** + * @brief Encode a mission_write_partial_list struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mission_write_partial_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_write_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list) +{ + return mavlink_msg_mission_write_partial_list_pack_chan(system_id, component_id, chan, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index); +} + +/** + * @brief Send a mission_write_partial_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + * @param end_index End index, equal or greater than start index. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_write_partial_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN]; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif +#else + mavlink_mission_write_partial_list_t packet; + packet.start_index = start_index; + packet.end_index = end_index; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_mission_write_partial_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int16_t(buf, 0, start_index); + _mav_put_int16_t(buf, 2, end_index); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif +#else + mavlink_mission_write_partial_list_t *packet = (mavlink_mission_write_partial_list_t *)msgbuf; + packet->start_index = start_index; + packet->end_index = end_index; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE MISSION_WRITE_PARTIAL_LIST UNPACKING + + +/** + * @brief Get field target_system from mission_write_partial_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from mission_write_partial_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field start_index from mission_write_partial_list message + * + * @return Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + */ +static inline int16_t mavlink_msg_mission_write_partial_list_get_start_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Get field end_index from mission_write_partial_list message + * + * @return End index, equal or greater than start index. + */ +static inline int16_t mavlink_msg_mission_write_partial_list_get_end_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 2); +} + +/** + * @brief Decode a mission_write_partial_list message into a struct + * + * @param msg The message to decode + * @param mission_write_partial_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_write_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_write_partial_list_t* mission_write_partial_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_write_partial_list->start_index = mavlink_msg_mission_write_partial_list_get_start_index(msg); + mission_write_partial_list->end_index = mavlink_msg_mission_write_partial_list_get_end_index(msg); + mission_write_partial_list->target_system = mavlink_msg_mission_write_partial_list_get_target_system(msg); + mission_write_partial_list->target_component = mavlink_msg_mission_write_partial_list_get_target_component(msg); +#else + memcpy(mission_write_partial_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_named_value_float.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_named_value_float.h new file mode 100644 index 0000000..a5c73a0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_named_value_float.h @@ -0,0 +1,249 @@ +// MESSAGE NAMED_VALUE_FLOAT PACKING + +#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251 + +typedef struct __mavlink_named_value_float_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float value; /*< Floating point value*/ + char name[10]; /*< Name of the debug variable*/ +} mavlink_named_value_float_t; + +#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18 +#define MAVLINK_MSG_ID_251_LEN 18 + +#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC 170 +#define MAVLINK_MSG_ID_251_CRC 170 + +#define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10 + +#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \ + "NAMED_VALUE_FLOAT", \ + 3, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \ + { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \ + } \ +} + + +/** + * @brief Pack a named_value_float message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Floating point value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, const char *name, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#else + mavlink_named_value_float_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif +} + +/** + * @brief Pack a named_value_float message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Floating point value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,const char *name,float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#else + mavlink_named_value_float_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif +} + +/** + * @brief Encode a named_value_float struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param named_value_float C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float) +{ + return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); +} + +/** + * @brief Encode a named_value_float struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param named_value_float C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_value_float_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float) +{ + return mavlink_msg_named_value_float_pack_chan(system_id, component_id, chan, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); +} + +/** + * @brief Send a named_value_float message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Floating point value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif +#else + mavlink_named_value_float_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_named_value_float_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif +#else + mavlink_named_value_float_t *packet = (mavlink_named_value_float_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->value = value; + mav_array_memcpy(packet->name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE NAMED_VALUE_FLOAT UNPACKING + + +/** + * @brief Get field time_boot_ms from named_value_float message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_named_value_float_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field name from named_value_float message + * + * @return Name of the debug variable + */ +static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 10, 8); +} + +/** + * @brief Get field value from named_value_float message + * + * @return Floating point value + */ +static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Decode a named_value_float message into a struct + * + * @param msg The message to decode + * @param named_value_float C-struct to decode the message contents into + */ +static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float) +{ +#if MAVLINK_NEED_BYTE_SWAP + named_value_float->time_boot_ms = mavlink_msg_named_value_float_get_time_boot_ms(msg); + named_value_float->value = mavlink_msg_named_value_float_get_value(msg); + mavlink_msg_named_value_float_get_name(msg, named_value_float->name); +#else + memcpy(named_value_float, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_named_value_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_named_value_int.h new file mode 100644 index 0000000..97177c7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_named_value_int.h @@ -0,0 +1,249 @@ +// MESSAGE NAMED_VALUE_INT PACKING + +#define MAVLINK_MSG_ID_NAMED_VALUE_INT 252 + +typedef struct __mavlink_named_value_int_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + int32_t value; /*< Signed integer value*/ + char name[10]; /*< Name of the debug variable*/ +} mavlink_named_value_int_t; + +#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18 +#define MAVLINK_MSG_ID_252_LEN 18 + +#define MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC 44 +#define MAVLINK_MSG_ID_252_CRC 44 + +#define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN 10 + +#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \ + "NAMED_VALUE_INT", \ + 3, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \ + { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \ + } \ +} + + +/** + * @brief Pack a named_value_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Signed integer value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, const char *name, int32_t value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#else + mavlink_named_value_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif +} + +/** + * @brief Pack a named_value_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Signed integer value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,const char *name,int32_t value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#else + mavlink_named_value_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif +} + +/** + * @brief Encode a named_value_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param named_value_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int) +{ + return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); +} + +/** + * @brief Encode a named_value_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param named_value_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_value_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int) +{ + return mavlink_msg_named_value_int_pack_chan(system_id, component_id, chan, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); +} + +/** + * @brief Send a named_value_int message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Signed integer value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, int32_t value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif +#else + mavlink_named_value_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + mav_array_memcpy(packet.name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_named_value_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, int32_t value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif +#else + mavlink_named_value_int_t *packet = (mavlink_named_value_int_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->value = value; + mav_array_memcpy(packet->name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE NAMED_VALUE_INT UNPACKING + + +/** + * @brief Get field time_boot_ms from named_value_int message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_named_value_int_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field name from named_value_int message + * + * @return Name of the debug variable + */ +static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 10, 8); +} + +/** + * @brief Get field value from named_value_int message + * + * @return Signed integer value + */ +static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Decode a named_value_int message into a struct + * + * @param msg The message to decode + * @param named_value_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* msg, mavlink_named_value_int_t* named_value_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + named_value_int->time_boot_ms = mavlink_msg_named_value_int_get_time_boot_ms(msg); + named_value_int->value = mavlink_msg_named_value_int_get_value(msg); + mavlink_msg_named_value_int_get_name(msg, named_value_int->name); +#else + memcpy(named_value_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h new file mode 100644 index 0000000..1691d58 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h @@ -0,0 +1,377 @@ +// MESSAGE NAV_CONTROLLER_OUTPUT PACKING + +#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62 + +typedef struct __mavlink_nav_controller_output_t +{ + float nav_roll; /*< Current desired roll in degrees*/ + float nav_pitch; /*< Current desired pitch in degrees*/ + float alt_error; /*< Current altitude error in meters*/ + float aspd_error; /*< Current airspeed error in meters/second*/ + float xtrack_error; /*< Current crosstrack error on x-y plane in meters*/ + int16_t nav_bearing; /*< Current desired heading in degrees*/ + int16_t target_bearing; /*< Bearing to current MISSION/target in degrees*/ + uint16_t wp_dist; /*< Distance to active MISSION in meters*/ +} mavlink_nav_controller_output_t; + +#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26 +#define MAVLINK_MSG_ID_62_LEN 26 + +#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC 183 +#define MAVLINK_MSG_ID_62_CRC 183 + + + +#define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \ + "NAV_CONTROLLER_OUTPUT", \ + 8, \ + { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ + { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ + { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ + { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ + { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ + { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ + { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ + { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ + } \ +} + + +/** + * @brief Pack a nav_controller_output message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param nav_roll Current desired roll in degrees + * @param nav_pitch Current desired pitch in degrees + * @param nav_bearing Current desired heading in degrees + * @param target_bearing Bearing to current MISSION/target in degrees + * @param wp_dist Distance to active MISSION in meters + * @param alt_error Current altitude error in meters + * @param aspd_error Current airspeed error in meters/second + * @param xtrack_error Current crosstrack error on x-y plane in meters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; + _mav_put_float(buf, 0, nav_roll); + _mav_put_float(buf, 4, nav_pitch); + _mav_put_float(buf, 8, alt_error); + _mav_put_float(buf, 12, aspd_error); + _mav_put_float(buf, 16, xtrack_error); + _mav_put_int16_t(buf, 20, nav_bearing); + _mav_put_int16_t(buf, 22, target_bearing); + _mav_put_uint16_t(buf, 24, wp_dist); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#else + mavlink_nav_controller_output_t packet; + packet.nav_roll = nav_roll; + packet.nav_pitch = nav_pitch; + packet.alt_error = alt_error; + packet.aspd_error = aspd_error; + packet.xtrack_error = xtrack_error; + packet.nav_bearing = nav_bearing; + packet.target_bearing = target_bearing; + packet.wp_dist = wp_dist; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif +} + +/** + * @brief Pack a nav_controller_output message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param nav_roll Current desired roll in degrees + * @param nav_pitch Current desired pitch in degrees + * @param nav_bearing Current desired heading in degrees + * @param target_bearing Bearing to current MISSION/target in degrees + * @param wp_dist Distance to active MISSION in meters + * @param alt_error Current altitude error in meters + * @param aspd_error Current airspeed error in meters/second + * @param xtrack_error Current crosstrack error on x-y plane in meters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float nav_roll,float nav_pitch,int16_t nav_bearing,int16_t target_bearing,uint16_t wp_dist,float alt_error,float aspd_error,float xtrack_error) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; + _mav_put_float(buf, 0, nav_roll); + _mav_put_float(buf, 4, nav_pitch); + _mav_put_float(buf, 8, alt_error); + _mav_put_float(buf, 12, aspd_error); + _mav_put_float(buf, 16, xtrack_error); + _mav_put_int16_t(buf, 20, nav_bearing); + _mav_put_int16_t(buf, 22, target_bearing); + _mav_put_uint16_t(buf, 24, wp_dist); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#else + mavlink_nav_controller_output_t packet; + packet.nav_roll = nav_roll; + packet.nav_pitch = nav_pitch; + packet.alt_error = alt_error; + packet.aspd_error = aspd_error; + packet.xtrack_error = xtrack_error; + packet.nav_bearing = nav_bearing; + packet.target_bearing = target_bearing; + packet.wp_dist = wp_dist; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif +} + +/** + * @brief Encode a nav_controller_output struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param nav_controller_output C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) +{ + return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); +} + +/** + * @brief Encode a nav_controller_output struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param nav_controller_output C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_nav_controller_output_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) +{ + return mavlink_msg_nav_controller_output_pack_chan(system_id, component_id, chan, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); +} + +/** + * @brief Send a nav_controller_output message + * @param chan MAVLink channel to send the message + * + * @param nav_roll Current desired roll in degrees + * @param nav_pitch Current desired pitch in degrees + * @param nav_bearing Current desired heading in degrees + * @param target_bearing Bearing to current MISSION/target in degrees + * @param wp_dist Distance to active MISSION in meters + * @param alt_error Current altitude error in meters + * @param aspd_error Current airspeed error in meters/second + * @param xtrack_error Current crosstrack error on x-y plane in meters + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; + _mav_put_float(buf, 0, nav_roll); + _mav_put_float(buf, 4, nav_pitch); + _mav_put_float(buf, 8, alt_error); + _mav_put_float(buf, 12, aspd_error); + _mav_put_float(buf, 16, xtrack_error); + _mav_put_int16_t(buf, 20, nav_bearing); + _mav_put_int16_t(buf, 22, target_bearing); + _mav_put_uint16_t(buf, 24, wp_dist); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif +#else + mavlink_nav_controller_output_t packet; + packet.nav_roll = nav_roll; + packet.nav_pitch = nav_pitch; + packet.alt_error = alt_error; + packet.aspd_error = aspd_error; + packet.xtrack_error = xtrack_error; + packet.nav_bearing = nav_bearing; + packet.target_bearing = target_bearing; + packet.wp_dist = wp_dist; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_nav_controller_output_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, nav_roll); + _mav_put_float(buf, 4, nav_pitch); + _mav_put_float(buf, 8, alt_error); + _mav_put_float(buf, 12, aspd_error); + _mav_put_float(buf, 16, xtrack_error); + _mav_put_int16_t(buf, 20, nav_bearing); + _mav_put_int16_t(buf, 22, target_bearing); + _mav_put_uint16_t(buf, 24, wp_dist); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif +#else + mavlink_nav_controller_output_t *packet = (mavlink_nav_controller_output_t *)msgbuf; + packet->nav_roll = nav_roll; + packet->nav_pitch = nav_pitch; + packet->alt_error = alt_error; + packet->aspd_error = aspd_error; + packet->xtrack_error = xtrack_error; + packet->nav_bearing = nav_bearing; + packet->target_bearing = target_bearing; + packet->wp_dist = wp_dist; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE NAV_CONTROLLER_OUTPUT UNPACKING + + +/** + * @brief Get field nav_roll from nav_controller_output message + * + * @return Current desired roll in degrees + */ +static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field nav_pitch from nav_controller_output message + * + * @return Current desired pitch in degrees + */ +static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field nav_bearing from nav_controller_output message + * + * @return Current desired heading in degrees + */ +static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field target_bearing from nav_controller_output message + * + * @return Bearing to current MISSION/target in degrees + */ +static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field wp_dist from nav_controller_output message + * + * @return Distance to active MISSION in meters + */ +static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field alt_error from nav_controller_output message + * + * @return Current altitude error in meters + */ +static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field aspd_error from nav_controller_output message + * + * @return Current airspeed error in meters/second + */ +static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field xtrack_error from nav_controller_output message + * + * @return Current crosstrack error on x-y plane in meters + */ +static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a nav_controller_output message into a struct + * + * @param msg The message to decode + * @param nav_controller_output C-struct to decode the message contents into + */ +static inline void mavlink_msg_nav_controller_output_decode(const mavlink_message_t* msg, mavlink_nav_controller_output_t* nav_controller_output) +{ +#if MAVLINK_NEED_BYTE_SWAP + nav_controller_output->nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg); + nav_controller_output->nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg); + nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg); + nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg); + nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg); + nav_controller_output->nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg); + nav_controller_output->target_bearing = mavlink_msg_nav_controller_output_get_target_bearing(msg); + nav_controller_output->wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg); +#else + memcpy(nav_controller_output, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_optical_flow.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_optical_flow.h new file mode 100644 index 0000000..69d8493 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_optical_flow.h @@ -0,0 +1,377 @@ +// MESSAGE OPTICAL_FLOW PACKING + +#define MAVLINK_MSG_ID_OPTICAL_FLOW 100 + +typedef struct __mavlink_optical_flow_t +{ + uint64_t time_usec; /*< Timestamp (UNIX)*/ + float flow_comp_m_x; /*< Flow in meters in x-sensor direction, angular-speed compensated*/ + float flow_comp_m_y; /*< Flow in meters in y-sensor direction, angular-speed compensated*/ + float ground_distance; /*< Ground distance in meters. Positive value: distance known. Negative value: Unknown distance*/ + int16_t flow_x; /*< Flow in pixels * 10 in x-sensor direction (dezi-pixels)*/ + int16_t flow_y; /*< Flow in pixels * 10 in y-sensor direction (dezi-pixels)*/ + uint8_t sensor_id; /*< Sensor ID*/ + uint8_t quality; /*< Optical flow quality / confidence. 0: bad, 255: maximum quality*/ +} mavlink_optical_flow_t; + +#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26 +#define MAVLINK_MSG_ID_100_LEN 26 + +#define MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175 +#define MAVLINK_MSG_ID_100_CRC 175 + + + +#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \ + "OPTICAL_FLOW", \ + 8, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \ + { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ + { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ + { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ + { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \ + { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ + { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \ + } \ +} + + +/** + * @brief Pack a optical_flow message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (UNIX) + * @param sensor_id Sensor ID + * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) + * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) + * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated + * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated + * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality + * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, flow_comp_m_x); + _mav_put_float(buf, 12, flow_comp_m_y); + _mav_put_float(buf, 16, ground_distance); + _mav_put_int16_t(buf, 20, flow_x); + _mav_put_int16_t(buf, 22, flow_y); + _mav_put_uint8_t(buf, 24, sensor_id); + _mav_put_uint8_t(buf, 25, quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#else + mavlink_optical_flow_t packet; + packet.time_usec = time_usec; + packet.flow_comp_m_x = flow_comp_m_x; + packet.flow_comp_m_y = flow_comp_m_y; + packet.ground_distance = ground_distance; + packet.flow_x = flow_x; + packet.flow_y = flow_y; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif +} + +/** + * @brief Pack a optical_flow message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (UNIX) + * @param sensor_id Sensor ID + * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) + * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) + * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated + * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated + * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality + * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,float flow_comp_m_x,float flow_comp_m_y,uint8_t quality,float ground_distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, flow_comp_m_x); + _mav_put_float(buf, 12, flow_comp_m_y); + _mav_put_float(buf, 16, ground_distance); + _mav_put_int16_t(buf, 20, flow_x); + _mav_put_int16_t(buf, 22, flow_y); + _mav_put_uint8_t(buf, 24, sensor_id); + _mav_put_uint8_t(buf, 25, quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#else + mavlink_optical_flow_t packet; + packet.time_usec = time_usec; + packet.flow_comp_m_x = flow_comp_m_x; + packet.flow_comp_m_y = flow_comp_m_y; + packet.ground_distance = ground_distance; + packet.flow_x = flow_x; + packet.flow_y = flow_y; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif +} + +/** + * @brief Encode a optical_flow struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param optical_flow C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow) +{ + return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance); +} + +/** + * @brief Encode a optical_flow struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param optical_flow C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow) +{ + return mavlink_msg_optical_flow_pack_chan(system_id, component_id, chan, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance); +} + +/** + * @brief Send a optical_flow message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (UNIX) + * @param sensor_id Sensor ID + * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) + * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) + * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated + * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated + * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality + * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, flow_comp_m_x); + _mav_put_float(buf, 12, flow_comp_m_y); + _mav_put_float(buf, 16, ground_distance); + _mav_put_int16_t(buf, 20, flow_x); + _mav_put_int16_t(buf, 22, flow_y); + _mav_put_uint8_t(buf, 24, sensor_id); + _mav_put_uint8_t(buf, 25, quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif +#else + mavlink_optical_flow_t packet; + packet.time_usec = time_usec; + packet.flow_comp_m_x = flow_comp_m_x; + packet.flow_comp_m_y = flow_comp_m_y; + packet.ground_distance = ground_distance; + packet.flow_x = flow_x; + packet.flow_y = flow_y; + packet.sensor_id = sensor_id; + packet.quality = quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, flow_comp_m_x); + _mav_put_float(buf, 12, flow_comp_m_y); + _mav_put_float(buf, 16, ground_distance); + _mav_put_int16_t(buf, 20, flow_x); + _mav_put_int16_t(buf, 22, flow_y); + _mav_put_uint8_t(buf, 24, sensor_id); + _mav_put_uint8_t(buf, 25, quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif +#else + mavlink_optical_flow_t *packet = (mavlink_optical_flow_t *)msgbuf; + packet->time_usec = time_usec; + packet->flow_comp_m_x = flow_comp_m_x; + packet->flow_comp_m_y = flow_comp_m_y; + packet->ground_distance = ground_distance; + packet->flow_x = flow_x; + packet->flow_y = flow_y; + packet->sensor_id = sensor_id; + packet->quality = quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE OPTICAL_FLOW UNPACKING + + +/** + * @brief Get field time_usec from optical_flow message + * + * @return Timestamp (UNIX) + */ +static inline uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field sensor_id from optical_flow message + * + * @return Sensor ID + */ +static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field flow_x from optical_flow message + * + * @return Flow in pixels * 10 in x-sensor direction (dezi-pixels) + */ +static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field flow_y from optical_flow message + * + * @return Flow in pixels * 10 in y-sensor direction (dezi-pixels) + */ +static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field flow_comp_m_x from optical_flow message + * + * @return Flow in meters in x-sensor direction, angular-speed compensated + */ +static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field flow_comp_m_y from optical_flow message + * + * @return Flow in meters in y-sensor direction, angular-speed compensated + */ +static inline float mavlink_msg_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field quality from optical_flow message + * + * @return Optical flow quality / confidence. 0: bad, 255: maximum quality + */ +static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 25); +} + +/** + * @brief Get field ground_distance from optical_flow message + * + * @return Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + */ +static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a optical_flow message into a struct + * + * @param msg The message to decode + * @param optical_flow C-struct to decode the message contents into + */ +static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, mavlink_optical_flow_t* optical_flow) +{ +#if MAVLINK_NEED_BYTE_SWAP + optical_flow->time_usec = mavlink_msg_optical_flow_get_time_usec(msg); + optical_flow->flow_comp_m_x = mavlink_msg_optical_flow_get_flow_comp_m_x(msg); + optical_flow->flow_comp_m_y = mavlink_msg_optical_flow_get_flow_comp_m_y(msg); + optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg); + optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg); + optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg); + optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg); + optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg); +#else + memcpy(optical_flow, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_optical_flow_rad.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_optical_flow_rad.h new file mode 100644 index 0000000..7d07703 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_optical_flow_rad.h @@ -0,0 +1,473 @@ +// MESSAGE OPTICAL_FLOW_RAD PACKING + +#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD 106 + +typedef struct __mavlink_optical_flow_rad_t +{ + uint64_t time_usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + uint32_t integration_time_us; /*< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/ + float integrated_x; /*< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/ + float integrated_y; /*< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/ + float integrated_xgyro; /*< RH rotation around X axis (rad)*/ + float integrated_ygyro; /*< RH rotation around Y axis (rad)*/ + float integrated_zgyro; /*< RH rotation around Z axis (rad)*/ + uint32_t time_delta_distance_us; /*< Time in microseconds since the distance was sampled.*/ + float distance; /*< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.*/ + int16_t temperature; /*< Temperature * 100 in centi-degrees Celsius*/ + uint8_t sensor_id; /*< Sensor ID*/ + uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/ +} mavlink_optical_flow_rad_t; + +#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN 44 +#define MAVLINK_MSG_ID_106_LEN 44 + +#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC 138 +#define MAVLINK_MSG_ID_106_CRC 138 + + + +#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD { \ + "OPTICAL_FLOW_RAD", \ + 12, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_rad_t, time_usec) }, \ + { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_optical_flow_rad_t, integration_time_us) }, \ + { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_rad_t, integrated_x) }, \ + { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_rad_t, integrated_y) }, \ + { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_optical_flow_rad_t, integrated_xgyro) }, \ + { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_optical_flow_rad_t, integrated_ygyro) }, \ + { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_optical_flow_rad_t, integrated_zgyro) }, \ + { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_optical_flow_rad_t, time_delta_distance_us) }, \ + { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_optical_flow_rad_t, distance) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \ + { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \ + } \ +} + + +/** + * @brief Pack a optical_flow_rad message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param sensor_id Sensor ID + * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro RH rotation around X axis (rad) + * @param integrated_ygyro RH rotation around Y axis (rad) + * @param integrated_zgyro RH rotation around Z axis (rad) + * @param temperature Temperature * 100 in centi-degrees Celsius + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us Time in microseconds since the distance was sampled. + * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_optical_flow_rad_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#else + mavlink_optical_flow_rad_t packet; + packet.time_usec = time_usec; + packet.integration_time_us = integration_time_us; + packet.integrated_x = integrated_x; + packet.integrated_y = integrated_y; + packet.integrated_xgyro = integrated_xgyro; + packet.integrated_ygyro = integrated_ygyro; + packet.integrated_zgyro = integrated_zgyro; + packet.time_delta_distance_us = time_delta_distance_us; + packet.distance = distance; + packet.temperature = temperature; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW_RAD; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif +} + +/** + * @brief Pack a optical_flow_rad message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param sensor_id Sensor ID + * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro RH rotation around X axis (rad) + * @param integrated_ygyro RH rotation around Y axis (rad) + * @param integrated_zgyro RH rotation around Z axis (rad) + * @param temperature Temperature * 100 in centi-degrees Celsius + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us Time in microseconds since the distance was sampled. + * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_optical_flow_rad_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t sensor_id,uint32_t integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,int16_t temperature,uint8_t quality,uint32_t time_delta_distance_us,float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#else + mavlink_optical_flow_rad_t packet; + packet.time_usec = time_usec; + packet.integration_time_us = integration_time_us; + packet.integrated_x = integrated_x; + packet.integrated_y = integrated_y; + packet.integrated_xgyro = integrated_xgyro; + packet.integrated_ygyro = integrated_ygyro; + packet.integrated_zgyro = integrated_zgyro; + packet.time_delta_distance_us = time_delta_distance_us; + packet.distance = distance; + packet.temperature = temperature; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW_RAD; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif +} + +/** + * @brief Encode a optical_flow_rad struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param optical_flow_rad C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_optical_flow_rad_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_rad_t* optical_flow_rad) +{ + return mavlink_msg_optical_flow_rad_pack(system_id, component_id, msg, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance); +} + +/** + * @brief Encode a optical_flow_rad struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param optical_flow_rad C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_optical_flow_rad_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_rad_t* optical_flow_rad) +{ + return mavlink_msg_optical_flow_rad_pack_chan(system_id, component_id, chan, msg, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance); +} + +/** + * @brief Send a optical_flow_rad message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param sensor_id Sensor ID + * @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + * @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + * @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + * @param integrated_xgyro RH rotation around X axis (rad) + * @param integrated_ygyro RH rotation around Y axis (rad) + * @param integrated_zgyro RH rotation around Z axis (rad) + * @param temperature Temperature * 100 in centi-degrees Celsius + * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + * @param time_delta_distance_us Time in microseconds since the distance was sampled. + * @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_optical_flow_rad_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif +#else + mavlink_optical_flow_rad_t packet; + packet.time_usec = time_usec; + packet.integration_time_us = integration_time_us; + packet.integrated_x = integrated_x; + packet.integrated_y = integrated_y; + packet.integrated_xgyro = integrated_xgyro; + packet.integrated_ygyro = integrated_ygyro; + packet.integrated_zgyro = integrated_zgyro; + packet.time_delta_distance_us = time_delta_distance_us; + packet.distance = distance; + packet.temperature = temperature; + packet.sensor_id = sensor_id; + packet.quality = quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_optical_flow_rad_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, integration_time_us); + _mav_put_float(buf, 12, integrated_x); + _mav_put_float(buf, 16, integrated_y); + _mav_put_float(buf, 20, integrated_xgyro); + _mav_put_float(buf, 24, integrated_ygyro); + _mav_put_float(buf, 28, integrated_zgyro); + _mav_put_uint32_t(buf, 32, time_delta_distance_us); + _mav_put_float(buf, 36, distance); + _mav_put_int16_t(buf, 40, temperature); + _mav_put_uint8_t(buf, 42, sensor_id); + _mav_put_uint8_t(buf, 43, quality); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif +#else + mavlink_optical_flow_rad_t *packet = (mavlink_optical_flow_rad_t *)msgbuf; + packet->time_usec = time_usec; + packet->integration_time_us = integration_time_us; + packet->integrated_x = integrated_x; + packet->integrated_y = integrated_y; + packet->integrated_xgyro = integrated_xgyro; + packet->integrated_ygyro = integrated_ygyro; + packet->integrated_zgyro = integrated_zgyro; + packet->time_delta_distance_us = time_delta_distance_us; + packet->distance = distance; + packet->temperature = temperature; + packet->sensor_id = sensor_id; + packet->quality = quality; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE OPTICAL_FLOW_RAD UNPACKING + + +/** + * @brief Get field time_usec from optical_flow_rad message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_optical_flow_rad_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field sensor_id from optical_flow_rad message + * + * @return Sensor ID + */ +static inline uint8_t mavlink_msg_optical_flow_rad_get_sensor_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 42); +} + +/** + * @brief Get field integration_time_us from optical_flow_rad message + * + * @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + */ +static inline uint32_t mavlink_msg_optical_flow_rad_get_integration_time_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field integrated_x from optical_flow_rad message + * + * @return Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + */ +static inline float mavlink_msg_optical_flow_rad_get_integrated_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field integrated_y from optical_flow_rad message + * + * @return Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + */ +static inline float mavlink_msg_optical_flow_rad_get_integrated_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field integrated_xgyro from optical_flow_rad message + * + * @return RH rotation around X axis (rad) + */ +static inline float mavlink_msg_optical_flow_rad_get_integrated_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field integrated_ygyro from optical_flow_rad message + * + * @return RH rotation around Y axis (rad) + */ +static inline float mavlink_msg_optical_flow_rad_get_integrated_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field integrated_zgyro from optical_flow_rad message + * + * @return RH rotation around Z axis (rad) + */ +static inline float mavlink_msg_optical_flow_rad_get_integrated_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field temperature from optical_flow_rad message + * + * @return Temperature * 100 in centi-degrees Celsius + */ +static inline int16_t mavlink_msg_optical_flow_rad_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 40); +} + +/** + * @brief Get field quality from optical_flow_rad message + * + * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + */ +static inline uint8_t mavlink_msg_optical_flow_rad_get_quality(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 43); +} + +/** + * @brief Get field time_delta_distance_us from optical_flow_rad message + * + * @return Time in microseconds since the distance was sampled. + */ +static inline uint32_t mavlink_msg_optical_flow_rad_get_time_delta_distance_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 32); +} + +/** + * @brief Get field distance from optical_flow_rad message + * + * @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + */ +static inline float mavlink_msg_optical_flow_rad_get_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Decode a optical_flow_rad message into a struct + * + * @param msg The message to decode + * @param optical_flow_rad C-struct to decode the message contents into + */ +static inline void mavlink_msg_optical_flow_rad_decode(const mavlink_message_t* msg, mavlink_optical_flow_rad_t* optical_flow_rad) +{ +#if MAVLINK_NEED_BYTE_SWAP + optical_flow_rad->time_usec = mavlink_msg_optical_flow_rad_get_time_usec(msg); + optical_flow_rad->integration_time_us = mavlink_msg_optical_flow_rad_get_integration_time_us(msg); + optical_flow_rad->integrated_x = mavlink_msg_optical_flow_rad_get_integrated_x(msg); + optical_flow_rad->integrated_y = mavlink_msg_optical_flow_rad_get_integrated_y(msg); + optical_flow_rad->integrated_xgyro = mavlink_msg_optical_flow_rad_get_integrated_xgyro(msg); + optical_flow_rad->integrated_ygyro = mavlink_msg_optical_flow_rad_get_integrated_ygyro(msg); + optical_flow_rad->integrated_zgyro = mavlink_msg_optical_flow_rad_get_integrated_zgyro(msg); + optical_flow_rad->time_delta_distance_us = mavlink_msg_optical_flow_rad_get_time_delta_distance_us(msg); + optical_flow_rad->distance = mavlink_msg_optical_flow_rad_get_distance(msg); + optical_flow_rad->temperature = mavlink_msg_optical_flow_rad_get_temperature(msg); + optical_flow_rad->sensor_id = mavlink_msg_optical_flow_rad_get_sensor_id(msg); + optical_flow_rad->quality = mavlink_msg_optical_flow_rad_get_quality(msg); +#else + memcpy(optical_flow_rad, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_param_map_rc.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_param_map_rc.h new file mode 100644 index 0000000..e4b7483 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_param_map_rc.h @@ -0,0 +1,393 @@ +// MESSAGE PARAM_MAP_RC PACKING + +#define MAVLINK_MSG_ID_PARAM_MAP_RC 50 + +typedef struct __mavlink_param_map_rc_t +{ + float param_value0; /*< Initial parameter value*/ + float scale; /*< Scale, maps the RC range [-1, 1] to a parameter value*/ + float param_value_min; /*< Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)*/ + float param_value_max; /*< Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)*/ + int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ + uint8_t parameter_rc_channel_index; /*< Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.*/ +} mavlink_param_map_rc_t; + +#define MAVLINK_MSG_ID_PARAM_MAP_RC_LEN 37 +#define MAVLINK_MSG_ID_50_LEN 37 + +#define MAVLINK_MSG_ID_PARAM_MAP_RC_CRC 78 +#define MAVLINK_MSG_ID_50_CRC 78 + +#define MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN 16 + +#define MAVLINK_MESSAGE_INFO_PARAM_MAP_RC { \ + "PARAM_MAP_RC", \ + 9, \ + { { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \ + { "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \ + { "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \ + { "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \ + { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \ + { "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \ + } \ +} + + +/** + * @brief Pack a param_map_rc message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. + * @param param_value0 Initial parameter value + * @param scale Scale, maps the RC range [-1, 1] to a parameter value + * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_map_rc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN]; + _mav_put_float(buf, 0, param_value0); + _mav_put_float(buf, 4, scale); + _mav_put_float(buf, 8, param_value_min); + _mav_put_float(buf, 12, param_value_max); + _mav_put_int16_t(buf, 16, param_index); + _mav_put_uint8_t(buf, 18, target_system); + _mav_put_uint8_t(buf, 19, target_component); + _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); + _mav_put_char_array(buf, 20, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#else + mavlink_param_map_rc_t packet; + packet.param_value0 = param_value0; + packet.scale = scale; + packet.param_value_min = param_value_min; + packet.param_value_max = param_value_max; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + packet.parameter_rc_channel_index = parameter_rc_channel_index; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_MAP_RC; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif +} + +/** + * @brief Pack a param_map_rc message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. + * @param param_value0 Initial parameter value + * @param scale Scale, maps the RC range [-1, 1] to a parameter value + * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_map_rc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index,uint8_t parameter_rc_channel_index,float param_value0,float scale,float param_value_min,float param_value_max) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN]; + _mav_put_float(buf, 0, param_value0); + _mav_put_float(buf, 4, scale); + _mav_put_float(buf, 8, param_value_min); + _mav_put_float(buf, 12, param_value_max); + _mav_put_int16_t(buf, 16, param_index); + _mav_put_uint8_t(buf, 18, target_system); + _mav_put_uint8_t(buf, 19, target_component); + _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); + _mav_put_char_array(buf, 20, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#else + mavlink_param_map_rc_t packet; + packet.param_value0 = param_value0; + packet.scale = scale; + packet.param_value_min = param_value_min; + packet.param_value_max = param_value_max; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + packet.parameter_rc_channel_index = parameter_rc_channel_index; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_MAP_RC; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif +} + +/** + * @brief Encode a param_map_rc struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_map_rc C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_map_rc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_map_rc_t* param_map_rc) +{ + return mavlink_msg_param_map_rc_pack(system_id, component_id, msg, param_map_rc->target_system, param_map_rc->target_component, param_map_rc->param_id, param_map_rc->param_index, param_map_rc->parameter_rc_channel_index, param_map_rc->param_value0, param_map_rc->scale, param_map_rc->param_value_min, param_map_rc->param_value_max); +} + +/** + * @brief Encode a param_map_rc struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param param_map_rc C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_map_rc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_map_rc_t* param_map_rc) +{ + return mavlink_msg_param_map_rc_pack_chan(system_id, component_id, chan, msg, param_map_rc->target_system, param_map_rc->target_component, param_map_rc->param_id, param_map_rc->param_index, param_map_rc->parameter_rc_channel_index, param_map_rc->param_value0, param_map_rc->scale, param_map_rc->param_value_min, param_map_rc->param_value_max); +} + +/** + * @brief Send a param_map_rc message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. + * @param param_value0 Initial parameter value + * @param scale Scale, maps the RC range [-1, 1] to a parameter value + * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_map_rc_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN]; + _mav_put_float(buf, 0, param_value0); + _mav_put_float(buf, 4, scale); + _mav_put_float(buf, 8, param_value_min); + _mav_put_float(buf, 12, param_value_max); + _mav_put_int16_t(buf, 16, param_index); + _mav_put_uint8_t(buf, 18, target_system); + _mav_put_uint8_t(buf, 19, target_component); + _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); + _mav_put_char_array(buf, 20, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif +#else + mavlink_param_map_rc_t packet; + packet.param_value0 = param_value0; + packet.scale = scale; + packet.param_value_min = param_value_min; + packet.param_value_max = param_value_max; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + packet.parameter_rc_channel_index = parameter_rc_channel_index; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)&packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)&packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_PARAM_MAP_RC_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_param_map_rc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, param_value0); + _mav_put_float(buf, 4, scale); + _mav_put_float(buf, 8, param_value_min); + _mav_put_float(buf, 12, param_value_max); + _mav_put_int16_t(buf, 16, param_index); + _mav_put_uint8_t(buf, 18, target_system); + _mav_put_uint8_t(buf, 19, target_component); + _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); + _mav_put_char_array(buf, 20, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif +#else + mavlink_param_map_rc_t *packet = (mavlink_param_map_rc_t *)msgbuf; + packet->param_value0 = param_value0; + packet->scale = scale; + packet->param_value_min = param_value_min; + packet->param_value_max = param_value_max; + packet->param_index = param_index; + packet->target_system = target_system; + packet->target_component = target_component; + packet->parameter_rc_channel_index = parameter_rc_channel_index; + mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE PARAM_MAP_RC UNPACKING + + +/** + * @brief Get field target_system from param_map_rc message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_map_rc_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 18); +} + +/** + * @brief Get field target_component from param_map_rc message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_map_rc_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 19); +} + +/** + * @brief Get field param_id from param_map_rc message + * + * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + */ +static inline uint16_t mavlink_msg_param_map_rc_get_param_id(const mavlink_message_t* msg, char *param_id) +{ + return _MAV_RETURN_char_array(msg, param_id, 16, 20); +} + +/** + * @brief Get field param_index from param_map_rc message + * + * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + */ +static inline int16_t mavlink_msg_param_map_rc_get_param_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field parameter_rc_channel_index from param_map_rc message + * + * @return Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. + */ +static inline uint8_t mavlink_msg_param_map_rc_get_parameter_rc_channel_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Get field param_value0 from param_map_rc message + * + * @return Initial parameter value + */ +static inline float mavlink_msg_param_map_rc_get_param_value0(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field scale from param_map_rc message + * + * @return Scale, maps the RC range [-1, 1] to a parameter value + */ +static inline float mavlink_msg_param_map_rc_get_scale(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param_value_min from param_map_rc message + * + * @return Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + */ +static inline float mavlink_msg_param_map_rc_get_param_value_min(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param_value_max from param_map_rc message + * + * @return Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + */ +static inline float mavlink_msg_param_map_rc_get_param_value_max(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a param_map_rc message into a struct + * + * @param msg The message to decode + * @param param_map_rc C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_map_rc_decode(const mavlink_message_t* msg, mavlink_param_map_rc_t* param_map_rc) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_map_rc->param_value0 = mavlink_msg_param_map_rc_get_param_value0(msg); + param_map_rc->scale = mavlink_msg_param_map_rc_get_scale(msg); + param_map_rc->param_value_min = mavlink_msg_param_map_rc_get_param_value_min(msg); + param_map_rc->param_value_max = mavlink_msg_param_map_rc_get_param_value_max(msg); + param_map_rc->param_index = mavlink_msg_param_map_rc_get_param_index(msg); + param_map_rc->target_system = mavlink_msg_param_map_rc_get_target_system(msg); + param_map_rc->target_component = mavlink_msg_param_map_rc_get_target_component(msg); + mavlink_msg_param_map_rc_get_param_id(msg, param_map_rc->param_id); + param_map_rc->parameter_rc_channel_index = mavlink_msg_param_map_rc_get_parameter_rc_channel_index(msg); +#else + memcpy(param_map_rc, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_param_request_list.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_param_request_list.h new file mode 100644 index 0000000..f78f049 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_param_request_list.h @@ -0,0 +1,233 @@ +// MESSAGE PARAM_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21 + +typedef struct __mavlink_param_request_list_t +{ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_param_request_list_t; + +#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2 +#define MAVLINK_MSG_ID_21_LEN 2 + +#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC 159 +#define MAVLINK_MSG_ID_21_CRC 159 + + + +#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \ + "PARAM_REQUEST_LIST", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a param_request_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#else + mavlink_param_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif +} + +/** + * @brief Pack a param_request_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#else + mavlink_param_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif +} + +/** + * @brief Encode a param_request_list struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) +{ + return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component); +} + +/** + * @brief Encode a param_request_list struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param param_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) +{ + return mavlink_msg_param_request_list_pack_chan(system_id, component_id, chan, msg, param_request_list->target_system, param_request_list->target_component); +} + +/** + * @brief Send a param_request_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif +#else + mavlink_param_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_param_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif +#else + mavlink_param_request_list_t *packet = (mavlink_param_request_list_t *)msgbuf; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE PARAM_REQUEST_LIST UNPACKING + + +/** + * @brief Get field target_system from param_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from param_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_request_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a param_request_list message into a struct + * + * @param msg The message to decode + * @param param_request_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t* msg, mavlink_param_request_list_t* param_request_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_request_list->target_system = mavlink_msg_param_request_list_get_target_system(msg); + param_request_list->target_component = mavlink_msg_param_request_list_get_target_component(msg); +#else + memcpy(param_request_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_param_request_read.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_param_request_read.h new file mode 100644 index 0000000..497f598 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_param_request_read.h @@ -0,0 +1,273 @@ +// MESSAGE PARAM_REQUEST_READ PACKING + +#define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20 + +typedef struct __mavlink_param_request_read_t +{ + int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ +} mavlink_param_request_read_t; + +#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20 +#define MAVLINK_MSG_ID_20_LEN 20 + +#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC 214 +#define MAVLINK_MSG_ID_20_CRC 214 + +#define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 16 + +#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \ + "PARAM_REQUEST_READ", \ + 4, \ + { { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \ + } \ +} + + +/** + * @brief Pack a param_request_read message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN]; + _mav_put_int16_t(buf, 0, param_index); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_char_array(buf, 4, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#else + mavlink_param_request_read_t packet; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif +} + +/** + * @brief Pack a param_request_read message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN]; + _mav_put_int16_t(buf, 0, param_index); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_char_array(buf, 4, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#else + mavlink_param_request_read_t packet; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif +} + +/** + * @brief Encode a param_request_read struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_request_read C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) +{ + return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); +} + +/** + * @brief Encode a param_request_read struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param param_request_read C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_request_read_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) +{ + return mavlink_msg_param_request_read_pack_chan(system_id, component_id, chan, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); +} + +/** + * @brief Send a param_request_read message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN]; + _mav_put_int16_t(buf, 0, param_index); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_char_array(buf, 4, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif +#else + mavlink_param_request_read_t packet; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_param_request_read_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int16_t(buf, 0, param_index); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_char_array(buf, 4, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif +#else + mavlink_param_request_read_t *packet = (mavlink_param_request_read_t *)msgbuf; + packet->param_index = param_index; + packet->target_system = target_system; + packet->target_component = target_component; + mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE PARAM_REQUEST_READ UNPACKING + + +/** + * @brief Get field target_system from param_request_read message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from param_request_read message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field param_id from param_request_read message + * + * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + */ +static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, char *param_id) +{ + return _MAV_RETURN_char_array(msg, param_id, 16, 4); +} + +/** + * @brief Get field param_index from param_request_read message + * + * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + */ +static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Decode a param_request_read message into a struct + * + * @param msg The message to decode + * @param param_request_read C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_request_read->param_index = mavlink_msg_param_request_read_get_param_index(msg); + param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg); + param_request_read->target_component = mavlink_msg_param_request_read_get_target_component(msg); + mavlink_msg_param_request_read_get_param_id(msg, param_request_read->param_id); +#else + memcpy(param_request_read, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_param_set.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_param_set.h new file mode 100644 index 0000000..471e674 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_param_set.h @@ -0,0 +1,297 @@ +// MESSAGE PARAM_SET PACKING + +#define MAVLINK_MSG_ID_PARAM_SET 23 + +typedef struct __mavlink_param_set_t +{ + float param_value; /*< Onboard parameter value*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ + uint8_t param_type; /*< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.*/ +} mavlink_param_set_t; + +#define MAVLINK_MSG_ID_PARAM_SET_LEN 23 +#define MAVLINK_MSG_ID_23_LEN 23 + +#define MAVLINK_MSG_ID_PARAM_SET_CRC 168 +#define MAVLINK_MSG_ID_23_CRC 168 + +#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 16 + +#define MAVLINK_MESSAGE_INFO_PARAM_SET { \ + "PARAM_SET", \ + 5, \ + { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \ + { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \ + } \ +} + + +/** + * @brief Pack a param_set message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_SET_LEN]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_char_array(buf, 6, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_SET_LEN); +#else + mavlink_param_set_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_SET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif +} + +/** + * @brief Pack a param_set message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,const char *param_id,float param_value,uint8_t param_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_SET_LEN]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_char_array(buf, 6, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_SET_LEN); +#else + mavlink_param_set_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_SET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif +} + +/** + * @brief Encode a param_set struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_set C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set) +{ + return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); +} + +/** + * @brief Encode a param_set struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param param_set C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_set_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_set_t* param_set) +{ + return mavlink_msg_param_set_pack_chan(system_id, component_id, chan, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); +} + +/** + * @brief Send a param_set message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_SET_LEN]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_char_array(buf, 6, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif +#else + mavlink_param_set_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_PARAM_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_param_set_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_char_array(buf, 6, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif +#else + mavlink_param_set_t *packet = (mavlink_param_set_t *)msgbuf; + packet->param_value = param_value; + packet->target_system = target_system; + packet->target_component = target_component; + packet->param_type = param_type; + mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE PARAM_SET UNPACKING + + +/** + * @brief Get field target_system from param_set message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from param_set message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field param_id from param_set message + * + * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + */ +static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, char *param_id) +{ + return _MAV_RETURN_char_array(msg, param_id, 16, 6); +} + +/** + * @brief Get field param_value from param_set message + * + * @return Onboard parameter value + */ +static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param_type from param_set message + * + * @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + */ +static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 22); +} + +/** + * @brief Decode a param_set message into a struct + * + * @param msg The message to decode + * @param param_set C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_set->param_value = mavlink_msg_param_set_get_param_value(msg); + param_set->target_system = mavlink_msg_param_set_get_target_system(msg); + param_set->target_component = mavlink_msg_param_set_get_target_component(msg); + mavlink_msg_param_set_get_param_id(msg, param_set->param_id); + param_set->param_type = mavlink_msg_param_set_get_param_type(msg); +#else + memcpy(param_set, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_SET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_param_value.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_param_value.h new file mode 100644 index 0000000..856fa5a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_param_value.h @@ -0,0 +1,297 @@ +// MESSAGE PARAM_VALUE PACKING + +#define MAVLINK_MSG_ID_PARAM_VALUE 22 + +typedef struct __mavlink_param_value_t +{ + float param_value; /*< Onboard parameter value*/ + uint16_t param_count; /*< Total number of onboard parameters*/ + uint16_t param_index; /*< Index of this onboard parameter*/ + char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ + uint8_t param_type; /*< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.*/ +} mavlink_param_value_t; + +#define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25 +#define MAVLINK_MSG_ID_22_LEN 25 + +#define MAVLINK_MSG_ID_PARAM_VALUE_CRC 220 +#define MAVLINK_MSG_ID_22_CRC 220 + +#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 16 + +#define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \ + "PARAM_VALUE", \ + 5, \ + { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \ + { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \ + { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \ + { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \ + } \ +} + + +/** + * @brief Pack a param_value message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint16_t(buf, 4, param_count); + _mav_put_uint16_t(buf, 6, param_index); + _mav_put_uint8_t(buf, 24, param_type); + _mav_put_char_array(buf, 8, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#else + mavlink_param_value_t packet; + packet.param_value = param_value; + packet.param_count = param_count; + packet.param_index = param_index; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif +} + +/** + * @brief Pack a param_value message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *param_id,float param_value,uint8_t param_type,uint16_t param_count,uint16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint16_t(buf, 4, param_count); + _mav_put_uint16_t(buf, 6, param_index); + _mav_put_uint8_t(buf, 24, param_type); + _mav_put_char_array(buf, 8, param_id, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#else + mavlink_param_value_t packet; + packet.param_value = param_value; + packet.param_count = param_count; + packet.param_index = param_index; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif +} + +/** + * @brief Encode a param_value struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_value C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value) +{ + return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); +} + +/** + * @brief Encode a param_value struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param param_value C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_value_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_value_t* param_value) +{ + return mavlink_msg_param_value_pack_chan(system_id, component_id, chan, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); +} + +/** + * @brief Send a param_value message + * @param chan MAVLink channel to send the message + * + * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint16_t(buf, 4, param_count); + _mav_put_uint16_t(buf, 6, param_index); + _mav_put_uint8_t(buf, 24, param_type); + _mav_put_char_array(buf, 8, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif +#else + mavlink_param_value_t packet; + packet.param_value = param_value; + packet.param_count = param_count; + packet.param_index = param_index; + packet.param_type = param_type; + mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_PARAM_VALUE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_param_value_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, param_value); + _mav_put_uint16_t(buf, 4, param_count); + _mav_put_uint16_t(buf, 6, param_index); + _mav_put_uint8_t(buf, 24, param_type); + _mav_put_char_array(buf, 8, param_id, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif +#else + mavlink_param_value_t *packet = (mavlink_param_value_t *)msgbuf; + packet->param_value = param_value; + packet->param_count = param_count; + packet->param_index = param_index; + packet->param_type = param_type; + mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE PARAM_VALUE UNPACKING + + +/** + * @brief Get field param_id from param_value message + * + * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + */ +static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, char *param_id) +{ + return _MAV_RETURN_char_array(msg, param_id, 16, 8); +} + +/** + * @brief Get field param_value from param_value message + * + * @return Onboard parameter value + */ +static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param_type from param_value message + * + * @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + */ +static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field param_count from param_value message + * + * @return Total number of onboard parameters + */ +static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field param_index from param_value message + * + * @return Index of this onboard parameter + */ +static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Decode a param_value message into a struct + * + * @param msg The message to decode + * @param param_value C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_value->param_value = mavlink_msg_param_value_get_param_value(msg); + param_value->param_count = mavlink_msg_param_value_get_param_count(msg); + param_value->param_index = mavlink_msg_param_value_get_param_index(msg); + mavlink_msg_param_value_get_param_id(msg, param_value->param_id); + param_value->param_type = mavlink_msg_param_value_get_param_type(msg); +#else + memcpy(param_value, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_VALUE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_ping.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_ping.h new file mode 100644 index 0000000..8664675 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_ping.h @@ -0,0 +1,281 @@ +// MESSAGE PING PACKING + +#define MAVLINK_MSG_ID_PING 4 + +typedef struct __mavlink_ping_t +{ + uint64_t time_usec; /*< Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)*/ + uint32_t seq; /*< PING sequence*/ + uint8_t target_system; /*< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system*/ + uint8_t target_component; /*< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system*/ +} mavlink_ping_t; + +#define MAVLINK_MSG_ID_PING_LEN 14 +#define MAVLINK_MSG_ID_4_LEN 14 + +#define MAVLINK_MSG_ID_PING_CRC 237 +#define MAVLINK_MSG_ID_4_CRC 237 + + + +#define MAVLINK_MESSAGE_INFO_PING { \ + "PING", \ + 4, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time_usec) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ping_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ping_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ping_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a ping message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PING_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_LEN); +#else + mavlink_ping_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PING; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_LEN); +#endif +} + +/** + * @brief Pack a ping message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint32_t seq,uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PING_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_LEN); +#else + mavlink_ping_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_PING; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_LEN); +#endif +} + +/** + * @brief Encode a ping struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param ping C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping) +{ + return mavlink_msg_ping_pack(system_id, component_id, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component); +} + +/** + * @brief Encode a ping struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param ping C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ping_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ping_t* ping) +{ + return mavlink_msg_ping_pack_chan(system_id, component_id, chan, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component); +} + +/** + * @brief Send a ping message + * @param chan MAVLink channel to send the message + * + * @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_PING_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN); +#endif +#else + mavlink_ping_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, MAVLINK_MSG_ID_PING_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_PING_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_ping_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN); +#endif +#else + mavlink_ping_t *packet = (mavlink_ping_t *)msgbuf; + packet->time_usec = time_usec; + packet->seq = seq; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)packet, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)packet, MAVLINK_MSG_ID_PING_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE PING UNPACKING + + +/** + * @brief Get field time_usec from ping message + * + * @return Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) + */ +static inline uint64_t mavlink_msg_ping_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field seq from ping message + * + * @return PING sequence + */ +static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field target_system from ping message + * + * @return 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + */ +static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field target_component from ping message + * + * @return 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + */ +static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 13); +} + +/** + * @brief Decode a ping message into a struct + * + * @param msg The message to decode + * @param ping C-struct to decode the message contents into + */ +static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping) +{ +#if MAVLINK_NEED_BYTE_SWAP + ping->time_usec = mavlink_msg_ping_get_time_usec(msg); + ping->seq = mavlink_msg_ping_get_seq(msg); + ping->target_system = mavlink_msg_ping_get_target_system(msg); + ping->target_component = mavlink_msg_ping_get_target_component(msg); +#else + memcpy(ping, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PING_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_position_target_global_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_position_target_global_int.h new file mode 100644 index 0000000..8416362 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_position_target_global_int.h @@ -0,0 +1,521 @@ +// MESSAGE POSITION_TARGET_GLOBAL_INT PACKING + +#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT 87 + +typedef struct __mavlink_position_target_global_int_t +{ + uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/ + int32_t lat_int; /*< X Position in WGS84 frame in 1e7 * meters*/ + int32_t lon_int; /*< Y Position in WGS84 frame in 1e7 * meters*/ + float alt; /*< Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT*/ + float vx; /*< X velocity in NED frame in meter / s*/ + float vy; /*< Y velocity in NED frame in meter / s*/ + float vz; /*< Z velocity in NED frame in meter / s*/ + float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float yaw; /*< yaw setpoint in rad*/ + float yaw_rate; /*< yaw rate setpoint in rad/s*/ + uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ + uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/ +} mavlink_position_target_global_int_t; + +#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 51 +#define MAVLINK_MSG_ID_87_LEN 51 + +#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC 150 +#define MAVLINK_MSG_ID_87_CRC 150 + + + +#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \ + "POSITION_TARGET_GLOBAL_INT", \ + 14, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \ + { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \ + { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_global_int_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_global_int_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_global_int_t, vz) }, \ + { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_global_int_t, afx) }, \ + { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_global_int_t, afy) }, \ + { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \ + { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a position_target_global_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param lat_int X Position in WGS84 frame in 1e7 * meters + * @param lon_int Y Position in WGS84 frame in 1e7 * meters + * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#else + mavlink_position_target_global_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat_int = lat_int; + packet.lon_int = lon_int; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +} + +/** + * @brief Pack a position_target_global_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param lat_int X Position in WGS84 frame in 1e7 * meters + * @param lon_int Y Position in WGS84 frame in 1e7 * meters + * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#else + mavlink_position_target_global_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat_int = lat_int; + packet.lon_int = lon_int; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +} + +/** + * @brief Encode a position_target_global_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param position_target_global_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int) +{ + return mavlink_msg_position_target_global_int_pack(system_id, component_id, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate); +} + +/** + * @brief Encode a position_target_global_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param position_target_global_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int) +{ + return mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, chan, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate); +} + +/** + * @brief Send a position_target_global_int message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param lat_int X Position in WGS84 frame in 1e7 * meters + * @param lon_int Y Position in WGS84 frame in 1e7 * meters + * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#else + mavlink_position_target_global_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat_int = lat_int; + packet.lon_int = lon_int; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#else + mavlink_position_target_global_int_t *packet = (mavlink_position_target_global_int_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->lat_int = lat_int; + packet->lon_int = lon_int; + packet->alt = alt; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->afx = afx; + packet->afy = afy; + packet->afz = afz; + packet->yaw = yaw; + packet->yaw_rate = yaw_rate; + packet->type_mask = type_mask; + packet->coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE POSITION_TARGET_GLOBAL_INT UNPACKING + + +/** + * @brief Get field time_boot_ms from position_target_global_int message + * + * @return Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + */ +static inline uint32_t mavlink_msg_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field coordinate_frame from position_target_global_int message + * + * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + */ +static inline uint8_t mavlink_msg_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 50); +} + +/** + * @brief Get field type_mask from position_target_global_int message + * + * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + */ +static inline uint16_t mavlink_msg_position_target_global_int_get_type_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 48); +} + +/** + * @brief Get field lat_int from position_target_global_int message + * + * @return X Position in WGS84 frame in 1e7 * meters + */ +static inline int32_t mavlink_msg_position_target_global_int_get_lat_int(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field lon_int from position_target_global_int message + * + * @return Y Position in WGS84 frame in 1e7 * meters + */ +static inline int32_t mavlink_msg_position_target_global_int_get_lon_int(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field alt from position_target_global_int message + * + * @return Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + */ +static inline float mavlink_msg_position_target_global_int_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vx from position_target_global_int message + * + * @return X velocity in NED frame in meter / s + */ +static inline float mavlink_msg_position_target_global_int_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vy from position_target_global_int message + * + * @return Y velocity in NED frame in meter / s + */ +static inline float mavlink_msg_position_target_global_int_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vz from position_target_global_int message + * + * @return Z velocity in NED frame in meter / s + */ +static inline float mavlink_msg_position_target_global_int_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field afx from position_target_global_int message + * + * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_position_target_global_int_get_afx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field afy from position_target_global_int message + * + * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_position_target_global_int_get_afy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field afz from position_target_global_int message + * + * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_position_target_global_int_get_afz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field yaw from position_target_global_int message + * + * @return yaw setpoint in rad + */ +static inline float mavlink_msg_position_target_global_int_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field yaw_rate from position_target_global_int message + * + * @return yaw rate setpoint in rad/s + */ +static inline float mavlink_msg_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Decode a position_target_global_int message into a struct + * + * @param msg The message to decode + * @param position_target_global_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_position_target_global_int_decode(const mavlink_message_t* msg, mavlink_position_target_global_int_t* position_target_global_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + position_target_global_int->time_boot_ms = mavlink_msg_position_target_global_int_get_time_boot_ms(msg); + position_target_global_int->lat_int = mavlink_msg_position_target_global_int_get_lat_int(msg); + position_target_global_int->lon_int = mavlink_msg_position_target_global_int_get_lon_int(msg); + position_target_global_int->alt = mavlink_msg_position_target_global_int_get_alt(msg); + position_target_global_int->vx = mavlink_msg_position_target_global_int_get_vx(msg); + position_target_global_int->vy = mavlink_msg_position_target_global_int_get_vy(msg); + position_target_global_int->vz = mavlink_msg_position_target_global_int_get_vz(msg); + position_target_global_int->afx = mavlink_msg_position_target_global_int_get_afx(msg); + position_target_global_int->afy = mavlink_msg_position_target_global_int_get_afy(msg); + position_target_global_int->afz = mavlink_msg_position_target_global_int_get_afz(msg); + position_target_global_int->yaw = mavlink_msg_position_target_global_int_get_yaw(msg); + position_target_global_int->yaw_rate = mavlink_msg_position_target_global_int_get_yaw_rate(msg); + position_target_global_int->type_mask = mavlink_msg_position_target_global_int_get_type_mask(msg); + position_target_global_int->coordinate_frame = mavlink_msg_position_target_global_int_get_coordinate_frame(msg); +#else + memcpy(position_target_global_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_position_target_local_ned.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_position_target_local_ned.h new file mode 100644 index 0000000..9099159 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_position_target_local_ned.h @@ -0,0 +1,521 @@ +// MESSAGE POSITION_TARGET_LOCAL_NED PACKING + +#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED 85 + +typedef struct __mavlink_position_target_local_ned_t +{ + uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ + float x; /*< X Position in NED frame in meters*/ + float y; /*< Y Position in NED frame in meters*/ + float z; /*< Z Position in NED frame in meters (note, altitude is negative in NED)*/ + float vx; /*< X velocity in NED frame in meter / s*/ + float vy; /*< Y velocity in NED frame in meter / s*/ + float vz; /*< Z velocity in NED frame in meter / s*/ + float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float yaw; /*< yaw setpoint in rad*/ + float yaw_rate; /*< yaw rate setpoint in rad/s*/ + uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ + uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/ +} mavlink_position_target_local_ned_t; + +#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN 51 +#define MAVLINK_MSG_ID_85_LEN 51 + +#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC 140 +#define MAVLINK_MSG_ID_85_CRC 140 + + + +#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED { \ + "POSITION_TARGET_LOCAL_NED", \ + 14, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_local_ned_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_local_ned_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_local_ned_t, z) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_local_ned_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_local_ned_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_local_ned_t, vz) }, \ + { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_local_ned_t, afx) }, \ + { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_local_ned_t, afy) }, \ + { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \ + { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a position_target_local_ned message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param x X Position in NED frame in meters + * @param y Y Position in NED frame in meters + * @param z Z Position in NED frame in meters (note, altitude is negative in NED) + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#else + mavlink_position_target_local_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif +} + +/** + * @brief Pack a position_target_local_ned message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param x X Position in NED frame in meters + * @param y Y Position in NED frame in meters + * @param z Z Position in NED frame in meters (note, altitude is negative in NED) + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#else + mavlink_position_target_local_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif +} + +/** + * @brief Encode a position_target_local_ned struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param position_target_local_ned C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned) +{ + return mavlink_msg_position_target_local_ned_pack(system_id, component_id, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate); +} + +/** + * @brief Encode a position_target_local_ned struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param position_target_local_ned C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned) +{ + return mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate); +} + +/** + * @brief Send a position_target_local_ned message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param x X Position in NED frame in meters + * @param y Y Position in NED frame in meters + * @param z Z Position in NED frame in meters (note, altitude is negative in NED) + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#else + mavlink_position_target_local_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#else + mavlink_position_target_local_ned_t *packet = (mavlink_position_target_local_ned_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->x = x; + packet->y = y; + packet->z = z; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->afx = afx; + packet->afy = afy; + packet->afz = afz; + packet->yaw = yaw; + packet->yaw_rate = yaw_rate; + packet->type_mask = type_mask; + packet->coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE POSITION_TARGET_LOCAL_NED UNPACKING + + +/** + * @brief Get field time_boot_ms from position_target_local_ned message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field coordinate_frame from position_target_local_ned message + * + * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + */ +static inline uint8_t mavlink_msg_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 50); +} + +/** + * @brief Get field type_mask from position_target_local_ned message + * + * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + */ +static inline uint16_t mavlink_msg_position_target_local_ned_get_type_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 48); +} + +/** + * @brief Get field x from position_target_local_ned message + * + * @return X Position in NED frame in meters + */ +static inline float mavlink_msg_position_target_local_ned_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field y from position_target_local_ned message + * + * @return Y Position in NED frame in meters + */ +static inline float mavlink_msg_position_target_local_ned_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field z from position_target_local_ned message + * + * @return Z Position in NED frame in meters (note, altitude is negative in NED) + */ +static inline float mavlink_msg_position_target_local_ned_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vx from position_target_local_ned message + * + * @return X velocity in NED frame in meter / s + */ +static inline float mavlink_msg_position_target_local_ned_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vy from position_target_local_ned message + * + * @return Y velocity in NED frame in meter / s + */ +static inline float mavlink_msg_position_target_local_ned_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vz from position_target_local_ned message + * + * @return Z velocity in NED frame in meter / s + */ +static inline float mavlink_msg_position_target_local_ned_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field afx from position_target_local_ned message + * + * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_position_target_local_ned_get_afx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field afy from position_target_local_ned message + * + * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_position_target_local_ned_get_afy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field afz from position_target_local_ned message + * + * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_position_target_local_ned_get_afz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field yaw from position_target_local_ned message + * + * @return yaw setpoint in rad + */ +static inline float mavlink_msg_position_target_local_ned_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field yaw_rate from position_target_local_ned message + * + * @return yaw rate setpoint in rad/s + */ +static inline float mavlink_msg_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Decode a position_target_local_ned message into a struct + * + * @param msg The message to decode + * @param position_target_local_ned C-struct to decode the message contents into + */ +static inline void mavlink_msg_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_position_target_local_ned_t* position_target_local_ned) +{ +#if MAVLINK_NEED_BYTE_SWAP + position_target_local_ned->time_boot_ms = mavlink_msg_position_target_local_ned_get_time_boot_ms(msg); + position_target_local_ned->x = mavlink_msg_position_target_local_ned_get_x(msg); + position_target_local_ned->y = mavlink_msg_position_target_local_ned_get_y(msg); + position_target_local_ned->z = mavlink_msg_position_target_local_ned_get_z(msg); + position_target_local_ned->vx = mavlink_msg_position_target_local_ned_get_vx(msg); + position_target_local_ned->vy = mavlink_msg_position_target_local_ned_get_vy(msg); + position_target_local_ned->vz = mavlink_msg_position_target_local_ned_get_vz(msg); + position_target_local_ned->afx = mavlink_msg_position_target_local_ned_get_afx(msg); + position_target_local_ned->afy = mavlink_msg_position_target_local_ned_get_afy(msg); + position_target_local_ned->afz = mavlink_msg_position_target_local_ned_get_afz(msg); + position_target_local_ned->yaw = mavlink_msg_position_target_local_ned_get_yaw(msg); + position_target_local_ned->yaw_rate = mavlink_msg_position_target_local_ned_get_yaw_rate(msg); + position_target_local_ned->type_mask = mavlink_msg_position_target_local_ned_get_type_mask(msg); + position_target_local_ned->coordinate_frame = mavlink_msg_position_target_local_ned_get_coordinate_frame(msg); +#else + memcpy(position_target_local_ned, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_power_status.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_power_status.h new file mode 100644 index 0000000..ffe8c84 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_power_status.h @@ -0,0 +1,257 @@ +// MESSAGE POWER_STATUS PACKING + +#define MAVLINK_MSG_ID_POWER_STATUS 125 + +typedef struct __mavlink_power_status_t +{ + uint16_t Vcc; /*< 5V rail voltage in millivolts*/ + uint16_t Vservo; /*< servo rail voltage in millivolts*/ + uint16_t flags; /*< power supply status flags (see MAV_POWER_STATUS enum)*/ +} mavlink_power_status_t; + +#define MAVLINK_MSG_ID_POWER_STATUS_LEN 6 +#define MAVLINK_MSG_ID_125_LEN 6 + +#define MAVLINK_MSG_ID_POWER_STATUS_CRC 203 +#define MAVLINK_MSG_ID_125_CRC 203 + + + +#define MAVLINK_MESSAGE_INFO_POWER_STATUS { \ + "POWER_STATUS", \ + 3, \ + { { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_power_status_t, Vcc) }, \ + { "Vservo", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_power_status_t, Vservo) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_power_status_t, flags) }, \ + } \ +} + + +/** + * @brief Pack a power_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param Vcc 5V rail voltage in millivolts + * @param Vservo servo rail voltage in millivolts + * @param flags power supply status flags (see MAV_POWER_STATUS enum) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_power_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t Vcc, uint16_t Vservo, uint16_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; + _mav_put_uint16_t(buf, 0, Vcc); + _mav_put_uint16_t(buf, 2, Vservo); + _mav_put_uint16_t(buf, 4, flags); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#else + mavlink_power_status_t packet; + packet.Vcc = Vcc; + packet.Vservo = Vservo; + packet.flags = flags; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_POWER_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif +} + +/** + * @brief Pack a power_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param Vcc 5V rail voltage in millivolts + * @param Vservo servo rail voltage in millivolts + * @param flags power supply status flags (see MAV_POWER_STATUS enum) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_power_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t Vcc,uint16_t Vservo,uint16_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; + _mav_put_uint16_t(buf, 0, Vcc); + _mav_put_uint16_t(buf, 2, Vservo); + _mav_put_uint16_t(buf, 4, flags); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#else + mavlink_power_status_t packet; + packet.Vcc = Vcc; + packet.Vservo = Vservo; + packet.flags = flags; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_POWER_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif +} + +/** + * @brief Encode a power_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param power_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_power_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_power_status_t* power_status) +{ + return mavlink_msg_power_status_pack(system_id, component_id, msg, power_status->Vcc, power_status->Vservo, power_status->flags); +} + +/** + * @brief Encode a power_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param power_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_power_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_power_status_t* power_status) +{ + return mavlink_msg_power_status_pack_chan(system_id, component_id, chan, msg, power_status->Vcc, power_status->Vservo, power_status->flags); +} + +/** + * @brief Send a power_status message + * @param chan MAVLink channel to send the message + * + * @param Vcc 5V rail voltage in millivolts + * @param Vservo servo rail voltage in millivolts + * @param flags power supply status flags (see MAV_POWER_STATUS enum) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_power_status_send(mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; + _mav_put_uint16_t(buf, 0, Vcc); + _mav_put_uint16_t(buf, 2, Vservo); + _mav_put_uint16_t(buf, 4, flags); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif +#else + mavlink_power_status_t packet; + packet.Vcc = Vcc; + packet.Vservo = Vservo; + packet.flags = flags; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_POWER_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_power_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, Vcc); + _mav_put_uint16_t(buf, 2, Vservo); + _mav_put_uint16_t(buf, 4, flags); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif +#else + mavlink_power_status_t *packet = (mavlink_power_status_t *)msgbuf; + packet->Vcc = Vcc; + packet->Vservo = Vservo; + packet->flags = flags; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)packet, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE POWER_STATUS UNPACKING + + +/** + * @brief Get field Vcc from power_status message + * + * @return 5V rail voltage in millivolts + */ +static inline uint16_t mavlink_msg_power_status_get_Vcc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field Vservo from power_status message + * + * @return servo rail voltage in millivolts + */ +static inline uint16_t mavlink_msg_power_status_get_Vservo(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Get field flags from power_status message + * + * @return power supply status flags (see MAV_POWER_STATUS enum) + */ +static inline uint16_t mavlink_msg_power_status_get_flags(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Decode a power_status message into a struct + * + * @param msg The message to decode + * @param power_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_power_status_decode(const mavlink_message_t* msg, mavlink_power_status_t* power_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + power_status->Vcc = mavlink_msg_power_status_get_Vcc(msg); + power_status->Vservo = mavlink_msg_power_status_get_Vservo(msg); + power_status->flags = mavlink_msg_power_status_get_flags(msg); +#else + memcpy(power_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POWER_STATUS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_radio_status.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_radio_status.h new file mode 100644 index 0000000..ebb8b67 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_radio_status.h @@ -0,0 +1,353 @@ +// MESSAGE RADIO_STATUS PACKING + +#define MAVLINK_MSG_ID_RADIO_STATUS 109 + +typedef struct __mavlink_radio_status_t +{ + uint16_t rxerrors; /*< Receive errors*/ + uint16_t fixed; /*< Count of error corrected packets*/ + uint8_t rssi; /*< Local signal strength*/ + uint8_t remrssi; /*< Remote signal strength*/ + uint8_t txbuf; /*< Remaining free buffer space in percent.*/ + uint8_t noise; /*< Background noise level*/ + uint8_t remnoise; /*< Remote background noise level*/ +} mavlink_radio_status_t; + +#define MAVLINK_MSG_ID_RADIO_STATUS_LEN 9 +#define MAVLINK_MSG_ID_109_LEN 9 + +#define MAVLINK_MSG_ID_RADIO_STATUS_CRC 185 +#define MAVLINK_MSG_ID_109_CRC 185 + + + +#define MAVLINK_MESSAGE_INFO_RADIO_STATUS { \ + "RADIO_STATUS", \ + 7, \ + { { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \ + { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \ + { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_status_t, remrssi) }, \ + { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_status_t, txbuf) }, \ + { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_status_t, noise) }, \ + { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_status_t, remnoise) }, \ + } \ +} + + +/** + * @brief Pack a radio_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param rssi Local signal strength + * @param remrssi Remote signal strength + * @param txbuf Remaining free buffer space in percent. + * @param noise Background noise level + * @param remnoise Remote background noise level + * @param rxerrors Receive errors + * @param fixed Count of error corrected packets + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_radio_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN]; + _mav_put_uint16_t(buf, 0, rxerrors); + _mav_put_uint16_t(buf, 2, fixed); + _mav_put_uint8_t(buf, 4, rssi); + _mav_put_uint8_t(buf, 5, remrssi); + _mav_put_uint8_t(buf, 6, txbuf); + _mav_put_uint8_t(buf, 7, noise); + _mav_put_uint8_t(buf, 8, remnoise); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#else + mavlink_radio_status_t packet; + packet.rxerrors = rxerrors; + packet.fixed = fixed; + packet.rssi = rssi; + packet.remrssi = remrssi; + packet.txbuf = txbuf; + packet.noise = noise; + packet.remnoise = remnoise; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RADIO_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +} + +/** + * @brief Pack a radio_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rssi Local signal strength + * @param remrssi Remote signal strength + * @param txbuf Remaining free buffer space in percent. + * @param noise Background noise level + * @param remnoise Remote background noise level + * @param rxerrors Receive errors + * @param fixed Count of error corrected packets + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_radio_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN]; + _mav_put_uint16_t(buf, 0, rxerrors); + _mav_put_uint16_t(buf, 2, fixed); + _mav_put_uint8_t(buf, 4, rssi); + _mav_put_uint8_t(buf, 5, remrssi); + _mav_put_uint8_t(buf, 6, txbuf); + _mav_put_uint8_t(buf, 7, noise); + _mav_put_uint8_t(buf, 8, remnoise); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#else + mavlink_radio_status_t packet; + packet.rxerrors = rxerrors; + packet.fixed = fixed; + packet.rssi = rssi; + packet.remrssi = remrssi; + packet.txbuf = txbuf; + packet.noise = noise; + packet.remnoise = remnoise; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RADIO_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +} + +/** + * @brief Encode a radio_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param radio_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_radio_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_status_t* radio_status) +{ + return mavlink_msg_radio_status_pack(system_id, component_id, msg, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed); +} + +/** + * @brief Encode a radio_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param radio_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_radio_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_radio_status_t* radio_status) +{ + return mavlink_msg_radio_status_pack_chan(system_id, component_id, chan, msg, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed); +} + +/** + * @brief Send a radio_status message + * @param chan MAVLink channel to send the message + * + * @param rssi Local signal strength + * @param remrssi Remote signal strength + * @param txbuf Remaining free buffer space in percent. + * @param noise Background noise level + * @param remnoise Remote background noise level + * @param rxerrors Receive errors + * @param fixed Count of error corrected packets + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_radio_status_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN]; + _mav_put_uint16_t(buf, 0, rxerrors); + _mav_put_uint16_t(buf, 2, fixed); + _mav_put_uint8_t(buf, 4, rssi); + _mav_put_uint8_t(buf, 5, remrssi); + _mav_put_uint8_t(buf, 6, txbuf); + _mav_put_uint8_t(buf, 7, noise); + _mav_put_uint8_t(buf, 8, remnoise); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +#else + mavlink_radio_status_t packet; + packet.rxerrors = rxerrors; + packet.fixed = fixed; + packet.rssi = rssi; + packet.remrssi = remrssi; + packet.txbuf = txbuf; + packet.noise = noise; + packet.remnoise = remnoise; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)&packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)&packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RADIO_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_radio_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, rxerrors); + _mav_put_uint16_t(buf, 2, fixed); + _mav_put_uint8_t(buf, 4, rssi); + _mav_put_uint8_t(buf, 5, remrssi); + _mav_put_uint8_t(buf, 6, txbuf); + _mav_put_uint8_t(buf, 7, noise); + _mav_put_uint8_t(buf, 8, remnoise); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +#else + mavlink_radio_status_t *packet = (mavlink_radio_status_t *)msgbuf; + packet->rxerrors = rxerrors; + packet->fixed = fixed; + packet->rssi = rssi; + packet->remrssi = remrssi; + packet->txbuf = txbuf; + packet->noise = noise; + packet->remnoise = remnoise; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RADIO_STATUS UNPACKING + + +/** + * @brief Get field rssi from radio_status message + * + * @return Local signal strength + */ +static inline uint8_t mavlink_msg_radio_status_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field remrssi from radio_status message + * + * @return Remote signal strength + */ +static inline uint8_t mavlink_msg_radio_status_get_remrssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field txbuf from radio_status message + * + * @return Remaining free buffer space in percent. + */ +static inline uint8_t mavlink_msg_radio_status_get_txbuf(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field noise from radio_status message + * + * @return Background noise level + */ +static inline uint8_t mavlink_msg_radio_status_get_noise(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field remnoise from radio_status message + * + * @return Remote background noise level + */ +static inline uint8_t mavlink_msg_radio_status_get_remnoise(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field rxerrors from radio_status message + * + * @return Receive errors + */ +static inline uint16_t mavlink_msg_radio_status_get_rxerrors(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field fixed from radio_status message + * + * @return Count of error corrected packets + */ +static inline uint16_t mavlink_msg_radio_status_get_fixed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Decode a radio_status message into a struct + * + * @param msg The message to decode + * @param radio_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_radio_status_decode(const mavlink_message_t* msg, mavlink_radio_status_t* radio_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + radio_status->rxerrors = mavlink_msg_radio_status_get_rxerrors(msg); + radio_status->fixed = mavlink_msg_radio_status_get_fixed(msg); + radio_status->rssi = mavlink_msg_radio_status_get_rssi(msg); + radio_status->remrssi = mavlink_msg_radio_status_get_remrssi(msg); + radio_status->txbuf = mavlink_msg_radio_status_get_txbuf(msg); + radio_status->noise = mavlink_msg_radio_status_get_noise(msg); + radio_status->remnoise = mavlink_msg_radio_status_get_remnoise(msg); +#else + memcpy(radio_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RADIO_STATUS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_raw_imu.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_raw_imu.h new file mode 100644 index 0000000..212ad73 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_raw_imu.h @@ -0,0 +1,425 @@ +// MESSAGE RAW_IMU PACKING + +#define MAVLINK_MSG_ID_RAW_IMU 27 + +typedef struct __mavlink_raw_imu_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + int16_t xacc; /*< X acceleration (raw)*/ + int16_t yacc; /*< Y acceleration (raw)*/ + int16_t zacc; /*< Z acceleration (raw)*/ + int16_t xgyro; /*< Angular speed around X axis (raw)*/ + int16_t ygyro; /*< Angular speed around Y axis (raw)*/ + int16_t zgyro; /*< Angular speed around Z axis (raw)*/ + int16_t xmag; /*< X Magnetic field (raw)*/ + int16_t ymag; /*< Y Magnetic field (raw)*/ + int16_t zmag; /*< Z Magnetic field (raw)*/ +} mavlink_raw_imu_t; + +#define MAVLINK_MSG_ID_RAW_IMU_LEN 26 +#define MAVLINK_MSG_ID_27_LEN 26 + +#define MAVLINK_MSG_ID_RAW_IMU_CRC 144 +#define MAVLINK_MSG_ID_27_CRC 144 + + + +#define MAVLINK_MESSAGE_INFO_RAW_IMU { \ + "RAW_IMU", \ + 10, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \ + } \ +} + + +/** + * @brief Pack a raw_imu message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RAW_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, xacc); + _mav_put_int16_t(buf, 10, yacc); + _mav_put_int16_t(buf, 12, zacc); + _mav_put_int16_t(buf, 14, xgyro); + _mav_put_int16_t(buf, 16, ygyro); + _mav_put_int16_t(buf, 18, zgyro); + _mav_put_int16_t(buf, 20, xmag); + _mav_put_int16_t(buf, 22, ymag); + _mav_put_int16_t(buf, 24, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN); +#else + mavlink_raw_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif +} + +/** + * @brief Pack a raw_imu message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RAW_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, xacc); + _mav_put_int16_t(buf, 10, yacc); + _mav_put_int16_t(buf, 12, zacc); + _mav_put_int16_t(buf, 14, xgyro); + _mav_put_int16_t(buf, 16, ygyro); + _mav_put_int16_t(buf, 18, zgyro); + _mav_put_int16_t(buf, 20, xmag); + _mav_put_int16_t(buf, 22, ymag); + _mav_put_int16_t(buf, 24, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN); +#else + mavlink_raw_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif +} + +/** + * @brief Encode a raw_imu struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param raw_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) +{ + return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); +} + +/** + * @brief Encode a raw_imu struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param raw_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) +{ + return mavlink_msg_raw_imu_pack_chan(system_id, component_id, chan, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); +} + +/** + * @brief Send a raw_imu message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RAW_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, xacc); + _mav_put_int16_t(buf, 10, yacc); + _mav_put_int16_t(buf, 12, zacc); + _mav_put_int16_t(buf, 14, xgyro); + _mav_put_int16_t(buf, 16, ygyro); + _mav_put_int16_t(buf, 18, zgyro); + _mav_put_int16_t(buf, 20, xmag); + _mav_put_int16_t(buf, 22, ymag); + _mav_put_int16_t(buf, 24, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif +#else + mavlink_raw_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RAW_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_raw_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, xacc); + _mav_put_int16_t(buf, 10, yacc); + _mav_put_int16_t(buf, 12, zacc); + _mav_put_int16_t(buf, 14, xgyro); + _mav_put_int16_t(buf, 16, ygyro); + _mav_put_int16_t(buf, 18, zgyro); + _mav_put_int16_t(buf, 20, xmag); + _mav_put_int16_t(buf, 22, ymag); + _mav_put_int16_t(buf, 24, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif +#else + mavlink_raw_imu_t *packet = (mavlink_raw_imu_t *)msgbuf; + packet->time_usec = time_usec; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->xmag = xmag; + packet->ymag = ymag; + packet->zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)packet, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)packet, MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RAW_IMU UNPACKING + + +/** + * @brief Get field time_usec from raw_imu message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_raw_imu_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field xacc from raw_imu message + * + * @return X acceleration (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field yacc from raw_imu message + * + * @return Y acceleration (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field zacc from raw_imu message + * + * @return Z acceleration (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field xgyro from raw_imu message + * + * @return Angular speed around X axis (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field ygyro from raw_imu message + * + * @return Angular speed around Y axis (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field zgyro from raw_imu message + * + * @return Angular speed around Z axis (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field xmag from raw_imu message + * + * @return X Magnetic field (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field ymag from raw_imu message + * + * @return Y Magnetic field (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field zmag from raw_imu message + * + * @return Z Magnetic field (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 24); +} + +/** + * @brief Decode a raw_imu message into a struct + * + * @param msg The message to decode + * @param raw_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu) +{ +#if MAVLINK_NEED_BYTE_SWAP + raw_imu->time_usec = mavlink_msg_raw_imu_get_time_usec(msg); + raw_imu->xacc = mavlink_msg_raw_imu_get_xacc(msg); + raw_imu->yacc = mavlink_msg_raw_imu_get_yacc(msg); + raw_imu->zacc = mavlink_msg_raw_imu_get_zacc(msg); + raw_imu->xgyro = mavlink_msg_raw_imu_get_xgyro(msg); + raw_imu->ygyro = mavlink_msg_raw_imu_get_ygyro(msg); + raw_imu->zgyro = mavlink_msg_raw_imu_get_zgyro(msg); + raw_imu->xmag = mavlink_msg_raw_imu_get_xmag(msg); + raw_imu->ymag = mavlink_msg_raw_imu_get_ymag(msg); + raw_imu->zmag = mavlink_msg_raw_imu_get_zmag(msg); +#else + memcpy(raw_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RAW_IMU_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_raw_pressure.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_raw_pressure.h new file mode 100644 index 0000000..f17ad48 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_raw_pressure.h @@ -0,0 +1,305 @@ +// MESSAGE RAW_PRESSURE PACKING + +#define MAVLINK_MSG_ID_RAW_PRESSURE 28 + +typedef struct __mavlink_raw_pressure_t +{ + uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/ + int16_t press_abs; /*< Absolute pressure (raw)*/ + int16_t press_diff1; /*< Differential pressure 1 (raw, 0 if nonexistant)*/ + int16_t press_diff2; /*< Differential pressure 2 (raw, 0 if nonexistant)*/ + int16_t temperature; /*< Raw Temperature measurement (raw)*/ +} mavlink_raw_pressure_t; + +#define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16 +#define MAVLINK_MSG_ID_28_LEN 16 + +#define MAVLINK_MSG_ID_RAW_PRESSURE_CRC 67 +#define MAVLINK_MSG_ID_28_CRC 67 + + + +#define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \ + "RAW_PRESSURE", \ + 5, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \ + { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \ + { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \ + { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a raw_pressure message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistant) + * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistant) + * @param temperature Raw Temperature measurement (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, press_abs); + _mav_put_int16_t(buf, 10, press_diff1); + _mav_put_int16_t(buf, 12, press_diff2); + _mav_put_int16_t(buf, 14, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#else + mavlink_raw_pressure_t packet; + packet.time_usec = time_usec; + packet.press_abs = press_abs; + packet.press_diff1 = press_diff1; + packet.press_diff2 = press_diff2; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif +} + +/** + * @brief Pack a raw_pressure message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistant) + * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistant) + * @param temperature Raw Temperature measurement (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,int16_t press_abs,int16_t press_diff1,int16_t press_diff2,int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, press_abs); + _mav_put_int16_t(buf, 10, press_diff1); + _mav_put_int16_t(buf, 12, press_diff2); + _mav_put_int16_t(buf, 14, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#else + mavlink_raw_pressure_t packet; + packet.time_usec = time_usec; + packet.press_abs = press_abs; + packet.press_diff1 = press_diff1; + packet.press_diff2 = press_diff2; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif +} + +/** + * @brief Encode a raw_pressure struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param raw_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) +{ + return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); +} + +/** + * @brief Encode a raw_pressure struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param raw_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) +{ + return mavlink_msg_raw_pressure_pack_chan(system_id, component_id, chan, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); +} + +/** + * @brief Send a raw_pressure message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistant) + * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistant) + * @param temperature Raw Temperature measurement (raw) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, press_abs); + _mav_put_int16_t(buf, 10, press_diff1); + _mav_put_int16_t(buf, 12, press_diff2); + _mav_put_int16_t(buf, 14, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif +#else + mavlink_raw_pressure_t packet; + packet.time_usec = time_usec; + packet.press_abs = press_abs; + packet.press_diff1 = press_diff1; + packet.press_diff2 = press_diff2; + packet.temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RAW_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_raw_pressure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, press_abs); + _mav_put_int16_t(buf, 10, press_diff1); + _mav_put_int16_t(buf, 12, press_diff2); + _mav_put_int16_t(buf, 14, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif +#else + mavlink_raw_pressure_t *packet = (mavlink_raw_pressure_t *)msgbuf; + packet->time_usec = time_usec; + packet->press_abs = press_abs; + packet->press_diff1 = press_diff1; + packet->press_diff2 = press_diff2; + packet->temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RAW_PRESSURE UNPACKING + + +/** + * @brief Get field time_usec from raw_pressure message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field press_abs from raw_pressure message + * + * @return Absolute pressure (raw) + */ +static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field press_diff1 from raw_pressure message + * + * @return Differential pressure 1 (raw, 0 if nonexistant) + */ +static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field press_diff2 from raw_pressure message + * + * @return Differential pressure 2 (raw, 0 if nonexistant) + */ +static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field temperature from raw_pressure message + * + * @return Raw Temperature measurement (raw) + */ +static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Decode a raw_pressure message into a struct + * + * @param msg The message to decode + * @param raw_pressure C-struct to decode the message contents into + */ +static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure) +{ +#if MAVLINK_NEED_BYTE_SWAP + raw_pressure->time_usec = mavlink_msg_raw_pressure_get_time_usec(msg); + raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg); + raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg); + raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg); + raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg); +#else + memcpy(raw_pressure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RAW_PRESSURE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_rc_channels.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_rc_channels.h new file mode 100644 index 0000000..b4ece26 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_rc_channels.h @@ -0,0 +1,689 @@ +// MESSAGE RC_CHANNELS PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS 65 + +typedef struct __mavlink_rc_channels_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan9_raw; /*< RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan10_raw; /*< RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan11_raw; /*< RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan12_raw; /*< RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan13_raw; /*< RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan14_raw; /*< RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan15_raw; /*< RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan16_raw; /*< RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan17_raw; /*< RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan18_raw; /*< RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint8_t chancount; /*< Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.*/ + uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/ +} mavlink_rc_channels_t; + +#define MAVLINK_MSG_ID_RC_CHANNELS_LEN 42 +#define MAVLINK_MSG_ID_65_LEN 42 + +#define MAVLINK_MSG_ID_RC_CHANNELS_CRC 118 +#define MAVLINK_MSG_ID_65_CRC 118 + + + +#define MAVLINK_MESSAGE_INFO_RC_CHANNELS { \ + "RC_CHANNELS", \ + 21, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \ + { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \ + { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \ + { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \ + { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \ + { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \ + { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \ + { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \ + { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \ + { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \ + { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \ + { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \ + { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \ + } \ +} + + +/** + * @brief Pack a rc_channels message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint16_t(buf, 20, chan9_raw); + _mav_put_uint16_t(buf, 22, chan10_raw); + _mav_put_uint16_t(buf, 24, chan11_raw); + _mav_put_uint16_t(buf, 26, chan12_raw); + _mav_put_uint16_t(buf, 28, chan13_raw); + _mav_put_uint16_t(buf, 30, chan14_raw); + _mav_put_uint16_t(buf, 32, chan15_raw); + _mav_put_uint16_t(buf, 34, chan16_raw); + _mav_put_uint16_t(buf, 36, chan17_raw); + _mav_put_uint16_t(buf, 38, chan18_raw); + _mav_put_uint8_t(buf, 40, chancount); + _mav_put_uint8_t(buf, 41, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#else + mavlink_rc_channels_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.chan13_raw = chan13_raw; + packet.chan14_raw = chan14_raw; + packet.chan15_raw = chan15_raw; + packet.chan16_raw = chan16_raw; + packet.chan17_raw = chan17_raw; + packet.chan18_raw = chan18_raw; + packet.chancount = chancount; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif +} + +/** + * @brief Pack a rc_channels message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t chancount,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint16_t chan13_raw,uint16_t chan14_raw,uint16_t chan15_raw,uint16_t chan16_raw,uint16_t chan17_raw,uint16_t chan18_raw,uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint16_t(buf, 20, chan9_raw); + _mav_put_uint16_t(buf, 22, chan10_raw); + _mav_put_uint16_t(buf, 24, chan11_raw); + _mav_put_uint16_t(buf, 26, chan12_raw); + _mav_put_uint16_t(buf, 28, chan13_raw); + _mav_put_uint16_t(buf, 30, chan14_raw); + _mav_put_uint16_t(buf, 32, chan15_raw); + _mav_put_uint16_t(buf, 34, chan16_raw); + _mav_put_uint16_t(buf, 36, chan17_raw); + _mav_put_uint16_t(buf, 38, chan18_raw); + _mav_put_uint8_t(buf, 40, chancount); + _mav_put_uint8_t(buf, 41, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#else + mavlink_rc_channels_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.chan13_raw = chan13_raw; + packet.chan14_raw = chan14_raw; + packet.chan15_raw = chan15_raw; + packet.chan16_raw = chan16_raw; + packet.chan17_raw = chan17_raw; + packet.chan18_raw = chan18_raw; + packet.chancount = chancount; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif +} + +/** + * @brief Encode a rc_channels struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rc_channels C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels) +{ + return mavlink_msg_rc_channels_pack(system_id, component_id, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi); +} + +/** + * @brief Encode a rc_channels struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rc_channels C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels) +{ + return mavlink_msg_rc_channels_pack_chan(system_id, component_id, chan, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi); +} + +/** + * @brief Send a rc_channels message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint16_t(buf, 20, chan9_raw); + _mav_put_uint16_t(buf, 22, chan10_raw); + _mav_put_uint16_t(buf, 24, chan11_raw); + _mav_put_uint16_t(buf, 26, chan12_raw); + _mav_put_uint16_t(buf, 28, chan13_raw); + _mav_put_uint16_t(buf, 30, chan14_raw); + _mav_put_uint16_t(buf, 32, chan15_raw); + _mav_put_uint16_t(buf, 34, chan16_raw); + _mav_put_uint16_t(buf, 36, chan17_raw); + _mav_put_uint16_t(buf, 38, chan18_raw); + _mav_put_uint8_t(buf, 40, chancount); + _mav_put_uint8_t(buf, 41, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif +#else + mavlink_rc_channels_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.chan13_raw = chan13_raw; + packet.chan14_raw = chan14_raw; + packet.chan15_raw = chan15_raw; + packet.chan16_raw = chan16_raw; + packet.chan17_raw = chan17_raw; + packet.chan18_raw = chan18_raw; + packet.chancount = chancount; + packet.rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RC_CHANNELS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rc_channels_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint16_t(buf, 20, chan9_raw); + _mav_put_uint16_t(buf, 22, chan10_raw); + _mav_put_uint16_t(buf, 24, chan11_raw); + _mav_put_uint16_t(buf, 26, chan12_raw); + _mav_put_uint16_t(buf, 28, chan13_raw); + _mav_put_uint16_t(buf, 30, chan14_raw); + _mav_put_uint16_t(buf, 32, chan15_raw); + _mav_put_uint16_t(buf, 34, chan16_raw); + _mav_put_uint16_t(buf, 36, chan17_raw); + _mav_put_uint16_t(buf, 38, chan18_raw); + _mav_put_uint8_t(buf, 40, chancount); + _mav_put_uint8_t(buf, 41, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif +#else + mavlink_rc_channels_t *packet = (mavlink_rc_channels_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->chan1_raw = chan1_raw; + packet->chan2_raw = chan2_raw; + packet->chan3_raw = chan3_raw; + packet->chan4_raw = chan4_raw; + packet->chan5_raw = chan5_raw; + packet->chan6_raw = chan6_raw; + packet->chan7_raw = chan7_raw; + packet->chan8_raw = chan8_raw; + packet->chan9_raw = chan9_raw; + packet->chan10_raw = chan10_raw; + packet->chan11_raw = chan11_raw; + packet->chan12_raw = chan12_raw; + packet->chan13_raw = chan13_raw; + packet->chan14_raw = chan14_raw; + packet->chan15_raw = chan15_raw; + packet->chan16_raw = chan16_raw; + packet->chan17_raw = chan17_raw; + packet->chan18_raw = chan18_raw; + packet->chancount = chancount; + packet->rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RC_CHANNELS UNPACKING + + +/** + * @brief Get field time_boot_ms from rc_channels message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_rc_channels_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field chancount from rc_channels message + * + * @return Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + */ +static inline uint8_t mavlink_msg_rc_channels_get_chancount(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 40); +} + +/** + * @brief Get field chan1_raw from rc_channels message + * + * @return RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field chan2_raw from rc_channels message + * + * @return RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field chan3_raw from rc_channels message + * + * @return RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field chan4_raw from rc_channels message + * + * @return RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field chan5_raw from rc_channels message + * + * @return RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field chan6_raw from rc_channels message + * + * @return RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field chan7_raw from rc_channels message + * + * @return RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field chan8_raw from rc_channels message + * + * @return RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field chan9_raw from rc_channels message + * + * @return RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan9_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field chan10_raw from rc_channels message + * + * @return RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan10_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field chan11_raw from rc_channels message + * + * @return RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan11_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field chan12_raw from rc_channels message + * + * @return RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan12_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field chan13_raw from rc_channels message + * + * @return RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan13_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field chan14_raw from rc_channels message + * + * @return RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan14_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 30); +} + +/** + * @brief Get field chan15_raw from rc_channels message + * + * @return RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan15_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 32); +} + +/** + * @brief Get field chan16_raw from rc_channels message + * + * @return RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan16_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 34); +} + +/** + * @brief Get field chan17_raw from rc_channels message + * + * @return RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan17_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 36); +} + +/** + * @brief Get field chan18_raw from rc_channels message + * + * @return RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_get_chan18_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 38); +} + +/** + * @brief Get field rssi from rc_channels message + * + * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + */ +static inline uint8_t mavlink_msg_rc_channels_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 41); +} + +/** + * @brief Decode a rc_channels message into a struct + * + * @param msg The message to decode + * @param rc_channels C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_decode(const mavlink_message_t* msg, mavlink_rc_channels_t* rc_channels) +{ +#if MAVLINK_NEED_BYTE_SWAP + rc_channels->time_boot_ms = mavlink_msg_rc_channels_get_time_boot_ms(msg); + rc_channels->chan1_raw = mavlink_msg_rc_channels_get_chan1_raw(msg); + rc_channels->chan2_raw = mavlink_msg_rc_channels_get_chan2_raw(msg); + rc_channels->chan3_raw = mavlink_msg_rc_channels_get_chan3_raw(msg); + rc_channels->chan4_raw = mavlink_msg_rc_channels_get_chan4_raw(msg); + rc_channels->chan5_raw = mavlink_msg_rc_channels_get_chan5_raw(msg); + rc_channels->chan6_raw = mavlink_msg_rc_channels_get_chan6_raw(msg); + rc_channels->chan7_raw = mavlink_msg_rc_channels_get_chan7_raw(msg); + rc_channels->chan8_raw = mavlink_msg_rc_channels_get_chan8_raw(msg); + rc_channels->chan9_raw = mavlink_msg_rc_channels_get_chan9_raw(msg); + rc_channels->chan10_raw = mavlink_msg_rc_channels_get_chan10_raw(msg); + rc_channels->chan11_raw = mavlink_msg_rc_channels_get_chan11_raw(msg); + rc_channels->chan12_raw = mavlink_msg_rc_channels_get_chan12_raw(msg); + rc_channels->chan13_raw = mavlink_msg_rc_channels_get_chan13_raw(msg); + rc_channels->chan14_raw = mavlink_msg_rc_channels_get_chan14_raw(msg); + rc_channels->chan15_raw = mavlink_msg_rc_channels_get_chan15_raw(msg); + rc_channels->chan16_raw = mavlink_msg_rc_channels_get_chan16_raw(msg); + rc_channels->chan17_raw = mavlink_msg_rc_channels_get_chan17_raw(msg); + rc_channels->chan18_raw = mavlink_msg_rc_channels_get_chan18_raw(msg); + rc_channels->chancount = mavlink_msg_rc_channels_get_chancount(msg); + rc_channels->rssi = mavlink_msg_rc_channels_get_rssi(msg); +#else + memcpy(rc_channels, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h new file mode 100644 index 0000000..0324706 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h @@ -0,0 +1,425 @@ +// MESSAGE RC_CHANNELS_OVERRIDE PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70 + +typedef struct __mavlink_rc_channels_override_t +{ + uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_rc_channels_override_t; + +#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18 +#define MAVLINK_MSG_ID_70_LEN 18 + +#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC 124 +#define MAVLINK_MSG_ID_70_CRC 124 + + + +#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \ + "RC_CHANNELS_OVERRIDE", \ + 10, \ + { { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a rc_channels_override message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN]; + _mav_put_uint16_t(buf, 0, chan1_raw); + _mav_put_uint16_t(buf, 2, chan2_raw); + _mav_put_uint16_t(buf, 4, chan3_raw); + _mav_put_uint16_t(buf, 6, chan4_raw); + _mav_put_uint16_t(buf, 8, chan5_raw); + _mav_put_uint16_t(buf, 10, chan6_raw); + _mav_put_uint16_t(buf, 12, chan7_raw); + _mav_put_uint16_t(buf, 14, chan8_raw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#else + mavlink_rc_channels_override_t packet; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif +} + +/** + * @brief Pack a rc_channels_override message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN]; + _mav_put_uint16_t(buf, 0, chan1_raw); + _mav_put_uint16_t(buf, 2, chan2_raw); + _mav_put_uint16_t(buf, 4, chan3_raw); + _mav_put_uint16_t(buf, 6, chan4_raw); + _mav_put_uint16_t(buf, 8, chan5_raw); + _mav_put_uint16_t(buf, 10, chan6_raw); + _mav_put_uint16_t(buf, 12, chan7_raw); + _mav_put_uint16_t(buf, 14, chan8_raw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#else + mavlink_rc_channels_override_t packet; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif +} + +/** + * @brief Encode a rc_channels_override struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rc_channels_override C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override) +{ + return mavlink_msg_rc_channels_override_pack(system_id, component_id, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw); +} + +/** + * @brief Encode a rc_channels_override struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rc_channels_override C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_override_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override) +{ + return mavlink_msg_rc_channels_override_pack_chan(system_id, component_id, chan, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw); +} + +/** + * @brief Send a rc_channels_override message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_override_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN]; + _mav_put_uint16_t(buf, 0, chan1_raw); + _mav_put_uint16_t(buf, 2, chan2_raw); + _mav_put_uint16_t(buf, 4, chan3_raw); + _mav_put_uint16_t(buf, 6, chan4_raw); + _mav_put_uint16_t(buf, 8, chan5_raw); + _mav_put_uint16_t(buf, 10, chan6_raw); + _mav_put_uint16_t(buf, 12, chan7_raw); + _mav_put_uint16_t(buf, 14, chan8_raw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif +#else + mavlink_rc_channels_override_t packet; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rc_channels_override_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, chan1_raw); + _mav_put_uint16_t(buf, 2, chan2_raw); + _mav_put_uint16_t(buf, 4, chan3_raw); + _mav_put_uint16_t(buf, 6, chan4_raw); + _mav_put_uint16_t(buf, 8, chan5_raw); + _mav_put_uint16_t(buf, 10, chan6_raw); + _mav_put_uint16_t(buf, 12, chan7_raw); + _mav_put_uint16_t(buf, 14, chan8_raw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif +#else + mavlink_rc_channels_override_t *packet = (mavlink_rc_channels_override_t *)msgbuf; + packet->chan1_raw = chan1_raw; + packet->chan2_raw = chan2_raw; + packet->chan3_raw = chan3_raw; + packet->chan4_raw = chan4_raw; + packet->chan5_raw = chan5_raw; + packet->chan6_raw = chan6_raw; + packet->chan7_raw = chan7_raw; + packet->chan8_raw = chan8_raw; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RC_CHANNELS_OVERRIDE UNPACKING + + +/** + * @brief Get field target_system from rc_channels_override message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_rc_channels_override_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field target_component from rc_channels_override message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field chan1_raw from rc_channels_override message + * + * @return RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field chan2_raw from rc_channels_override message + * + * @return RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Get field chan3_raw from rc_channels_override message + * + * @return RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field chan4_raw from rc_channels_override message + * + * @return RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field chan5_raw from rc_channels_override message + * + * @return RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field chan6_raw from rc_channels_override message + * + * @return RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field chan7_raw from rc_channels_override message + * + * @return RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field chan8_raw from rc_channels_override message + * + * @return RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Decode a rc_channels_override message into a struct + * + * @param msg The message to decode + * @param rc_channels_override C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_override_decode(const mavlink_message_t* msg, mavlink_rc_channels_override_t* rc_channels_override) +{ +#if MAVLINK_NEED_BYTE_SWAP + rc_channels_override->chan1_raw = mavlink_msg_rc_channels_override_get_chan1_raw(msg); + rc_channels_override->chan2_raw = mavlink_msg_rc_channels_override_get_chan2_raw(msg); + rc_channels_override->chan3_raw = mavlink_msg_rc_channels_override_get_chan3_raw(msg); + rc_channels_override->chan4_raw = mavlink_msg_rc_channels_override_get_chan4_raw(msg); + rc_channels_override->chan5_raw = mavlink_msg_rc_channels_override_get_chan5_raw(msg); + rc_channels_override->chan6_raw = mavlink_msg_rc_channels_override_get_chan6_raw(msg); + rc_channels_override->chan7_raw = mavlink_msg_rc_channels_override_get_chan7_raw(msg); + rc_channels_override->chan8_raw = mavlink_msg_rc_channels_override_get_chan8_raw(msg); + rc_channels_override->target_system = mavlink_msg_rc_channels_override_get_target_system(msg); + rc_channels_override->target_component = mavlink_msg_rc_channels_override_get_target_component(msg); +#else + memcpy(rc_channels_override, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h new file mode 100644 index 0000000..d9ba874 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h @@ -0,0 +1,449 @@ +// MESSAGE RC_CHANNELS_RAW PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35 + +typedef struct __mavlink_rc_channels_raw_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + uint16_t chan1_raw; /*< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan2_raw; /*< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan3_raw; /*< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan4_raw; /*< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan5_raw; /*< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan6_raw; /*< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan7_raw; /*< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint16_t chan8_raw; /*< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.*/ + uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.*/ + uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/ +} mavlink_rc_channels_raw_t; + +#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22 +#define MAVLINK_MSG_ID_35_LEN 22 + +#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC 244 +#define MAVLINK_MSG_ID_35_CRC 244 + + + +#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \ + "RC_CHANNELS_RAW", \ + 11, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, time_boot_ms) }, \ + { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_raw_t, rssi) }, \ + } \ +} + + +/** + * @brief Pack a rc_channels_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#else + mavlink_rc_channels_raw_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif +} + +/** + * @brief Pack a rc_channels_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t port,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#else + mavlink_rc_channels_raw_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif +} + +/** + * @brief Encode a rc_channels_raw struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rc_channels_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) +{ + return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); +} + +/** + * @brief Encode a rc_channels_raw struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rc_channels_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) +{ + return mavlink_msg_rc_channels_raw_pack_chan(system_id, component_id, chan, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); +} + +/** + * @brief Send a rc_channels_raw message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif +#else + mavlink_rc_channels_raw_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.port = port; + packet.rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rc_channels_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif +#else + mavlink_rc_channels_raw_t *packet = (mavlink_rc_channels_raw_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->chan1_raw = chan1_raw; + packet->chan2_raw = chan2_raw; + packet->chan3_raw = chan3_raw; + packet->chan4_raw = chan4_raw; + packet->chan5_raw = chan5_raw; + packet->chan6_raw = chan6_raw; + packet->chan7_raw = chan7_raw; + packet->chan8_raw = chan8_raw; + packet->port = port; + packet->rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RC_CHANNELS_RAW UNPACKING + + +/** + * @brief Get field time_boot_ms from rc_channels_raw message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_rc_channels_raw_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field port from rc_channels_raw message + * + * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + */ +static inline uint8_t mavlink_msg_rc_channels_raw_get_port(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field chan1_raw from rc_channels_raw message + * + * @return RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field chan2_raw from rc_channels_raw message + * + * @return RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field chan3_raw from rc_channels_raw message + * + * @return RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field chan4_raw from rc_channels_raw message + * + * @return RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field chan5_raw from rc_channels_raw message + * + * @return RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field chan6_raw from rc_channels_raw message + * + * @return RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field chan7_raw from rc_channels_raw message + * + * @return RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field chan8_raw from rc_channels_raw message + * + * @return RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field rssi from rc_channels_raw message + * + * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + */ +static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 21); +} + +/** + * @brief Decode a rc_channels_raw message into a struct + * + * @param msg The message to decode + * @param rc_channels_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + rc_channels_raw->time_boot_ms = mavlink_msg_rc_channels_raw_get_time_boot_ms(msg); + rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg); + rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg); + rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg); + rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg); + rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg); + rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg); + rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg); + rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg); + rc_channels_raw->port = mavlink_msg_rc_channels_raw_get_port(msg); + rc_channels_raw->rssi = mavlink_msg_rc_channels_raw_get_rssi(msg); +#else + memcpy(rc_channels_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h new file mode 100644 index 0000000..c9d0c17 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h @@ -0,0 +1,449 @@ +// MESSAGE RC_CHANNELS_SCALED PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED 34 + +typedef struct __mavlink_rc_channels_scaled_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + int16_t chan1_scaled; /*< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + int16_t chan2_scaled; /*< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + int16_t chan3_scaled; /*< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + int16_t chan4_scaled; /*< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + int16_t chan5_scaled; /*< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + int16_t chan6_scaled; /*< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + int16_t chan7_scaled; /*< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + int16_t chan8_scaled; /*< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.*/ + uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.*/ + uint8_t rssi; /*< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.*/ +} mavlink_rc_channels_scaled_t; + +#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22 +#define MAVLINK_MSG_ID_34_LEN 22 + +#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC 237 +#define MAVLINK_MSG_ID_34_CRC 237 + + + +#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \ + "RC_CHANNELS_SCALED", \ + 11, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \ + { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \ + { "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \ + { "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \ + { "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \ + { "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \ + { "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \ + { "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \ + { "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \ + } \ +} + + +/** + * @brief Pack a rc_channels_scaled message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, chan1_scaled); + _mav_put_int16_t(buf, 6, chan2_scaled); + _mav_put_int16_t(buf, 8, chan3_scaled); + _mav_put_int16_t(buf, 10, chan4_scaled); + _mav_put_int16_t(buf, 12, chan5_scaled); + _mav_put_int16_t(buf, 14, chan6_scaled); + _mav_put_int16_t(buf, 16, chan7_scaled); + _mav_put_int16_t(buf, 18, chan8_scaled); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#else + mavlink_rc_channels_scaled_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_scaled = chan1_scaled; + packet.chan2_scaled = chan2_scaled; + packet.chan3_scaled = chan3_scaled; + packet.chan4_scaled = chan4_scaled; + packet.chan5_scaled = chan5_scaled; + packet.chan6_scaled = chan6_scaled; + packet.chan7_scaled = chan7_scaled; + packet.chan8_scaled = chan8_scaled; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif +} + +/** + * @brief Pack a rc_channels_scaled message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t port,int16_t chan1_scaled,int16_t chan2_scaled,int16_t chan3_scaled,int16_t chan4_scaled,int16_t chan5_scaled,int16_t chan6_scaled,int16_t chan7_scaled,int16_t chan8_scaled,uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, chan1_scaled); + _mav_put_int16_t(buf, 6, chan2_scaled); + _mav_put_int16_t(buf, 8, chan3_scaled); + _mav_put_int16_t(buf, 10, chan4_scaled); + _mav_put_int16_t(buf, 12, chan5_scaled); + _mav_put_int16_t(buf, 14, chan6_scaled); + _mav_put_int16_t(buf, 16, chan7_scaled); + _mav_put_int16_t(buf, 18, chan8_scaled); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#else + mavlink_rc_channels_scaled_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_scaled = chan1_scaled; + packet.chan2_scaled = chan2_scaled; + packet.chan3_scaled = chan3_scaled; + packet.chan4_scaled = chan4_scaled; + packet.chan5_scaled = chan5_scaled; + packet.chan6_scaled = chan6_scaled; + packet.chan7_scaled = chan7_scaled; + packet.chan8_scaled = chan8_scaled; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif +} + +/** + * @brief Encode a rc_channels_scaled struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rc_channels_scaled C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) +{ + return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); +} + +/** + * @brief Encode a rc_channels_scaled struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rc_channels_scaled C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) +{ + return mavlink_msg_rc_channels_scaled_pack_chan(system_id, component_id, chan, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); +} + +/** + * @brief Send a rc_channels_scaled message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, chan1_scaled); + _mav_put_int16_t(buf, 6, chan2_scaled); + _mav_put_int16_t(buf, 8, chan3_scaled); + _mav_put_int16_t(buf, 10, chan4_scaled); + _mav_put_int16_t(buf, 12, chan5_scaled); + _mav_put_int16_t(buf, 14, chan6_scaled); + _mav_put_int16_t(buf, 16, chan7_scaled); + _mav_put_int16_t(buf, 18, chan8_scaled); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif +#else + mavlink_rc_channels_scaled_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_scaled = chan1_scaled; + packet.chan2_scaled = chan2_scaled; + packet.chan3_scaled = chan3_scaled; + packet.chan4_scaled = chan4_scaled; + packet.chan5_scaled = chan5_scaled; + packet.chan6_scaled = chan6_scaled; + packet.chan7_scaled = chan7_scaled; + packet.chan8_scaled = chan8_scaled; + packet.port = port; + packet.rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rc_channels_scaled_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, chan1_scaled); + _mav_put_int16_t(buf, 6, chan2_scaled); + _mav_put_int16_t(buf, 8, chan3_scaled); + _mav_put_int16_t(buf, 10, chan4_scaled); + _mav_put_int16_t(buf, 12, chan5_scaled); + _mav_put_int16_t(buf, 14, chan6_scaled); + _mav_put_int16_t(buf, 16, chan7_scaled); + _mav_put_int16_t(buf, 18, chan8_scaled); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif +#else + mavlink_rc_channels_scaled_t *packet = (mavlink_rc_channels_scaled_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->chan1_scaled = chan1_scaled; + packet->chan2_scaled = chan2_scaled; + packet->chan3_scaled = chan3_scaled; + packet->chan4_scaled = chan4_scaled; + packet->chan5_scaled = chan5_scaled; + packet->chan6_scaled = chan6_scaled; + packet->chan7_scaled = chan7_scaled; + packet->chan8_scaled = chan8_scaled; + packet->port = port; + packet->rssi = rssi; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RC_CHANNELS_SCALED UNPACKING + + +/** + * @brief Get field time_boot_ms from rc_channels_scaled message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_rc_channels_scaled_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field port from rc_channels_scaled message + * + * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + */ +static inline uint8_t mavlink_msg_rc_channels_scaled_get_port(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field chan1_scaled from rc_channels_scaled message + * + * @return RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Get field chan2_scaled from rc_channels_scaled message + * + * @return RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 6); +} + +/** + * @brief Get field chan3_scaled from rc_channels_scaled message + * + * @return RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field chan4_scaled from rc_channels_scaled message + * + * @return RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field chan5_scaled from rc_channels_scaled message + * + * @return RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field chan6_scaled from rc_channels_scaled message + * + * @return RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field chan7_scaled from rc_channels_scaled message + * + * @return RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field chan8_scaled from rc_channels_scaled message + * + * @return RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field rssi from rc_channels_scaled message + * + * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + */ +static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 21); +} + +/** + * @brief Decode a rc_channels_scaled message into a struct + * + * @param msg The message to decode + * @param rc_channels_scaled C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t* msg, mavlink_rc_channels_scaled_t* rc_channels_scaled) +{ +#if MAVLINK_NEED_BYTE_SWAP + rc_channels_scaled->time_boot_ms = mavlink_msg_rc_channels_scaled_get_time_boot_ms(msg); + rc_channels_scaled->chan1_scaled = mavlink_msg_rc_channels_scaled_get_chan1_scaled(msg); + rc_channels_scaled->chan2_scaled = mavlink_msg_rc_channels_scaled_get_chan2_scaled(msg); + rc_channels_scaled->chan3_scaled = mavlink_msg_rc_channels_scaled_get_chan3_scaled(msg); + rc_channels_scaled->chan4_scaled = mavlink_msg_rc_channels_scaled_get_chan4_scaled(msg); + rc_channels_scaled->chan5_scaled = mavlink_msg_rc_channels_scaled_get_chan5_scaled(msg); + rc_channels_scaled->chan6_scaled = mavlink_msg_rc_channels_scaled_get_chan6_scaled(msg); + rc_channels_scaled->chan7_scaled = mavlink_msg_rc_channels_scaled_get_chan7_scaled(msg); + rc_channels_scaled->chan8_scaled = mavlink_msg_rc_channels_scaled_get_chan8_scaled(msg); + rc_channels_scaled->port = mavlink_msg_rc_channels_scaled_get_port(msg); + rc_channels_scaled->rssi = mavlink_msg_rc_channels_scaled_get_rssi(msg); +#else + memcpy(rc_channels_scaled, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_request_data_stream.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_request_data_stream.h new file mode 100644 index 0000000..c03c76a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_request_data_stream.h @@ -0,0 +1,305 @@ +// MESSAGE REQUEST_DATA_STREAM PACKING + +#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66 + +typedef struct __mavlink_request_data_stream_t +{ + uint16_t req_message_rate; /*< The requested message rate*/ + uint8_t target_system; /*< The target requested to send the message stream.*/ + uint8_t target_component; /*< The target requested to send the message stream.*/ + uint8_t req_stream_id; /*< The ID of the requested data stream*/ + uint8_t start_stop; /*< 1 to start sending, 0 to stop sending.*/ +} mavlink_request_data_stream_t; + +#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6 +#define MAVLINK_MSG_ID_66_LEN 6 + +#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC 148 +#define MAVLINK_MSG_ID_66_CRC 148 + + + +#define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \ + "REQUEST_DATA_STREAM", \ + 5, \ + { { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \ + { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \ + { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \ + } \ +} + + +/** + * @brief Pack a request_data_stream message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested data stream + * @param req_message_rate The requested message rate + * @param start_stop 1 to start sending, 0 to stop sending. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN]; + _mav_put_uint16_t(buf, 0, req_message_rate); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, req_stream_id); + _mav_put_uint8_t(buf, 5, start_stop); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#else + mavlink_request_data_stream_t packet; + packet.req_message_rate = req_message_rate; + packet.target_system = target_system; + packet.target_component = target_component; + packet.req_stream_id = req_stream_id; + packet.start_stop = start_stop; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif +} + +/** + * @brief Pack a request_data_stream message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested data stream + * @param req_message_rate The requested message rate + * @param start_stop 1 to start sending, 0 to stop sending. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t req_stream_id,uint16_t req_message_rate,uint8_t start_stop) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN]; + _mav_put_uint16_t(buf, 0, req_message_rate); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, req_stream_id); + _mav_put_uint8_t(buf, 5, start_stop); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#else + mavlink_request_data_stream_t packet; + packet.req_message_rate = req_message_rate; + packet.target_system = target_system; + packet.target_component = target_component; + packet.req_stream_id = req_stream_id; + packet.start_stop = start_stop; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif +} + +/** + * @brief Encode a request_data_stream struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param request_data_stream C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) +{ + return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); +} + +/** + * @brief Encode a request_data_stream struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param request_data_stream C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_request_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) +{ + return mavlink_msg_request_data_stream_pack_chan(system_id, component_id, chan, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); +} + +/** + * @brief Send a request_data_stream message + * @param chan MAVLink channel to send the message + * + * @param target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested data stream + * @param req_message_rate The requested message rate + * @param start_stop 1 to start sending, 0 to stop sending. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN]; + _mav_put_uint16_t(buf, 0, req_message_rate); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, req_stream_id); + _mav_put_uint8_t(buf, 5, start_stop); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif +#else + mavlink_request_data_stream_t packet; + packet.req_message_rate = req_message_rate; + packet.target_system = target_system; + packet.target_component = target_component; + packet.req_stream_id = req_stream_id; + packet.start_stop = start_stop; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_request_data_stream_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, req_message_rate); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, req_stream_id); + _mav_put_uint8_t(buf, 5, start_stop); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif +#else + mavlink_request_data_stream_t *packet = (mavlink_request_data_stream_t *)msgbuf; + packet->req_message_rate = req_message_rate; + packet->target_system = target_system; + packet->target_component = target_component; + packet->req_stream_id = req_stream_id; + packet->start_stop = start_stop; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE REQUEST_DATA_STREAM UNPACKING + + +/** + * @brief Get field target_system from request_data_stream message + * + * @return The target requested to send the message stream. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from request_data_stream message + * + * @return The target requested to send the message stream. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field req_stream_id from request_data_stream message + * + * @return The ID of the requested data stream + */ +static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field req_message_rate from request_data_stream message + * + * @return The requested message rate + */ +static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field start_stop from request_data_stream message + * + * @return 1 to start sending, 0 to stop sending. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Decode a request_data_stream message into a struct + * + * @param msg The message to decode + * @param request_data_stream C-struct to decode the message contents into + */ +static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream) +{ +#if MAVLINK_NEED_BYTE_SWAP + request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg); + request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg); + request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg); + request_data_stream->req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg); + request_data_stream->start_stop = mavlink_msg_request_data_stream_get_start_stop(msg); +#else + memcpy(request_data_stream, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_resource_request.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_resource_request.h new file mode 100644 index 0000000..3cbb560 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_resource_request.h @@ -0,0 +1,298 @@ +// MESSAGE RESOURCE_REQUEST PACKING + +#define MAVLINK_MSG_ID_RESOURCE_REQUEST 142 + +typedef struct __mavlink_resource_request_t +{ + uint8_t request_id; /*< Request ID. This ID should be re-used when sending back URI contents*/ + uint8_t uri_type; /*< The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary*/ + uint8_t uri[120]; /*< The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)*/ + uint8_t transfer_type; /*< The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream.*/ + uint8_t storage[120]; /*< The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP).*/ +} mavlink_resource_request_t; + +#define MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN 243 +#define MAVLINK_MSG_ID_142_LEN 243 + +#define MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC 72 +#define MAVLINK_MSG_ID_142_CRC 72 + +#define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_URI_LEN 120 +#define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_STORAGE_LEN 120 + +#define MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST { \ + "RESOURCE_REQUEST", \ + 5, \ + { { "request_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_resource_request_t, request_id) }, \ + { "uri_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_resource_request_t, uri_type) }, \ + { "uri", NULL, MAVLINK_TYPE_UINT8_T, 120, 2, offsetof(mavlink_resource_request_t, uri) }, \ + { "transfer_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 122, offsetof(mavlink_resource_request_t, transfer_type) }, \ + { "storage", NULL, MAVLINK_TYPE_UINT8_T, 120, 123, offsetof(mavlink_resource_request_t, storage) }, \ + } \ +} + + +/** + * @brief Pack a resource_request message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param request_id Request ID. This ID should be re-used when sending back URI contents + * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_resource_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN]; + _mav_put_uint8_t(buf, 0, request_id); + _mav_put_uint8_t(buf, 1, uri_type); + _mav_put_uint8_t(buf, 122, transfer_type); + _mav_put_uint8_t_array(buf, 2, uri, 120); + _mav_put_uint8_t_array(buf, 123, storage, 120); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#else + mavlink_resource_request_t packet; + packet.request_id = request_id; + packet.uri_type = uri_type; + packet.transfer_type = transfer_type; + mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120); + mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RESOURCE_REQUEST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif +} + +/** + * @brief Pack a resource_request message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param request_id Request ID. This ID should be re-used when sending back URI contents + * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_resource_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t request_id,uint8_t uri_type,const uint8_t *uri,uint8_t transfer_type,const uint8_t *storage) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN]; + _mav_put_uint8_t(buf, 0, request_id); + _mav_put_uint8_t(buf, 1, uri_type); + _mav_put_uint8_t(buf, 122, transfer_type); + _mav_put_uint8_t_array(buf, 2, uri, 120); + _mav_put_uint8_t_array(buf, 123, storage, 120); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#else + mavlink_resource_request_t packet; + packet.request_id = request_id; + packet.uri_type = uri_type; + packet.transfer_type = transfer_type; + mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120); + mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_RESOURCE_REQUEST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif +} + +/** + * @brief Encode a resource_request struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param resource_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_resource_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_resource_request_t* resource_request) +{ + return mavlink_msg_resource_request_pack(system_id, component_id, msg, resource_request->request_id, resource_request->uri_type, resource_request->uri, resource_request->transfer_type, resource_request->storage); +} + +/** + * @brief Encode a resource_request struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param resource_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_resource_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_resource_request_t* resource_request) +{ + return mavlink_msg_resource_request_pack_chan(system_id, component_id, chan, msg, resource_request->request_id, resource_request->uri_type, resource_request->uri, resource_request->transfer_type, resource_request->storage); +} + +/** + * @brief Send a resource_request message + * @param chan MAVLink channel to send the message + * + * @param request_id Request ID. This ID should be re-used when sending back URI contents + * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_resource_request_send(mavlink_channel_t chan, uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN]; + _mav_put_uint8_t(buf, 0, request_id); + _mav_put_uint8_t(buf, 1, uri_type); + _mav_put_uint8_t(buf, 122, transfer_type); + _mav_put_uint8_t_array(buf, 2, uri, 120); + _mav_put_uint8_t_array(buf, 123, storage, 120); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif +#else + mavlink_resource_request_t packet; + packet.request_id = request_id; + packet.uri_type = uri_type; + packet.transfer_type = transfer_type; + mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120); + mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_resource_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, request_id); + _mav_put_uint8_t(buf, 1, uri_type); + _mav_put_uint8_t(buf, 122, transfer_type); + _mav_put_uint8_t_array(buf, 2, uri, 120); + _mav_put_uint8_t_array(buf, 123, storage, 120); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif +#else + mavlink_resource_request_t *packet = (mavlink_resource_request_t *)msgbuf; + packet->request_id = request_id; + packet->uri_type = uri_type; + packet->transfer_type = transfer_type; + mav_array_memcpy(packet->uri, uri, sizeof(uint8_t)*120); + mav_array_memcpy(packet->storage, storage, sizeof(uint8_t)*120); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE RESOURCE_REQUEST UNPACKING + + +/** + * @brief Get field request_id from resource_request message + * + * @return Request ID. This ID should be re-used when sending back URI contents + */ +static inline uint8_t mavlink_msg_resource_request_get_request_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field uri_type from resource_request message + * + * @return The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + */ +static inline uint8_t mavlink_msg_resource_request_get_uri_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field uri from resource_request message + * + * @return The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + */ +static inline uint16_t mavlink_msg_resource_request_get_uri(const mavlink_message_t* msg, uint8_t *uri) +{ + return _MAV_RETURN_uint8_t_array(msg, uri, 120, 2); +} + +/** + * @brief Get field transfer_type from resource_request message + * + * @return The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + */ +static inline uint8_t mavlink_msg_resource_request_get_transfer_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 122); +} + +/** + * @brief Get field storage from resource_request message + * + * @return The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + */ +static inline uint16_t mavlink_msg_resource_request_get_storage(const mavlink_message_t* msg, uint8_t *storage) +{ + return _MAV_RETURN_uint8_t_array(msg, storage, 120, 123); +} + +/** + * @brief Decode a resource_request message into a struct + * + * @param msg The message to decode + * @param resource_request C-struct to decode the message contents into + */ +static inline void mavlink_msg_resource_request_decode(const mavlink_message_t* msg, mavlink_resource_request_t* resource_request) +{ +#if MAVLINK_NEED_BYTE_SWAP + resource_request->request_id = mavlink_msg_resource_request_get_request_id(msg); + resource_request->uri_type = mavlink_msg_resource_request_get_uri_type(msg); + mavlink_msg_resource_request_get_uri(msg, resource_request->uri); + resource_request->transfer_type = mavlink_msg_resource_request_get_transfer_type(msg); + mavlink_msg_resource_request_get_storage(msg, resource_request->storage); +#else + memcpy(resource_request, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h new file mode 100644 index 0000000..e0722c1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h @@ -0,0 +1,353 @@ +// MESSAGE SAFETY_ALLOWED_AREA PACKING + +#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55 + +typedef struct __mavlink_safety_allowed_area_t +{ + float p1x; /*< x position 1 / Latitude 1*/ + float p1y; /*< y position 1 / Longitude 1*/ + float p1z; /*< z position 1 / Altitude 1*/ + float p2x; /*< x position 2 / Latitude 2*/ + float p2y; /*< y position 2 / Longitude 2*/ + float p2z; /*< z position 2 / Altitude 2*/ + uint8_t frame; /*< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.*/ +} mavlink_safety_allowed_area_t; + +#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25 +#define MAVLINK_MSG_ID_55_LEN 25 + +#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC 3 +#define MAVLINK_MSG_ID_55_CRC 3 + + + +#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \ + "SAFETY_ALLOWED_AREA", \ + 7, \ + { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ + { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ + { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ + { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ + { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ + { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ + } \ +} + + +/** + * @brief Pack a safety_allowed_area message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#else + mavlink_safety_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif +} + +/** + * @brief Pack a safety_allowed_area message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#else + mavlink_safety_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif +} + +/** + * @brief Encode a safety_allowed_area struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param safety_allowed_area C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) +{ + return mavlink_msg_safety_allowed_area_pack(system_id, component_id, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); +} + +/** + * @brief Encode a safety_allowed_area struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param safety_allowed_area C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_safety_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) +{ + return mavlink_msg_safety_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); +} + +/** + * @brief Send a safety_allowed_area message + * @param chan MAVLink channel to send the message + * + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif +#else + mavlink_safety_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.frame = frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_safety_allowed_area_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif +#else + mavlink_safety_allowed_area_t *packet = (mavlink_safety_allowed_area_t *)msgbuf; + packet->p1x = p1x; + packet->p1y = p1y; + packet->p1z = p1z; + packet->p2x = p2x; + packet->p2y = p2y; + packet->p2z = p2z; + packet->frame = frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SAFETY_ALLOWED_AREA UNPACKING + + +/** + * @brief Get field frame from safety_allowed_area message + * + * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + */ +static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field p1x from safety_allowed_area message + * + * @return x position 1 / Latitude 1 + */ +static inline float mavlink_msg_safety_allowed_area_get_p1x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field p1y from safety_allowed_area message + * + * @return y position 1 / Longitude 1 + */ +static inline float mavlink_msg_safety_allowed_area_get_p1y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field p1z from safety_allowed_area message + * + * @return z position 1 / Altitude 1 + */ +static inline float mavlink_msg_safety_allowed_area_get_p1z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field p2x from safety_allowed_area message + * + * @return x position 2 / Latitude 2 + */ +static inline float mavlink_msg_safety_allowed_area_get_p2x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field p2y from safety_allowed_area message + * + * @return y position 2 / Longitude 2 + */ +static inline float mavlink_msg_safety_allowed_area_get_p2y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field p2z from safety_allowed_area message + * + * @return z position 2 / Altitude 2 + */ +static inline float mavlink_msg_safety_allowed_area_get_p2z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Decode a safety_allowed_area message into a struct + * + * @param msg The message to decode + * @param safety_allowed_area C-struct to decode the message contents into + */ +static inline void mavlink_msg_safety_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_allowed_area_t* safety_allowed_area) +{ +#if MAVLINK_NEED_BYTE_SWAP + safety_allowed_area->p1x = mavlink_msg_safety_allowed_area_get_p1x(msg); + safety_allowed_area->p1y = mavlink_msg_safety_allowed_area_get_p1y(msg); + safety_allowed_area->p1z = mavlink_msg_safety_allowed_area_get_p1z(msg); + safety_allowed_area->p2x = mavlink_msg_safety_allowed_area_get_p2x(msg); + safety_allowed_area->p2y = mavlink_msg_safety_allowed_area_get_p2y(msg); + safety_allowed_area->p2z = mavlink_msg_safety_allowed_area_get_p2z(msg); + safety_allowed_area->frame = mavlink_msg_safety_allowed_area_get_frame(msg); +#else + memcpy(safety_allowed_area, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h new file mode 100644 index 0000000..1fdfc77 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h @@ -0,0 +1,401 @@ +// MESSAGE SAFETY_SET_ALLOWED_AREA PACKING + +#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54 + +typedef struct __mavlink_safety_set_allowed_area_t +{ + float p1x; /*< x position 1 / Latitude 1*/ + float p1y; /*< y position 1 / Longitude 1*/ + float p1z; /*< z position 1 / Altitude 1*/ + float p2x; /*< x position 2 / Latitude 2*/ + float p2y; /*< y position 2 / Longitude 2*/ + float p2z; /*< z position 2 / Altitude 2*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t frame; /*< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.*/ +} mavlink_safety_set_allowed_area_t; + +#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27 +#define MAVLINK_MSG_ID_54_LEN 27 + +#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC 15 +#define MAVLINK_MSG_ID_54_CRC 15 + + + +#define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \ + "SAFETY_SET_ALLOWED_AREA", \ + 9, \ + { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ + { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \ + { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \ + { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \ + { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \ + { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ + } \ +} + + +/** + * @brief Pack a safety_set_allowed_area message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, target_system); + _mav_put_uint8_t(buf, 25, target_component); + _mav_put_uint8_t(buf, 26, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#else + mavlink_safety_set_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif +} + +/** + * @brief Pack a safety_set_allowed_area message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, target_system); + _mav_put_uint8_t(buf, 25, target_component); + _mav_put_uint8_t(buf, 26, frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#else + mavlink_safety_set_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif +} + +/** + * @brief Encode a safety_set_allowed_area struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param safety_set_allowed_area C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) +{ + return mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); +} + +/** + * @brief Encode a safety_set_allowed_area struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param safety_set_allowed_area C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) +{ + return mavlink_msg_safety_set_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); +} + +/** + * @brief Send a safety_set_allowed_area message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_safety_set_allowed_area_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, target_system); + _mav_put_uint8_t(buf, 25, target_component); + _mav_put_uint8_t(buf, 26, frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif +#else + mavlink_safety_set_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_safety_set_allowed_area_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, target_system); + _mav_put_uint8_t(buf, 25, target_component); + _mav_put_uint8_t(buf, 26, frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif +#else + mavlink_safety_set_allowed_area_t *packet = (mavlink_safety_set_allowed_area_t *)msgbuf; + packet->p1x = p1x; + packet->p1y = p1y; + packet->p1z = p1z; + packet->p2x = p2x; + packet->p2y = p2y; + packet->p2z = p2z; + packet->target_system = target_system; + packet->target_component = target_component; + packet->frame = frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SAFETY_SET_ALLOWED_AREA UNPACKING + + +/** + * @brief Get field target_system from safety_set_allowed_area message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field target_component from safety_set_allowed_area message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 25); +} + +/** + * @brief Get field frame from safety_set_allowed_area message + * + * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + */ +static inline uint8_t mavlink_msg_safety_set_allowed_area_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 26); +} + +/** + * @brief Get field p1x from safety_set_allowed_area message + * + * @return x position 1 / Latitude 1 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p1x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field p1y from safety_set_allowed_area message + * + * @return y position 1 / Longitude 1 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p1y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field p1z from safety_set_allowed_area message + * + * @return z position 1 / Altitude 1 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p1z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field p2x from safety_set_allowed_area message + * + * @return x position 2 / Latitude 2 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p2x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field p2y from safety_set_allowed_area message + * + * @return y position 2 / Longitude 2 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p2y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field p2z from safety_set_allowed_area message + * + * @return z position 2 / Altitude 2 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p2z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Decode a safety_set_allowed_area message into a struct + * + * @param msg The message to decode + * @param safety_set_allowed_area C-struct to decode the message contents into + */ +static inline void mavlink_msg_safety_set_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_set_allowed_area_t* safety_set_allowed_area) +{ +#if MAVLINK_NEED_BYTE_SWAP + safety_set_allowed_area->p1x = mavlink_msg_safety_set_allowed_area_get_p1x(msg); + safety_set_allowed_area->p1y = mavlink_msg_safety_set_allowed_area_get_p1y(msg); + safety_set_allowed_area->p1z = mavlink_msg_safety_set_allowed_area_get_p1z(msg); + safety_set_allowed_area->p2x = mavlink_msg_safety_set_allowed_area_get_p2x(msg); + safety_set_allowed_area->p2y = mavlink_msg_safety_set_allowed_area_get_p2y(msg); + safety_set_allowed_area->p2z = mavlink_msg_safety_set_allowed_area_get_p2z(msg); + safety_set_allowed_area->target_system = mavlink_msg_safety_set_allowed_area_get_target_system(msg); + safety_set_allowed_area->target_component = mavlink_msg_safety_set_allowed_area_get_target_component(msg); + safety_set_allowed_area->frame = mavlink_msg_safety_set_allowed_area_get_frame(msg); +#else + memcpy(safety_set_allowed_area, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_imu.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_imu.h new file mode 100644 index 0000000..b828030 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_imu.h @@ -0,0 +1,425 @@ +// MESSAGE SCALED_IMU PACKING + +#define MAVLINK_MSG_ID_SCALED_IMU 26 + +typedef struct __mavlink_scaled_imu_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + int16_t xacc; /*< X acceleration (mg)*/ + int16_t yacc; /*< Y acceleration (mg)*/ + int16_t zacc; /*< Z acceleration (mg)*/ + int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/ + int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/ + int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/ + int16_t xmag; /*< X Magnetic field (milli tesla)*/ + int16_t ymag; /*< Y Magnetic field (milli tesla)*/ + int16_t zmag; /*< Z Magnetic field (milli tesla)*/ +} mavlink_scaled_imu_t; + +#define MAVLINK_MSG_ID_SCALED_IMU_LEN 22 +#define MAVLINK_MSG_ID_26_LEN 22 + +#define MAVLINK_MSG_ID_SCALED_IMU_CRC 170 +#define MAVLINK_MSG_ID_26_CRC 170 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \ + "SCALED_IMU", \ + 10, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \ + } \ +} + + +/** + * @brief Pack a scaled_imu message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#else + mavlink_scaled_imu_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif +} + +/** + * @brief Pack a scaled_imu message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#else + mavlink_scaled_imu_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif +} + +/** + * @brief Encode a scaled_imu struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param scaled_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu) +{ + return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag); +} + +/** + * @brief Encode a scaled_imu struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param scaled_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu) +{ + return mavlink_msg_scaled_imu_pack_chan(system_id, component_id, chan, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag); +} + +/** + * @brief Send a scaled_imu message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif +#else + mavlink_scaled_imu_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SCALED_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_scaled_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif +#else + mavlink_scaled_imu_t *packet = (mavlink_scaled_imu_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->xmag = xmag; + packet->ymag = ymag; + packet->zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SCALED_IMU UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_imu message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_imu_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field xacc from scaled_imu message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Get field yacc from scaled_imu message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 6); +} + +/** + * @brief Get field zacc from scaled_imu message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field xgyro from scaled_imu message + * + * @return Angular speed around X axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field ygyro from scaled_imu message + * + * @return Angular speed around Y axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field zgyro from scaled_imu message + * + * @return Angular speed around Z axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field xmag from scaled_imu message + * + * @return X Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field ymag from scaled_imu message + * + * @return Y Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field zmag from scaled_imu message + * + * @return Z Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Decode a scaled_imu message into a struct + * + * @param msg The message to decode + * @param scaled_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_imu_decode(const mavlink_message_t* msg, mavlink_scaled_imu_t* scaled_imu) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_imu->time_boot_ms = mavlink_msg_scaled_imu_get_time_boot_ms(msg); + scaled_imu->xacc = mavlink_msg_scaled_imu_get_xacc(msg); + scaled_imu->yacc = mavlink_msg_scaled_imu_get_yacc(msg); + scaled_imu->zacc = mavlink_msg_scaled_imu_get_zacc(msg); + scaled_imu->xgyro = mavlink_msg_scaled_imu_get_xgyro(msg); + scaled_imu->ygyro = mavlink_msg_scaled_imu_get_ygyro(msg); + scaled_imu->zgyro = mavlink_msg_scaled_imu_get_zgyro(msg); + scaled_imu->xmag = mavlink_msg_scaled_imu_get_xmag(msg); + scaled_imu->ymag = mavlink_msg_scaled_imu_get_ymag(msg); + scaled_imu->zmag = mavlink_msg_scaled_imu_get_zmag(msg); +#else + memcpy(scaled_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_IMU_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h new file mode 100644 index 0000000..1d8fa32 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h @@ -0,0 +1,425 @@ +// MESSAGE SCALED_IMU2 PACKING + +#define MAVLINK_MSG_ID_SCALED_IMU2 116 + +typedef struct __mavlink_scaled_imu2_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + int16_t xacc; /*< X acceleration (mg)*/ + int16_t yacc; /*< Y acceleration (mg)*/ + int16_t zacc; /*< Z acceleration (mg)*/ + int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/ + int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/ + int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/ + int16_t xmag; /*< X Magnetic field (milli tesla)*/ + int16_t ymag; /*< Y Magnetic field (milli tesla)*/ + int16_t zmag; /*< Z Magnetic field (milli tesla)*/ +} mavlink_scaled_imu2_t; + +#define MAVLINK_MSG_ID_SCALED_IMU2_LEN 22 +#define MAVLINK_MSG_ID_116_LEN 22 + +#define MAVLINK_MSG_ID_SCALED_IMU2_CRC 76 +#define MAVLINK_MSG_ID_116_CRC 76 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_IMU2 { \ + "SCALED_IMU2", \ + 10, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu2_t, time_boot_ms) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu2_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu2_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu2_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu2_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu2_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu2_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu2_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu2_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu2_t, zmag) }, \ + } \ +} + + +/** + * @brief Pack a scaled_imu2 message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#else + mavlink_scaled_imu2_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +} + +/** + * @brief Pack a scaled_imu2 message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#else + mavlink_scaled_imu2_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +} + +/** + * @brief Encode a scaled_imu2 struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param scaled_imu2 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2) +{ + return mavlink_msg_scaled_imu2_pack(system_id, component_id, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag); +} + +/** + * @brief Encode a scaled_imu2 struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param scaled_imu2 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2) +{ + return mavlink_msg_scaled_imu2_pack_chan(system_id, component_id, chan, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag); +} + +/** + * @brief Send a scaled_imu2 message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_imu2_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +#else + mavlink_scaled_imu2_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SCALED_IMU2_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_scaled_imu2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +#else + mavlink_scaled_imu2_t *packet = (mavlink_scaled_imu2_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->xmag = xmag; + packet->ymag = ymag; + packet->zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SCALED_IMU2 UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_imu2 message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_imu2_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field xacc from scaled_imu2 message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Get field yacc from scaled_imu2 message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 6); +} + +/** + * @brief Get field zacc from scaled_imu2 message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field xgyro from scaled_imu2 message + * + * @return Angular speed around X axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field ygyro from scaled_imu2 message + * + * @return Angular speed around Y axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field zgyro from scaled_imu2 message + * + * @return Angular speed around Z axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field xmag from scaled_imu2 message + * + * @return X Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field ymag from scaled_imu2 message + * + * @return Y Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field zmag from scaled_imu2 message + * + * @return Z Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu2_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Decode a scaled_imu2 message into a struct + * + * @param msg The message to decode + * @param scaled_imu2 C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_imu2_decode(const mavlink_message_t* msg, mavlink_scaled_imu2_t* scaled_imu2) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_imu2->time_boot_ms = mavlink_msg_scaled_imu2_get_time_boot_ms(msg); + scaled_imu2->xacc = mavlink_msg_scaled_imu2_get_xacc(msg); + scaled_imu2->yacc = mavlink_msg_scaled_imu2_get_yacc(msg); + scaled_imu2->zacc = mavlink_msg_scaled_imu2_get_zacc(msg); + scaled_imu2->xgyro = mavlink_msg_scaled_imu2_get_xgyro(msg); + scaled_imu2->ygyro = mavlink_msg_scaled_imu2_get_ygyro(msg); + scaled_imu2->zgyro = mavlink_msg_scaled_imu2_get_zgyro(msg); + scaled_imu2->xmag = mavlink_msg_scaled_imu2_get_xmag(msg); + scaled_imu2->ymag = mavlink_msg_scaled_imu2_get_ymag(msg); + scaled_imu2->zmag = mavlink_msg_scaled_imu2_get_zmag(msg); +#else + memcpy(scaled_imu2, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_IMU2_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_imu3.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_imu3.h new file mode 100644 index 0000000..2ae3093 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_imu3.h @@ -0,0 +1,425 @@ +// MESSAGE SCALED_IMU3 PACKING + +#define MAVLINK_MSG_ID_SCALED_IMU3 129 + +typedef struct __mavlink_scaled_imu3_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + int16_t xacc; /*< X acceleration (mg)*/ + int16_t yacc; /*< Y acceleration (mg)*/ + int16_t zacc; /*< Z acceleration (mg)*/ + int16_t xgyro; /*< Angular speed around X axis (millirad /sec)*/ + int16_t ygyro; /*< Angular speed around Y axis (millirad /sec)*/ + int16_t zgyro; /*< Angular speed around Z axis (millirad /sec)*/ + int16_t xmag; /*< X Magnetic field (milli tesla)*/ + int16_t ymag; /*< Y Magnetic field (milli tesla)*/ + int16_t zmag; /*< Z Magnetic field (milli tesla)*/ +} mavlink_scaled_imu3_t; + +#define MAVLINK_MSG_ID_SCALED_IMU3_LEN 22 +#define MAVLINK_MSG_ID_129_LEN 22 + +#define MAVLINK_MSG_ID_SCALED_IMU3_CRC 46 +#define MAVLINK_MSG_ID_129_CRC 46 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_IMU3 { \ + "SCALED_IMU3", \ + 10, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu3_t, time_boot_ms) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu3_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu3_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu3_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu3_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu3_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu3_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu3_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu3_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu3_t, zmag) }, \ + } \ +} + + +/** + * @brief Pack a scaled_imu3 message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu3_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU3_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#else + mavlink_scaled_imu3_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU3; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif +} + +/** + * @brief Pack a scaled_imu3 message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu3_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU3_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#else + mavlink_scaled_imu3_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU3; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif +} + +/** + * @brief Encode a scaled_imu3 struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param scaled_imu3 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu3_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu3_t* scaled_imu3) +{ + return mavlink_msg_scaled_imu3_pack(system_id, component_id, msg, scaled_imu3->time_boot_ms, scaled_imu3->xacc, scaled_imu3->yacc, scaled_imu3->zacc, scaled_imu3->xgyro, scaled_imu3->ygyro, scaled_imu3->zgyro, scaled_imu3->xmag, scaled_imu3->ymag, scaled_imu3->zmag); +} + +/** + * @brief Encode a scaled_imu3 struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param scaled_imu3 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu3_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu3_t* scaled_imu3) +{ + return mavlink_msg_scaled_imu3_pack_chan(system_id, component_id, chan, msg, scaled_imu3->time_boot_ms, scaled_imu3->xacc, scaled_imu3->yacc, scaled_imu3->zacc, scaled_imu3->xgyro, scaled_imu3->ygyro, scaled_imu3->zgyro, scaled_imu3->xmag, scaled_imu3->ymag, scaled_imu3->zmag); +} + +/** + * @brief Send a scaled_imu3 message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_imu3_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_IMU3_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif +#else + mavlink_scaled_imu3_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SCALED_IMU3_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_scaled_imu3_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif +#else + mavlink_scaled_imu3_t *packet = (mavlink_scaled_imu3_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->xmag = xmag; + packet->ymag = ymag; + packet->zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SCALED_IMU3 UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_imu3 message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_imu3_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field xacc from scaled_imu3 message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Get field yacc from scaled_imu3 message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 6); +} + +/** + * @brief Get field zacc from scaled_imu3 message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field xgyro from scaled_imu3 message + * + * @return Angular speed around X axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field ygyro from scaled_imu3 message + * + * @return Angular speed around Y axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field zgyro from scaled_imu3 message + * + * @return Angular speed around Z axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field xmag from scaled_imu3 message + * + * @return X Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field ymag from scaled_imu3 message + * + * @return Y Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field zmag from scaled_imu3 message + * + * @return Z Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu3_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Decode a scaled_imu3 message into a struct + * + * @param msg The message to decode + * @param scaled_imu3 C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_imu3_decode(const mavlink_message_t* msg, mavlink_scaled_imu3_t* scaled_imu3) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_imu3->time_boot_ms = mavlink_msg_scaled_imu3_get_time_boot_ms(msg); + scaled_imu3->xacc = mavlink_msg_scaled_imu3_get_xacc(msg); + scaled_imu3->yacc = mavlink_msg_scaled_imu3_get_yacc(msg); + scaled_imu3->zacc = mavlink_msg_scaled_imu3_get_zacc(msg); + scaled_imu3->xgyro = mavlink_msg_scaled_imu3_get_xgyro(msg); + scaled_imu3->ygyro = mavlink_msg_scaled_imu3_get_ygyro(msg); + scaled_imu3->zgyro = mavlink_msg_scaled_imu3_get_zgyro(msg); + scaled_imu3->xmag = mavlink_msg_scaled_imu3_get_xmag(msg); + scaled_imu3->ymag = mavlink_msg_scaled_imu3_get_ymag(msg); + scaled_imu3->zmag = mavlink_msg_scaled_imu3_get_zmag(msg); +#else + memcpy(scaled_imu3, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_IMU3_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h new file mode 100644 index 0000000..5ddad6d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h @@ -0,0 +1,281 @@ +// MESSAGE SCALED_PRESSURE PACKING + +#define MAVLINK_MSG_ID_SCALED_PRESSURE 29 + +typedef struct __mavlink_scaled_pressure_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float press_abs; /*< Absolute pressure (hectopascal)*/ + float press_diff; /*< Differential pressure 1 (hectopascal)*/ + int16_t temperature; /*< Temperature measurement (0.01 degrees celsius)*/ +} mavlink_scaled_pressure_t; + +#define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 14 +#define MAVLINK_MSG_ID_29_LEN 14 + +#define MAVLINK_MSG_ID_SCALED_PRESSURE_CRC 115 +#define MAVLINK_MSG_ID_29_CRC 115 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \ + "SCALED_PRESSURE", \ + 4, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \ + { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \ + { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a scaled_pressure message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#else + mavlink_scaled_pressure_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif +} + +/** + * @brief Pack a scaled_pressure message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#else + mavlink_scaled_pressure_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif +} + +/** + * @brief Encode a scaled_pressure struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param scaled_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) +{ + return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); +} + +/** + * @brief Encode a scaled_pressure struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param scaled_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) +{ + return mavlink_msg_scaled_pressure_pack_chan(system_id, component_id, chan, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); +} + +/** + * @brief Send a scaled_pressure message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif +#else + mavlink_scaled_pressure_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SCALED_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_scaled_pressure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif +#else + mavlink_scaled_pressure_t *packet = (mavlink_scaled_pressure_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->press_abs = press_abs; + packet->press_diff = press_diff; + packet->temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SCALED_PRESSURE UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_pressure message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_pressure_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field press_abs from scaled_pressure message + * + * @return Absolute pressure (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field press_diff from scaled_pressure message + * + * @return Differential pressure 1 (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field temperature from scaled_pressure message + * + * @return Temperature measurement (0.01 degrees celsius) + */ +static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Decode a scaled_pressure message into a struct + * + * @param msg The message to decode + * @param scaled_pressure C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_pressure->time_boot_ms = mavlink_msg_scaled_pressure_get_time_boot_ms(msg); + scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg); + scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg); + scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg); +#else + memcpy(scaled_pressure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_pressure2.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_pressure2.h new file mode 100644 index 0000000..c9ca5dc --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_pressure2.h @@ -0,0 +1,281 @@ +// MESSAGE SCALED_PRESSURE2 PACKING + +#define MAVLINK_MSG_ID_SCALED_PRESSURE2 137 + +typedef struct __mavlink_scaled_pressure2_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float press_abs; /*< Absolute pressure (hectopascal)*/ + float press_diff; /*< Differential pressure 1 (hectopascal)*/ + int16_t temperature; /*< Temperature measurement (0.01 degrees celsius)*/ +} mavlink_scaled_pressure2_t; + +#define MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN 14 +#define MAVLINK_MSG_ID_137_LEN 14 + +#define MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC 195 +#define MAVLINK_MSG_ID_137_CRC 195 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2 { \ + "SCALED_PRESSURE2", \ + 4, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure2_t, time_boot_ms) }, \ + { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure2_t, press_abs) }, \ + { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure2_t, press_diff) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure2_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a scaled_pressure2 message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#else + mavlink_scaled_pressure2_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE2; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif +} + +/** + * @brief Pack a scaled_pressure2 message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#else + mavlink_scaled_pressure2_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE2; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif +} + +/** + * @brief Encode a scaled_pressure2 struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param scaled_pressure2 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure2_t* scaled_pressure2) +{ + return mavlink_msg_scaled_pressure2_pack(system_id, component_id, msg, scaled_pressure2->time_boot_ms, scaled_pressure2->press_abs, scaled_pressure2->press_diff, scaled_pressure2->temperature); +} + +/** + * @brief Encode a scaled_pressure2 struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param scaled_pressure2 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure2_t* scaled_pressure2) +{ + return mavlink_msg_scaled_pressure2_pack_chan(system_id, component_id, chan, msg, scaled_pressure2->time_boot_ms, scaled_pressure2->press_abs, scaled_pressure2->press_diff, scaled_pressure2->temperature); +} + +/** + * @brief Send a scaled_pressure2 message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_pressure2_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif +#else + mavlink_scaled_pressure2_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_scaled_pressure2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif +#else + mavlink_scaled_pressure2_t *packet = (mavlink_scaled_pressure2_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->press_abs = press_abs; + packet->press_diff = press_diff; + packet->temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SCALED_PRESSURE2 UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_pressure2 message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_pressure2_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field press_abs from scaled_pressure2 message + * + * @return Absolute pressure (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure2_get_press_abs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field press_diff from scaled_pressure2 message + * + * @return Differential pressure 1 (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure2_get_press_diff(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field temperature from scaled_pressure2 message + * + * @return Temperature measurement (0.01 degrees celsius) + */ +static inline int16_t mavlink_msg_scaled_pressure2_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Decode a scaled_pressure2 message into a struct + * + * @param msg The message to decode + * @param scaled_pressure2 C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_pressure2_decode(const mavlink_message_t* msg, mavlink_scaled_pressure2_t* scaled_pressure2) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_pressure2->time_boot_ms = mavlink_msg_scaled_pressure2_get_time_boot_ms(msg); + scaled_pressure2->press_abs = mavlink_msg_scaled_pressure2_get_press_abs(msg); + scaled_pressure2->press_diff = mavlink_msg_scaled_pressure2_get_press_diff(msg); + scaled_pressure2->temperature = mavlink_msg_scaled_pressure2_get_temperature(msg); +#else + memcpy(scaled_pressure2, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_pressure3.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_pressure3.h new file mode 100644 index 0000000..62d46ae --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_scaled_pressure3.h @@ -0,0 +1,281 @@ +// MESSAGE SCALED_PRESSURE3 PACKING + +#define MAVLINK_MSG_ID_SCALED_PRESSURE3 143 + +typedef struct __mavlink_scaled_pressure3_t +{ + uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/ + float press_abs; /*< Absolute pressure (hectopascal)*/ + float press_diff; /*< Differential pressure 1 (hectopascal)*/ + int16_t temperature; /*< Temperature measurement (0.01 degrees celsius)*/ +} mavlink_scaled_pressure3_t; + +#define MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN 14 +#define MAVLINK_MSG_ID_143_LEN 14 + +#define MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC 131 +#define MAVLINK_MSG_ID_143_CRC 131 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3 { \ + "SCALED_PRESSURE3", \ + 4, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure3_t, time_boot_ms) }, \ + { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure3_t, press_abs) }, \ + { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure3_t, press_diff) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure3_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a scaled_pressure3 message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure3_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#else + mavlink_scaled_pressure3_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE3; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif +} + +/** + * @brief Pack a scaled_pressure3 message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure3_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#else + mavlink_scaled_pressure3_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE3; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif +} + +/** + * @brief Encode a scaled_pressure3 struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param scaled_pressure3 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure3_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure3_t* scaled_pressure3) +{ + return mavlink_msg_scaled_pressure3_pack(system_id, component_id, msg, scaled_pressure3->time_boot_ms, scaled_pressure3->press_abs, scaled_pressure3->press_diff, scaled_pressure3->temperature); +} + +/** + * @brief Encode a scaled_pressure3 struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param scaled_pressure3 C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure3_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure3_t* scaled_pressure3) +{ + return mavlink_msg_scaled_pressure3_pack_chan(system_id, component_id, chan, msg, scaled_pressure3->time_boot_ms, scaled_pressure3->press_abs, scaled_pressure3->press_diff, scaled_pressure3->temperature); +} + +/** + * @brief Send a scaled_pressure3 message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_pressure3_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif +#else + mavlink_scaled_pressure3_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_scaled_pressure3_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif +#else + mavlink_scaled_pressure3_t *packet = (mavlink_scaled_pressure3_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->press_abs = press_abs; + packet->press_diff = press_diff; + packet->temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SCALED_PRESSURE3 UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_pressure3 message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_pressure3_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field press_abs from scaled_pressure3 message + * + * @return Absolute pressure (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure3_get_press_abs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field press_diff from scaled_pressure3 message + * + * @return Differential pressure 1 (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure3_get_press_diff(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field temperature from scaled_pressure3 message + * + * @return Temperature measurement (0.01 degrees celsius) + */ +static inline int16_t mavlink_msg_scaled_pressure3_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Decode a scaled_pressure3 message into a struct + * + * @param msg The message to decode + * @param scaled_pressure3 C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_pressure3_decode(const mavlink_message_t* msg, mavlink_scaled_pressure3_t* scaled_pressure3) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_pressure3->time_boot_ms = mavlink_msg_scaled_pressure3_get_time_boot_ms(msg); + scaled_pressure3->press_abs = mavlink_msg_scaled_pressure3_get_press_abs(msg); + scaled_pressure3->press_diff = mavlink_msg_scaled_pressure3_get_press_diff(msg); + scaled_pressure3->temperature = mavlink_msg_scaled_pressure3_get_temperature(msg); +#else + memcpy(scaled_pressure3, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_serial_control.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_serial_control.h new file mode 100644 index 0000000..ab4f10f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_serial_control.h @@ -0,0 +1,321 @@ +// MESSAGE SERIAL_CONTROL PACKING + +#define MAVLINK_MSG_ID_SERIAL_CONTROL 126 + +typedef struct __mavlink_serial_control_t +{ + uint32_t baudrate; /*< Baudrate of transfer. Zero means no change.*/ + uint16_t timeout; /*< Timeout for reply data in milliseconds*/ + uint8_t device; /*< See SERIAL_CONTROL_DEV enum*/ + uint8_t flags; /*< See SERIAL_CONTROL_FLAG enum*/ + uint8_t count; /*< how many bytes in this transfer*/ + uint8_t data[70]; /*< serial data*/ +} mavlink_serial_control_t; + +#define MAVLINK_MSG_ID_SERIAL_CONTROL_LEN 79 +#define MAVLINK_MSG_ID_126_LEN 79 + +#define MAVLINK_MSG_ID_SERIAL_CONTROL_CRC 220 +#define MAVLINK_MSG_ID_126_CRC 220 + +#define MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN 70 + +#define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL { \ + "SERIAL_CONTROL", \ + 6, \ + { { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \ + { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \ + { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \ + { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \ + { "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \ + } \ +} + + +/** + * @brief Pack a serial_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param device See SERIAL_CONTROL_DEV enum + * @param flags See SERIAL_CONTROL_FLAG enum + * @param timeout Timeout for reply data in milliseconds + * @param baudrate Baudrate of transfer. Zero means no change. + * @param count how many bytes in this transfer + * @param data serial data + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_serial_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; + _mav_put_uint32_t(buf, 0, baudrate); + _mav_put_uint16_t(buf, 4, timeout); + _mav_put_uint8_t(buf, 6, device); + _mav_put_uint8_t(buf, 7, flags); + _mav_put_uint8_t(buf, 8, count); + _mav_put_uint8_t_array(buf, 9, data, 70); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#else + mavlink_serial_control_t packet; + packet.baudrate = baudrate; + packet.timeout = timeout; + packet.device = device; + packet.flags = flags; + packet.count = count; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif +} + +/** + * @brief Pack a serial_control message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param device See SERIAL_CONTROL_DEV enum + * @param flags See SERIAL_CONTROL_FLAG enum + * @param timeout Timeout for reply data in milliseconds + * @param baudrate Baudrate of transfer. Zero means no change. + * @param count how many bytes in this transfer + * @param data serial data + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_serial_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t device,uint8_t flags,uint16_t timeout,uint32_t baudrate,uint8_t count,const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; + _mav_put_uint32_t(buf, 0, baudrate); + _mav_put_uint16_t(buf, 4, timeout); + _mav_put_uint8_t(buf, 6, device); + _mav_put_uint8_t(buf, 7, flags); + _mav_put_uint8_t(buf, 8, count); + _mav_put_uint8_t_array(buf, 9, data, 70); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#else + mavlink_serial_control_t packet; + packet.baudrate = baudrate; + packet.timeout = timeout; + packet.device = device; + packet.flags = flags; + packet.count = count; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif +} + +/** + * @brief Encode a serial_control struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param serial_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_serial_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control) +{ + return mavlink_msg_serial_control_pack(system_id, component_id, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data); +} + +/** + * @brief Encode a serial_control struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param serial_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_serial_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control) +{ + return mavlink_msg_serial_control_pack_chan(system_id, component_id, chan, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data); +} + +/** + * @brief Send a serial_control message + * @param chan MAVLink channel to send the message + * + * @param device See SERIAL_CONTROL_DEV enum + * @param flags See SERIAL_CONTROL_FLAG enum + * @param timeout Timeout for reply data in milliseconds + * @param baudrate Baudrate of transfer. Zero means no change. + * @param count how many bytes in this transfer + * @param data serial data + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_serial_control_send(mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; + _mav_put_uint32_t(buf, 0, baudrate); + _mav_put_uint16_t(buf, 4, timeout); + _mav_put_uint8_t(buf, 6, device); + _mav_put_uint8_t(buf, 7, flags); + _mav_put_uint8_t(buf, 8, count); + _mav_put_uint8_t_array(buf, 9, data, 70); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif +#else + mavlink_serial_control_t packet; + packet.baudrate = baudrate; + packet.timeout = timeout; + packet.device = device; + packet.flags = flags; + packet.count = count; + mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SERIAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_serial_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, baudrate); + _mav_put_uint16_t(buf, 4, timeout); + _mav_put_uint8_t(buf, 6, device); + _mav_put_uint8_t(buf, 7, flags); + _mav_put_uint8_t(buf, 8, count); + _mav_put_uint8_t_array(buf, 9, data, 70); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif +#else + mavlink_serial_control_t *packet = (mavlink_serial_control_t *)msgbuf; + packet->baudrate = baudrate; + packet->timeout = timeout; + packet->device = device; + packet->flags = flags; + packet->count = count; + mav_array_memcpy(packet->data, data, sizeof(uint8_t)*70); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SERIAL_CONTROL UNPACKING + + +/** + * @brief Get field device from serial_control message + * + * @return See SERIAL_CONTROL_DEV enum + */ +static inline uint8_t mavlink_msg_serial_control_get_device(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field flags from serial_control message + * + * @return See SERIAL_CONTROL_FLAG enum + */ +static inline uint8_t mavlink_msg_serial_control_get_flags(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field timeout from serial_control message + * + * @return Timeout for reply data in milliseconds + */ +static inline uint16_t mavlink_msg_serial_control_get_timeout(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field baudrate from serial_control message + * + * @return Baudrate of transfer. Zero means no change. + */ +static inline uint32_t mavlink_msg_serial_control_get_baudrate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field count from serial_control message + * + * @return how many bytes in this transfer + */ +static inline uint8_t mavlink_msg_serial_control_get_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field data from serial_control message + * + * @return serial data + */ +static inline uint16_t mavlink_msg_serial_control_get_data(const mavlink_message_t* msg, uint8_t *data) +{ + return _MAV_RETURN_uint8_t_array(msg, data, 70, 9); +} + +/** + * @brief Decode a serial_control message into a struct + * + * @param msg The message to decode + * @param serial_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_serial_control_decode(const mavlink_message_t* msg, mavlink_serial_control_t* serial_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + serial_control->baudrate = mavlink_msg_serial_control_get_baudrate(msg); + serial_control->timeout = mavlink_msg_serial_control_get_timeout(msg); + serial_control->device = mavlink_msg_serial_control_get_device(msg); + serial_control->flags = mavlink_msg_serial_control_get_flags(msg); + serial_control->count = mavlink_msg_serial_control_get_count(msg); + mavlink_msg_serial_control_get_data(msg, serial_control->data); +#else + memcpy(serial_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h new file mode 100644 index 0000000..d6952d0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h @@ -0,0 +1,425 @@ +// MESSAGE SERVO_OUTPUT_RAW PACKING + +#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 36 + +typedef struct __mavlink_servo_output_raw_t +{ + uint32_t time_usec; /*< Timestamp (microseconds since system boot)*/ + uint16_t servo1_raw; /*< Servo output 1 value, in microseconds*/ + uint16_t servo2_raw; /*< Servo output 2 value, in microseconds*/ + uint16_t servo3_raw; /*< Servo output 3 value, in microseconds*/ + uint16_t servo4_raw; /*< Servo output 4 value, in microseconds*/ + uint16_t servo5_raw; /*< Servo output 5 value, in microseconds*/ + uint16_t servo6_raw; /*< Servo output 6 value, in microseconds*/ + uint16_t servo7_raw; /*< Servo output 7 value, in microseconds*/ + uint16_t servo8_raw; /*< Servo output 8 value, in microseconds*/ + uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.*/ +} mavlink_servo_output_raw_t; + +#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 21 +#define MAVLINK_MSG_ID_36_LEN 21 + +#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC 222 +#define MAVLINK_MSG_ID_36_CRC 222 + + + +#define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \ + "SERVO_OUTPUT_RAW", \ + 10, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \ + { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \ + { "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \ + { "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \ + { "servo4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \ + { "servo5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \ + { "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \ + { "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \ + { "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \ + } \ +} + + +/** + * @brief Pack a servo_output_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param servo1_raw Servo output 1 value, in microseconds + * @param servo2_raw Servo output 2 value, in microseconds + * @param servo3_raw Servo output 3 value, in microseconds + * @param servo4_raw Servo output 4 value, in microseconds + * @param servo5_raw Servo output 5 value, in microseconds + * @param servo6_raw Servo output 6 value, in microseconds + * @param servo7_raw Servo output 7 value, in microseconds + * @param servo8_raw Servo output 8 value, in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN]; + _mav_put_uint32_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 4, servo1_raw); + _mav_put_uint16_t(buf, 6, servo2_raw); + _mav_put_uint16_t(buf, 8, servo3_raw); + _mav_put_uint16_t(buf, 10, servo4_raw); + _mav_put_uint16_t(buf, 12, servo5_raw); + _mav_put_uint16_t(buf, 14, servo6_raw); + _mav_put_uint16_t(buf, 16, servo7_raw); + _mav_put_uint16_t(buf, 18, servo8_raw); + _mav_put_uint8_t(buf, 20, port); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#else + mavlink_servo_output_raw_t packet; + packet.time_usec = time_usec; + packet.servo1_raw = servo1_raw; + packet.servo2_raw = servo2_raw; + packet.servo3_raw = servo3_raw; + packet.servo4_raw = servo4_raw; + packet.servo5_raw = servo5_raw; + packet.servo6_raw = servo6_raw; + packet.servo7_raw = servo7_raw; + packet.servo8_raw = servo8_raw; + packet.port = port; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif +} + +/** + * @brief Pack a servo_output_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param servo1_raw Servo output 1 value, in microseconds + * @param servo2_raw Servo output 2 value, in microseconds + * @param servo3_raw Servo output 3 value, in microseconds + * @param servo4_raw Servo output 4 value, in microseconds + * @param servo5_raw Servo output 5 value, in microseconds + * @param servo6_raw Servo output 6 value, in microseconds + * @param servo7_raw Servo output 7 value, in microseconds + * @param servo8_raw Servo output 8 value, in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_usec,uint8_t port,uint16_t servo1_raw,uint16_t servo2_raw,uint16_t servo3_raw,uint16_t servo4_raw,uint16_t servo5_raw,uint16_t servo6_raw,uint16_t servo7_raw,uint16_t servo8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN]; + _mav_put_uint32_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 4, servo1_raw); + _mav_put_uint16_t(buf, 6, servo2_raw); + _mav_put_uint16_t(buf, 8, servo3_raw); + _mav_put_uint16_t(buf, 10, servo4_raw); + _mav_put_uint16_t(buf, 12, servo5_raw); + _mav_put_uint16_t(buf, 14, servo6_raw); + _mav_put_uint16_t(buf, 16, servo7_raw); + _mav_put_uint16_t(buf, 18, servo8_raw); + _mav_put_uint8_t(buf, 20, port); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#else + mavlink_servo_output_raw_t packet; + packet.time_usec = time_usec; + packet.servo1_raw = servo1_raw; + packet.servo2_raw = servo2_raw; + packet.servo3_raw = servo3_raw; + packet.servo4_raw = servo4_raw; + packet.servo5_raw = servo5_raw; + packet.servo6_raw = servo6_raw; + packet.servo7_raw = servo7_raw; + packet.servo8_raw = servo8_raw; + packet.port = port; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif +} + +/** + * @brief Encode a servo_output_raw struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param servo_output_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw) +{ + return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw); +} + +/** + * @brief Encode a servo_output_raw struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param servo_output_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_servo_output_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw) +{ + return mavlink_msg_servo_output_raw_pack_chan(system_id, component_id, chan, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw); +} + +/** + * @brief Send a servo_output_raw message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param servo1_raw Servo output 1 value, in microseconds + * @param servo2_raw Servo output 2 value, in microseconds + * @param servo3_raw Servo output 3 value, in microseconds + * @param servo4_raw Servo output 4 value, in microseconds + * @param servo5_raw Servo output 5 value, in microseconds + * @param servo6_raw Servo output 6 value, in microseconds + * @param servo7_raw Servo output 7 value, in microseconds + * @param servo8_raw Servo output 8 value, in microseconds + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN]; + _mav_put_uint32_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 4, servo1_raw); + _mav_put_uint16_t(buf, 6, servo2_raw); + _mav_put_uint16_t(buf, 8, servo3_raw); + _mav_put_uint16_t(buf, 10, servo4_raw); + _mav_put_uint16_t(buf, 12, servo5_raw); + _mav_put_uint16_t(buf, 14, servo6_raw); + _mav_put_uint16_t(buf, 16, servo7_raw); + _mav_put_uint16_t(buf, 18, servo8_raw); + _mav_put_uint8_t(buf, 20, port); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif +#else + mavlink_servo_output_raw_t packet; + packet.time_usec = time_usec; + packet.servo1_raw = servo1_raw; + packet.servo2_raw = servo2_raw; + packet.servo3_raw = servo3_raw; + packet.servo4_raw = servo4_raw; + packet.servo5_raw = servo5_raw; + packet.servo6_raw = servo6_raw; + packet.servo7_raw = servo7_raw; + packet.servo8_raw = servo8_raw; + packet.port = port; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_servo_output_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 4, servo1_raw); + _mav_put_uint16_t(buf, 6, servo2_raw); + _mav_put_uint16_t(buf, 8, servo3_raw); + _mav_put_uint16_t(buf, 10, servo4_raw); + _mav_put_uint16_t(buf, 12, servo5_raw); + _mav_put_uint16_t(buf, 14, servo6_raw); + _mav_put_uint16_t(buf, 16, servo7_raw); + _mav_put_uint16_t(buf, 18, servo8_raw); + _mav_put_uint8_t(buf, 20, port); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif +#else + mavlink_servo_output_raw_t *packet = (mavlink_servo_output_raw_t *)msgbuf; + packet->time_usec = time_usec; + packet->servo1_raw = servo1_raw; + packet->servo2_raw = servo2_raw; + packet->servo3_raw = servo3_raw; + packet->servo4_raw = servo4_raw; + packet->servo5_raw = servo5_raw; + packet->servo6_raw = servo6_raw; + packet->servo7_raw = servo7_raw; + packet->servo8_raw = servo8_raw; + packet->port = port; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SERVO_OUTPUT_RAW UNPACKING + + +/** + * @brief Get field time_usec from servo_output_raw message + * + * @return Timestamp (microseconds since system boot) + */ +static inline uint32_t mavlink_msg_servo_output_raw_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field port from servo_output_raw message + * + * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + */ +static inline uint8_t mavlink_msg_servo_output_raw_get_port(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field servo1_raw from servo_output_raw message + * + * @return Servo output 1 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field servo2_raw from servo_output_raw message + * + * @return Servo output 2 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field servo3_raw from servo_output_raw message + * + * @return Servo output 3 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field servo4_raw from servo_output_raw message + * + * @return Servo output 4 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field servo5_raw from servo_output_raw message + * + * @return Servo output 5 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field servo6_raw from servo_output_raw message + * + * @return Servo output 6 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field servo7_raw from servo_output_raw message + * + * @return Servo output 7 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field servo8_raw from servo_output_raw message + * + * @return Servo output 8 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Decode a servo_output_raw message into a struct + * + * @param msg The message to decode + * @param servo_output_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* msg, mavlink_servo_output_raw_t* servo_output_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + servo_output_raw->time_usec = mavlink_msg_servo_output_raw_get_time_usec(msg); + servo_output_raw->servo1_raw = mavlink_msg_servo_output_raw_get_servo1_raw(msg); + servo_output_raw->servo2_raw = mavlink_msg_servo_output_raw_get_servo2_raw(msg); + servo_output_raw->servo3_raw = mavlink_msg_servo_output_raw_get_servo3_raw(msg); + servo_output_raw->servo4_raw = mavlink_msg_servo_output_raw_get_servo4_raw(msg); + servo_output_raw->servo5_raw = mavlink_msg_servo_output_raw_get_servo5_raw(msg); + servo_output_raw->servo6_raw = mavlink_msg_servo_output_raw_get_servo6_raw(msg); + servo_output_raw->servo7_raw = mavlink_msg_servo_output_raw_get_servo7_raw(msg); + servo_output_raw->servo8_raw = mavlink_msg_servo_output_raw_get_servo8_raw(msg); + servo_output_raw->port = mavlink_msg_servo_output_raw_get_port(msg); +#else + memcpy(servo_output_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_actuator_control_target.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_actuator_control_target.h new file mode 100644 index 0000000..5632dba --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_actuator_control_target.h @@ -0,0 +1,297 @@ +// MESSAGE SET_ACTUATOR_CONTROL_TARGET PACKING + +#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET 139 + +typedef struct __mavlink_set_actuator_control_target_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/ + uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ +} mavlink_set_actuator_control_target_t; + +#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN 43 +#define MAVLINK_MSG_ID_139_LEN 43 + +#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC 168 +#define MAVLINK_MSG_ID_139_CRC 168 + +#define MAVLINK_MSG_SET_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS_LEN 8 + +#define MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET { \ + "SET_ACTUATOR_CONTROL_TARGET", \ + 5, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_set_actuator_control_target_t, time_usec) }, \ + { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_set_actuator_control_target_t, controls) }, \ + { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_set_actuator_control_target_t, group_mlx) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_set_actuator_control_target_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_set_actuator_control_target_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a set_actuator_control_target message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param target_system System ID + * @param target_component Component ID + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_uint8_t(buf, 41, target_system); + _mav_put_uint8_t(buf, 42, target_component); + _mav_put_float_array(buf, 8, controls, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#else + mavlink_set_actuator_control_target_t packet; + packet.time_usec = time_usec; + packet.group_mlx = group_mlx; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.controls, controls, sizeof(float)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif +} + +/** + * @brief Pack a set_actuator_control_target message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param target_system System ID + * @param target_component Component ID + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t group_mlx,uint8_t target_system,uint8_t target_component,const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_uint8_t(buf, 41, target_system); + _mav_put_uint8_t(buf, 42, target_component); + _mav_put_float_array(buf, 8, controls, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#else + mavlink_set_actuator_control_target_t packet; + packet.time_usec = time_usec; + packet.group_mlx = group_mlx; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.controls, controls, sizeof(float)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif +} + +/** + * @brief Encode a set_actuator_control_target struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_actuator_control_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_actuator_control_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_actuator_control_target_t* set_actuator_control_target) +{ + return mavlink_msg_set_actuator_control_target_pack(system_id, component_id, msg, set_actuator_control_target->time_usec, set_actuator_control_target->group_mlx, set_actuator_control_target->target_system, set_actuator_control_target->target_component, set_actuator_control_target->controls); +} + +/** + * @brief Encode a set_actuator_control_target struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param set_actuator_control_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_actuator_control_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_actuator_control_target_t* set_actuator_control_target) +{ + return mavlink_msg_set_actuator_control_target_pack_chan(system_id, component_id, chan, msg, set_actuator_control_target->time_usec, set_actuator_control_target->group_mlx, set_actuator_control_target->target_system, set_actuator_control_target->target_component, set_actuator_control_target->controls); +} + +/** + * @brief Send a set_actuator_control_target message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + * @param target_system System ID + * @param target_component Component ID + * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_actuator_control_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_uint8_t(buf, 41, target_system); + _mav_put_uint8_t(buf, 42, target_component); + _mav_put_float_array(buf, 8, controls, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#else + mavlink_set_actuator_control_target_t packet; + packet.time_usec = time_usec; + packet.group_mlx = group_mlx; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.controls, controls, sizeof(float)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_set_actuator_control_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint8_t(buf, 40, group_mlx); + _mav_put_uint8_t(buf, 41, target_system); + _mav_put_uint8_t(buf, 42, target_component); + _mav_put_float_array(buf, 8, controls, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#else + mavlink_set_actuator_control_target_t *packet = (mavlink_set_actuator_control_target_t *)msgbuf; + packet->time_usec = time_usec; + packet->group_mlx = group_mlx; + packet->target_system = target_system; + packet->target_component = target_component; + mav_array_memcpy(packet->controls, controls, sizeof(float)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SET_ACTUATOR_CONTROL_TARGET UNPACKING + + +/** + * @brief Get field time_usec from set_actuator_control_target message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_set_actuator_control_target_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field group_mlx from set_actuator_control_target message + * + * @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + */ +static inline uint8_t mavlink_msg_set_actuator_control_target_get_group_mlx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 40); +} + +/** + * @brief Get field target_system from set_actuator_control_target message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 41); +} + +/** + * @brief Get field target_component from set_actuator_control_target message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 42); +} + +/** + * @brief Get field controls from set_actuator_control_target message + * + * @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + */ +static inline uint16_t mavlink_msg_set_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls) +{ + return _MAV_RETURN_float_array(msg, controls, 8, 8); +} + +/** + * @brief Decode a set_actuator_control_target message into a struct + * + * @param msg The message to decode + * @param set_actuator_control_target C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_actuator_control_target_decode(const mavlink_message_t* msg, mavlink_set_actuator_control_target_t* set_actuator_control_target) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_actuator_control_target->time_usec = mavlink_msg_set_actuator_control_target_get_time_usec(msg); + mavlink_msg_set_actuator_control_target_get_controls(msg, set_actuator_control_target->controls); + set_actuator_control_target->group_mlx = mavlink_msg_set_actuator_control_target_get_group_mlx(msg); + set_actuator_control_target->target_system = mavlink_msg_set_actuator_control_target_get_target_system(msg); + set_actuator_control_target->target_component = mavlink_msg_set_actuator_control_target_get_target_component(msg); +#else + memcpy(set_actuator_control_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_attitude_target.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_attitude_target.h new file mode 100644 index 0000000..cca0d72 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_attitude_target.h @@ -0,0 +1,393 @@ +// MESSAGE SET_ATTITUDE_TARGET PACKING + +#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET 82 + +typedef struct __mavlink_set_attitude_target_t +{ + uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ + float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ + float body_roll_rate; /*< Body roll rate in radians per second*/ + float body_pitch_rate; /*< Body roll rate in radians per second*/ + float body_yaw_rate; /*< Body roll rate in radians per second*/ + float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t type_mask; /*< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude*/ +} mavlink_set_attitude_target_t; + +#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN 39 +#define MAVLINK_MSG_ID_82_LEN 39 + +#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC 49 +#define MAVLINK_MSG_ID_82_CRC 49 + +#define MAVLINK_MSG_SET_ATTITUDE_TARGET_FIELD_Q_LEN 4 + +#define MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET { \ + "SET_ATTITUDE_TARGET", \ + 9, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_attitude_target_t, time_boot_ms) }, \ + { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_set_attitude_target_t, q) }, \ + { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_attitude_target_t, body_roll_rate) }, \ + { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_attitude_target_t, body_pitch_rate) }, \ + { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_attitude_target_t, body_yaw_rate) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_attitude_target_t, thrust) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_set_attitude_target_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_set_attitude_target_t, target_component) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_set_attitude_target_t, type_mask) }, \ + } \ +} + + +/** + * @brief Pack a set_attitude_target message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate Body roll rate in radians per second + * @param body_pitch_rate Body roll rate in radians per second + * @param body_yaw_rate Body roll rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, target_system); + _mav_put_uint8_t(buf, 37, target_component); + _mav_put_uint8_t(buf, 38, type_mask); + _mav_put_float_array(buf, 4, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#else + mavlink_set_attitude_target_t packet; + packet.time_boot_ms = time_boot_ms; + packet.body_roll_rate = body_roll_rate; + packet.body_pitch_rate = body_pitch_rate; + packet.body_yaw_rate = body_yaw_rate; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type_mask = type_mask; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ATTITUDE_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif +} + +/** + * @brief Pack a set_attitude_target message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate Body roll rate in radians per second + * @param body_pitch_rate Body roll rate in radians per second + * @param body_yaw_rate Body roll rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t type_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, target_system); + _mav_put_uint8_t(buf, 37, target_component); + _mav_put_uint8_t(buf, 38, type_mask); + _mav_put_float_array(buf, 4, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#else + mavlink_set_attitude_target_t packet; + packet.time_boot_ms = time_boot_ms; + packet.body_roll_rate = body_roll_rate; + packet.body_pitch_rate = body_pitch_rate; + packet.body_yaw_rate = body_yaw_rate; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type_mask = type_mask; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ATTITUDE_TARGET; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif +} + +/** + * @brief Encode a set_attitude_target struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_attitude_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_attitude_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_attitude_target_t* set_attitude_target) +{ + return mavlink_msg_set_attitude_target_pack(system_id, component_id, msg, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust); +} + +/** + * @brief Encode a set_attitude_target struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param set_attitude_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_attitude_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_attitude_target_t* set_attitude_target) +{ + return mavlink_msg_set_attitude_target_pack_chan(system_id, component_id, chan, msg, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust); +} + +/** + * @brief Send a set_attitude_target message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + * @param body_roll_rate Body roll rate in radians per second + * @param body_pitch_rate Body roll rate in radians per second + * @param body_yaw_rate Body roll rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_attitude_target_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, target_system); + _mav_put_uint8_t(buf, 37, target_component); + _mav_put_uint8_t(buf, 38, type_mask); + _mav_put_float_array(buf, 4, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif +#else + mavlink_set_attitude_target_t packet; + packet.time_boot_ms = time_boot_ms; + packet.body_roll_rate = body_roll_rate; + packet.body_pitch_rate = body_pitch_rate; + packet.body_yaw_rate = body_yaw_rate; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type_mask = type_mask; + mav_array_memcpy(packet.q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_set_attitude_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, target_system); + _mav_put_uint8_t(buf, 37, target_component); + _mav_put_uint8_t(buf, 38, type_mask); + _mav_put_float_array(buf, 4, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif +#else + mavlink_set_attitude_target_t *packet = (mavlink_set_attitude_target_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->body_roll_rate = body_roll_rate; + packet->body_pitch_rate = body_pitch_rate; + packet->body_yaw_rate = body_yaw_rate; + packet->thrust = thrust; + packet->target_system = target_system; + packet->target_component = target_component; + packet->type_mask = type_mask; + mav_array_memcpy(packet->q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SET_ATTITUDE_TARGET UNPACKING + + +/** + * @brief Get field time_boot_ms from set_attitude_target message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_set_attitude_target_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field target_system from set_attitude_target message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_attitude_target_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Get field target_component from set_attitude_target message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_attitude_target_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 37); +} + +/** + * @brief Get field type_mask from set_attitude_target message + * + * @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + */ +static inline uint8_t mavlink_msg_set_attitude_target_get_type_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 38); +} + +/** + * @brief Get field q from set_attitude_target message + * + * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + */ +static inline uint16_t mavlink_msg_set_attitude_target_get_q(const mavlink_message_t* msg, float *q) +{ + return _MAV_RETURN_float_array(msg, q, 4, 4); +} + +/** + * @brief Get field body_roll_rate from set_attitude_target message + * + * @return Body roll rate in radians per second + */ +static inline float mavlink_msg_set_attitude_target_get_body_roll_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field body_pitch_rate from set_attitude_target message + * + * @return Body roll rate in radians per second + */ +static inline float mavlink_msg_set_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field body_yaw_rate from set_attitude_target message + * + * @return Body roll rate in radians per second + */ +static inline float mavlink_msg_set_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field thrust from set_attitude_target message + * + * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + */ +static inline float mavlink_msg_set_attitude_target_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Decode a set_attitude_target message into a struct + * + * @param msg The message to decode + * @param set_attitude_target C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_attitude_target_decode(const mavlink_message_t* msg, mavlink_set_attitude_target_t* set_attitude_target) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_attitude_target->time_boot_ms = mavlink_msg_set_attitude_target_get_time_boot_ms(msg); + mavlink_msg_set_attitude_target_get_q(msg, set_attitude_target->q); + set_attitude_target->body_roll_rate = mavlink_msg_set_attitude_target_get_body_roll_rate(msg); + set_attitude_target->body_pitch_rate = mavlink_msg_set_attitude_target_get_body_pitch_rate(msg); + set_attitude_target->body_yaw_rate = mavlink_msg_set_attitude_target_get_body_yaw_rate(msg); + set_attitude_target->thrust = mavlink_msg_set_attitude_target_get_thrust(msg); + set_attitude_target->target_system = mavlink_msg_set_attitude_target_get_target_system(msg); + set_attitude_target->target_component = mavlink_msg_set_attitude_target_get_target_component(msg); + set_attitude_target->type_mask = mavlink_msg_set_attitude_target_get_type_mask(msg); +#else + memcpy(set_attitude_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h new file mode 100644 index 0000000..6644a61 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h @@ -0,0 +1,281 @@ +// MESSAGE SET_GPS_GLOBAL_ORIGIN PACKING + +#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN 48 + +typedef struct __mavlink_set_gps_global_origin_t +{ + int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/ + int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ + uint8_t target_system; /*< System ID*/ +} mavlink_set_gps_global_origin_t; + +#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN 13 +#define MAVLINK_MSG_ID_48_LEN 13 + +#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC 41 +#define MAVLINK_MSG_ID_48_CRC 41 + + + +#define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \ + "SET_GPS_GLOBAL_ORIGIN", \ + 4, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \ + } \ +} + + +/** + * @brief Pack a set_gps_global_origin message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#else + mavlink_set_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.target_system = target_system; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif +} + +/** + * @brief Pack a set_gps_global_origin message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,int32_t latitude,int32_t longitude,int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#else + mavlink_set_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.target_system = target_system; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif +} + +/** + * @brief Encode a set_gps_global_origin struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_gps_global_origin C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin) +{ + return mavlink_msg_set_gps_global_origin_pack(system_id, component_id, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude); +} + +/** + * @brief Encode a set_gps_global_origin struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param set_gps_global_origin C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_gps_global_origin_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin) +{ + return mavlink_msg_set_gps_global_origin_pack_chan(system_id, component_id, chan, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude); +} + +/** + * @brief Send a set_gps_global_origin message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_gps_global_origin_send(mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif +#else + mavlink_set_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.target_system = target_system; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_set_gps_global_origin_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif +#else + mavlink_set_gps_global_origin_t *packet = (mavlink_set_gps_global_origin_t *)msgbuf; + packet->latitude = latitude; + packet->longitude = longitude; + packet->altitude = altitude; + packet->target_system = target_system; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SET_GPS_GLOBAL_ORIGIN UNPACKING + + +/** + * @brief Get field target_system from set_gps_global_origin message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_gps_global_origin_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field latitude from set_gps_global_origin message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_set_gps_global_origin_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from set_gps_global_origin message + * + * @return Longitude (WGS84, in degrees * 1E7 + */ +static inline int32_t mavlink_msg_set_gps_global_origin_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from set_gps_global_origin message + * + * @return Altitude (AMSL), in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_set_gps_global_origin_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Decode a set_gps_global_origin message into a struct + * + * @param msg The message to decode + * @param set_gps_global_origin C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_set_gps_global_origin_t* set_gps_global_origin) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_gps_global_origin->latitude = mavlink_msg_set_gps_global_origin_get_latitude(msg); + set_gps_global_origin->longitude = mavlink_msg_set_gps_global_origin_get_longitude(msg); + set_gps_global_origin->altitude = mavlink_msg_set_gps_global_origin_get_altitude(msg); + set_gps_global_origin->target_system = mavlink_msg_set_gps_global_origin_get_target_system(msg); +#else + memcpy(set_gps_global_origin, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_home_position.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_home_position.h new file mode 100644 index 0000000..91ed1c7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_home_position.h @@ -0,0 +1,441 @@ +// MESSAGE SET_HOME_POSITION PACKING + +#define MAVLINK_MSG_ID_SET_HOME_POSITION 243 + +typedef struct __mavlink_set_home_position_t +{ + int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/ + int32_t longitude; /*< Longitude (WGS84, in degrees * 1E7*/ + int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/ + float x; /*< Local X position of this position in the local coordinate frame*/ + float y; /*< Local Y position of this position in the local coordinate frame*/ + float z; /*< Local Z position of this position in the local coordinate frame*/ + float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/ + float approach_x; /*< Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ + float approach_y; /*< Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ + float approach_z; /*< Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ + uint8_t target_system; /*< System ID.*/ +} mavlink_set_home_position_t; + +#define MAVLINK_MSG_ID_SET_HOME_POSITION_LEN 53 +#define MAVLINK_MSG_ID_243_LEN 53 + +#define MAVLINK_MSG_ID_SET_HOME_POSITION_CRC 85 +#define MAVLINK_MSG_ID_243_CRC 85 + +#define MAVLINK_MSG_SET_HOME_POSITION_FIELD_Q_LEN 4 + +#define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION { \ + "SET_HOME_POSITION", \ + 11, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_home_position_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_home_position_t, altitude) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_home_position_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_home_position_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_home_position_t, z) }, \ + { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_set_home_position_t, q) }, \ + { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_home_position_t, approach_x) }, \ + { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_home_position_t, approach_y) }, \ + { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_set_home_position_t, approach_z) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \ + } \ +} + + +/** + * @brief Pack a set_home_position message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID. + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param x Local X position of this position in the local coordinate frame + * @param y Local Y position of this position in the local coordinate frame + * @param z Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_uint8_t(buf, 52, target_system); + _mav_put_float_array(buf, 24, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#else + mavlink_set_home_position_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.x = x; + packet.y = y; + packet.z = z; + packet.approach_x = approach_x; + packet.approach_y = approach_y; + packet.approach_z = approach_z; + packet.target_system = target_system; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_HOME_POSITION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif +} + +/** + * @brief Pack a set_home_position message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID. + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param x Local X position of this position in the local coordinate frame + * @param y Local Y position of this position in the local coordinate frame + * @param z Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,int32_t latitude,int32_t longitude,int32_t altitude,float x,float y,float z,const float *q,float approach_x,float approach_y,float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_uint8_t(buf, 52, target_system); + _mav_put_float_array(buf, 24, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#else + mavlink_set_home_position_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.x = x; + packet.y = y; + packet.z = z; + packet.approach_x = approach_x; + packet.approach_y = approach_y; + packet.approach_z = approach_z; + packet.target_system = target_system; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_HOME_POSITION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif +} + +/** + * @brief Encode a set_home_position struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_home_position C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_home_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_home_position_t* set_home_position) +{ + return mavlink_msg_set_home_position_pack(system_id, component_id, msg, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z); +} + +/** + * @brief Encode a set_home_position struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param set_home_position C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_home_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_home_position_t* set_home_position) +{ + return mavlink_msg_set_home_position_pack_chan(system_id, component_id, chan, msg, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z); +} + +/** + * @brief Send a set_home_position message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID. + * @param latitude Latitude (WGS84), in degrees * 1E7 + * @param longitude Longitude (WGS84, in degrees * 1E7 + * @param altitude Altitude (AMSL), in meters * 1000 (positive for up) + * @param x Local X position of this position in the local coordinate frame + * @param y Local Y position of this position in the local coordinate frame + * @param z Local Z position of this position in the local coordinate frame + * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + * @param approach_x Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_y Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + * @param approach_z Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_home_position_send(mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_uint8_t(buf, 52, target_system); + _mav_put_float_array(buf, 24, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif +#else + mavlink_set_home_position_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.x = x; + packet.y = y; + packet.z = z; + packet.approach_x = approach_x; + packet.approach_y = approach_y; + packet.approach_z = approach_z; + packet.target_system = target_system; + mav_array_memcpy(packet.q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SET_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_set_home_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_float(buf, 12, x); + _mav_put_float(buf, 16, y); + _mav_put_float(buf, 20, z); + _mav_put_float(buf, 40, approach_x); + _mav_put_float(buf, 44, approach_y); + _mav_put_float(buf, 48, approach_z); + _mav_put_uint8_t(buf, 52, target_system); + _mav_put_float_array(buf, 24, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif +#else + mavlink_set_home_position_t *packet = (mavlink_set_home_position_t *)msgbuf; + packet->latitude = latitude; + packet->longitude = longitude; + packet->altitude = altitude; + packet->x = x; + packet->y = y; + packet->z = z; + packet->approach_x = approach_x; + packet->approach_y = approach_y; + packet->approach_z = approach_z; + packet->target_system = target_system; + mav_array_memcpy(packet->q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SET_HOME_POSITION UNPACKING + + +/** + * @brief Get field target_system from set_home_position message + * + * @return System ID. + */ +static inline uint8_t mavlink_msg_set_home_position_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 52); +} + +/** + * @brief Get field latitude from set_home_position message + * + * @return Latitude (WGS84), in degrees * 1E7 + */ +static inline int32_t mavlink_msg_set_home_position_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from set_home_position message + * + * @return Longitude (WGS84, in degrees * 1E7 + */ +static inline int32_t mavlink_msg_set_home_position_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from set_home_position message + * + * @return Altitude (AMSL), in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_set_home_position_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field x from set_home_position message + * + * @return Local X position of this position in the local coordinate frame + */ +static inline float mavlink_msg_set_home_position_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field y from set_home_position message + * + * @return Local Y position of this position in the local coordinate frame + */ +static inline float mavlink_msg_set_home_position_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field z from set_home_position message + * + * @return Local Z position of this position in the local coordinate frame + */ +static inline float mavlink_msg_set_home_position_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field q from set_home_position message + * + * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + */ +static inline uint16_t mavlink_msg_set_home_position_get_q(const mavlink_message_t* msg, float *q) +{ + return _MAV_RETURN_float_array(msg, q, 4, 24); +} + +/** + * @brief Get field approach_x from set_home_position message + * + * @return Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +static inline float mavlink_msg_set_home_position_get_approach_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field approach_y from set_home_position message + * + * @return Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +static inline float mavlink_msg_set_home_position_get_approach_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field approach_z from set_home_position message + * + * @return Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + */ +static inline float mavlink_msg_set_home_position_get_approach_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 48); +} + +/** + * @brief Decode a set_home_position message into a struct + * + * @param msg The message to decode + * @param set_home_position C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_home_position_decode(const mavlink_message_t* msg, mavlink_set_home_position_t* set_home_position) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_home_position->latitude = mavlink_msg_set_home_position_get_latitude(msg); + set_home_position->longitude = mavlink_msg_set_home_position_get_longitude(msg); + set_home_position->altitude = mavlink_msg_set_home_position_get_altitude(msg); + set_home_position->x = mavlink_msg_set_home_position_get_x(msg); + set_home_position->y = mavlink_msg_set_home_position_get_y(msg); + set_home_position->z = mavlink_msg_set_home_position_get_z(msg); + mavlink_msg_set_home_position_get_q(msg, set_home_position->q); + set_home_position->approach_x = mavlink_msg_set_home_position_get_approach_x(msg); + set_home_position->approach_y = mavlink_msg_set_home_position_get_approach_y(msg); + set_home_position->approach_z = mavlink_msg_set_home_position_get_approach_z(msg); + set_home_position->target_system = mavlink_msg_set_home_position_get_target_system(msg); +#else + memcpy(set_home_position, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_mode.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_mode.h new file mode 100644 index 0000000..849c1a4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_mode.h @@ -0,0 +1,257 @@ +// MESSAGE SET_MODE PACKING + +#define MAVLINK_MSG_ID_SET_MODE 11 + +typedef struct __mavlink_set_mode_t +{ + uint32_t custom_mode; /*< The new autopilot-specific mode. This field can be ignored by an autopilot.*/ + uint8_t target_system; /*< The system setting the mode*/ + uint8_t base_mode; /*< The new base mode*/ +} mavlink_set_mode_t; + +#define MAVLINK_MSG_ID_SET_MODE_LEN 6 +#define MAVLINK_MSG_ID_11_LEN 6 + +#define MAVLINK_MSG_ID_SET_MODE_CRC 89 +#define MAVLINK_MSG_ID_11_CRC 89 + + + +#define MAVLINK_MESSAGE_INFO_SET_MODE { \ + "SET_MODE", \ + 3, \ + { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ + { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \ + } \ +} + + +/** + * @brief Pack a set_mode message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system The system setting the mode + * @param base_mode The new base mode + * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_MODE_LEN]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, base_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MODE_LEN); +#else + mavlink_set_mode_t packet; + packet.custom_mode = custom_mode; + packet.target_system = target_system; + packet.base_mode = base_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_MODE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif +} + +/** + * @brief Pack a set_mode message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_system The system setting the mode + * @param base_mode The new base mode + * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t base_mode,uint32_t custom_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_MODE_LEN]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, base_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MODE_LEN); +#else + mavlink_set_mode_t packet; + packet.custom_mode = custom_mode; + packet.target_system = target_system; + packet.base_mode = base_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_MODE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif +} + +/** + * @brief Encode a set_mode struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_mode C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) +{ + return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); +} + +/** + * @brief Encode a set_mode struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param set_mode C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_mode_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) +{ + return mavlink_msg_set_mode_pack_chan(system_id, component_id, chan, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); +} + +/** + * @brief Send a set_mode message + * @param chan MAVLink channel to send the message + * + * @param target_system The system setting the mode + * @param base_mode The new base mode + * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_MODE_LEN]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, base_mode); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif +#else + mavlink_set_mode_t packet; + packet.custom_mode = custom_mode; + packet.target_system = target_system; + packet.base_mode = base_mode; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SET_MODE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_set_mode_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, base_mode); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif +#else + mavlink_set_mode_t *packet = (mavlink_set_mode_t *)msgbuf; + packet->custom_mode = custom_mode; + packet->target_system = target_system; + packet->base_mode = base_mode; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)packet, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)packet, MAVLINK_MSG_ID_SET_MODE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SET_MODE UNPACKING + + +/** + * @brief Get field target_system from set_mode message + * + * @return The system setting the mode + */ +static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field base_mode from set_mode message + * + * @return The new base mode + */ +static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field custom_mode from set_mode message + * + * @return The new autopilot-specific mode. This field can be ignored by an autopilot. + */ +static inline uint32_t mavlink_msg_set_mode_get_custom_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Decode a set_mode message into a struct + * + * @param msg The message to decode + * @param set_mode C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_mode->custom_mode = mavlink_msg_set_mode_get_custom_mode(msg); + set_mode->target_system = mavlink_msg_set_mode_get_target_system(msg); + set_mode->base_mode = mavlink_msg_set_mode_get_base_mode(msg); +#else + memcpy(set_mode, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_MODE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_position_target_global_int.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_position_target_global_int.h new file mode 100644 index 0000000..b63b636 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_position_target_global_int.h @@ -0,0 +1,569 @@ +// MESSAGE SET_POSITION_TARGET_GLOBAL_INT PACKING + +#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT 86 + +typedef struct __mavlink_set_position_target_global_int_t +{ + uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/ + int32_t lat_int; /*< X Position in WGS84 frame in 1e7 * meters*/ + int32_t lon_int; /*< Y Position in WGS84 frame in 1e7 * meters*/ + float alt; /*< Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT*/ + float vx; /*< X velocity in NED frame in meter / s*/ + float vy; /*< Y velocity in NED frame in meter / s*/ + float vz; /*< Z velocity in NED frame in meter / s*/ + float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float yaw; /*< yaw setpoint in rad*/ + float yaw_rate; /*< yaw rate setpoint in rad/s*/ + uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/ +} mavlink_set_position_target_global_int_t; + +#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN 53 +#define MAVLINK_MSG_ID_86_LEN 53 + +#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC 5 +#define MAVLINK_MSG_ID_86_CRC 5 + + + +#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \ + "SET_POSITION_TARGET_GLOBAL_INT", \ + 16, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \ + { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \ + { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_global_int_t, alt) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_global_int_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_global_int_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_global_int_t, vz) }, \ + { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_global_int_t, afx) }, \ + { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_global_int_t, afy) }, \ + { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \ + { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a set_position_target_global_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param lat_int X Position in WGS84 frame in 1e7 * meters + * @param lon_int Y Position in WGS84 frame in 1e7 * meters + * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#else + mavlink_set_position_target_global_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat_int = lat_int; + packet.lon_int = lon_int; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +} + +/** + * @brief Pack a set_position_target_global_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param lat_int X Position in WGS84 frame in 1e7 * meters + * @param lon_int Y Position in WGS84 frame in 1e7 * meters + * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#else + mavlink_set_position_target_global_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat_int = lat_int; + packet.lon_int = lon_int; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +} + +/** + * @brief Encode a set_position_target_global_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_position_target_global_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int) +{ + return mavlink_msg_set_position_target_global_int_pack(system_id, component_id, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate); +} + +/** + * @brief Encode a set_position_target_global_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param set_position_target_global_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int) +{ + return mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, chan, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate); +} + +/** + * @brief Send a set_position_target_global_int message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param lat_int X Position in WGS84 frame in 1e7 * meters + * @param lon_int Y Position in WGS84 frame in 1e7 * meters + * @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#else + mavlink_set_position_target_global_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat_int = lat_int; + packet.lon_int = lon_int; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_set_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#else + mavlink_set_position_target_global_int_t *packet = (mavlink_set_position_target_global_int_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->lat_int = lat_int; + packet->lon_int = lon_int; + packet->alt = alt; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->afx = afx; + packet->afy = afy; + packet->afz = afz; + packet->yaw = yaw; + packet->yaw_rate = yaw_rate; + packet->type_mask = type_mask; + packet->target_system = target_system; + packet->target_component = target_component; + packet->coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SET_POSITION_TARGET_GLOBAL_INT UNPACKING + + +/** + * @brief Get field time_boot_ms from set_position_target_global_int message + * + * @return Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + */ +static inline uint32_t mavlink_msg_set_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field target_system from set_position_target_global_int message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 50); +} + +/** + * @brief Get field target_component from set_position_target_global_int message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 51); +} + +/** + * @brief Get field coordinate_frame from set_position_target_global_int message + * + * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + */ +static inline uint8_t mavlink_msg_set_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 52); +} + +/** + * @brief Get field type_mask from set_position_target_global_int message + * + * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + */ +static inline uint16_t mavlink_msg_set_position_target_global_int_get_type_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 48); +} + +/** + * @brief Get field lat_int from set_position_target_global_int message + * + * @return X Position in WGS84 frame in 1e7 * meters + */ +static inline int32_t mavlink_msg_set_position_target_global_int_get_lat_int(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field lon_int from set_position_target_global_int message + * + * @return Y Position in WGS84 frame in 1e7 * meters + */ +static inline int32_t mavlink_msg_set_position_target_global_int_get_lon_int(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field alt from set_position_target_global_int message + * + * @return Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + */ +static inline float mavlink_msg_set_position_target_global_int_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vx from set_position_target_global_int message + * + * @return X velocity in NED frame in meter / s + */ +static inline float mavlink_msg_set_position_target_global_int_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vy from set_position_target_global_int message + * + * @return Y velocity in NED frame in meter / s + */ +static inline float mavlink_msg_set_position_target_global_int_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vz from set_position_target_global_int message + * + * @return Z velocity in NED frame in meter / s + */ +static inline float mavlink_msg_set_position_target_global_int_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field afx from set_position_target_global_int message + * + * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_set_position_target_global_int_get_afx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field afy from set_position_target_global_int message + * + * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_set_position_target_global_int_get_afy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field afz from set_position_target_global_int message + * + * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_set_position_target_global_int_get_afz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field yaw from set_position_target_global_int message + * + * @return yaw setpoint in rad + */ +static inline float mavlink_msg_set_position_target_global_int_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field yaw_rate from set_position_target_global_int message + * + * @return yaw rate setpoint in rad/s + */ +static inline float mavlink_msg_set_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Decode a set_position_target_global_int message into a struct + * + * @param msg The message to decode + * @param set_position_target_global_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_position_target_global_int_decode(const mavlink_message_t* msg, mavlink_set_position_target_global_int_t* set_position_target_global_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_position_target_global_int->time_boot_ms = mavlink_msg_set_position_target_global_int_get_time_boot_ms(msg); + set_position_target_global_int->lat_int = mavlink_msg_set_position_target_global_int_get_lat_int(msg); + set_position_target_global_int->lon_int = mavlink_msg_set_position_target_global_int_get_lon_int(msg); + set_position_target_global_int->alt = mavlink_msg_set_position_target_global_int_get_alt(msg); + set_position_target_global_int->vx = mavlink_msg_set_position_target_global_int_get_vx(msg); + set_position_target_global_int->vy = mavlink_msg_set_position_target_global_int_get_vy(msg); + set_position_target_global_int->vz = mavlink_msg_set_position_target_global_int_get_vz(msg); + set_position_target_global_int->afx = mavlink_msg_set_position_target_global_int_get_afx(msg); + set_position_target_global_int->afy = mavlink_msg_set_position_target_global_int_get_afy(msg); + set_position_target_global_int->afz = mavlink_msg_set_position_target_global_int_get_afz(msg); + set_position_target_global_int->yaw = mavlink_msg_set_position_target_global_int_get_yaw(msg); + set_position_target_global_int->yaw_rate = mavlink_msg_set_position_target_global_int_get_yaw_rate(msg); + set_position_target_global_int->type_mask = mavlink_msg_set_position_target_global_int_get_type_mask(msg); + set_position_target_global_int->target_system = mavlink_msg_set_position_target_global_int_get_target_system(msg); + set_position_target_global_int->target_component = mavlink_msg_set_position_target_global_int_get_target_component(msg); + set_position_target_global_int->coordinate_frame = mavlink_msg_set_position_target_global_int_get_coordinate_frame(msg); +#else + memcpy(set_position_target_global_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_position_target_local_ned.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_position_target_local_ned.h new file mode 100644 index 0000000..3a8b635 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_set_position_target_local_ned.h @@ -0,0 +1,569 @@ +// MESSAGE SET_POSITION_TARGET_LOCAL_NED PACKING + +#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED 84 + +typedef struct __mavlink_set_position_target_local_ned_t +{ + uint32_t time_boot_ms; /*< Timestamp in milliseconds since system boot*/ + float x; /*< X Position in NED frame in meters*/ + float y; /*< Y Position in NED frame in meters*/ + float z; /*< Z Position in NED frame in meters (note, altitude is negative in NED)*/ + float vx; /*< X velocity in NED frame in meter / s*/ + float vy; /*< Y velocity in NED frame in meter / s*/ + float vz; /*< Z velocity in NED frame in meter / s*/ + float afx; /*< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afy; /*< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float afz; /*< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ + float yaw; /*< yaw setpoint in rad*/ + float yaw_rate; /*< yaw rate setpoint in rad/s*/ + uint16_t type_mask; /*< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate*/ + uint8_t target_system; /*< System ID*/ + uint8_t target_component; /*< Component ID*/ + uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/ +} mavlink_set_position_target_local_ned_t; + +#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN 53 +#define MAVLINK_MSG_ID_84_LEN 53 + +#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC 143 +#define MAVLINK_MSG_ID_84_CRC 143 + + + +#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED { \ + "SET_POSITION_TARGET_LOCAL_NED", \ + 16, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_local_ned_t, time_boot_ms) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_target_local_ned_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_target_local_ned_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_local_ned_t, z) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_local_ned_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_local_ned_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_local_ned_t, vz) }, \ + { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_local_ned_t, afx) }, \ + { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_local_ned_t, afy) }, \ + { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_local_ned_t, afz) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, yaw) }, \ + { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, yaw_rate) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a set_position_target_local_ned message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param x X Position in NED frame in meters + * @param y Y Position in NED frame in meters + * @param z Z Position in NED frame in meters (note, altitude is negative in NED) + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#else + mavlink_set_position_target_local_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif +} + +/** + * @brief Pack a set_position_target_local_ned message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param x X Position in NED frame in meters + * @param y Y Position in NED frame in meters + * @param z Z Position in NED frame in meters (note, altitude is negative in NED) + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#else + mavlink_set_position_target_local_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif +} + +/** + * @brief Encode a set_position_target_local_ned struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_position_target_local_ned C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned) +{ + return mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate); +} + +/** + * @brief Encode a set_position_target_local_ned struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param set_position_target_local_ned C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned) +{ + return mavlink_msg_set_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate); +} + +/** + * @brief Send a set_position_target_local_ned message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + * @param x X Position in NED frame in meters + * @param y Y Position in NED frame in meters + * @param z Z Position in NED frame in meters (note, altitude is negative in NED) + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param yaw yaw setpoint in rad + * @param yaw_rate yaw rate setpoint in rad/s + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#else + mavlink_set_position_target_local_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.yaw = yaw; + packet.yaw_rate = yaw_rate; + packet.type_mask = type_mask; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_set_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_float(buf, 40, yaw); + _mav_put_float(buf, 44, yaw_rate); + _mav_put_uint16_t(buf, 48, type_mask); + _mav_put_uint8_t(buf, 50, target_system); + _mav_put_uint8_t(buf, 51, target_component); + _mav_put_uint8_t(buf, 52, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#else + mavlink_set_position_target_local_ned_t *packet = (mavlink_set_position_target_local_ned_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->x = x; + packet->y = y; + packet->z = z; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->afx = afx; + packet->afy = afy; + packet->afz = afz; + packet->yaw = yaw; + packet->yaw_rate = yaw_rate; + packet->type_mask = type_mask; + packet->target_system = target_system; + packet->target_component = target_component; + packet->coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SET_POSITION_TARGET_LOCAL_NED UNPACKING + + +/** + * @brief Get field time_boot_ms from set_position_target_local_ned message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_set_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field target_system from set_position_target_local_ned message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 50); +} + +/** + * @brief Get field target_component from set_position_target_local_ned message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 51); +} + +/** + * @brief Get field coordinate_frame from set_position_target_local_ned message + * + * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + */ +static inline uint8_t mavlink_msg_set_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 52); +} + +/** + * @brief Get field type_mask from set_position_target_local_ned message + * + * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + */ +static inline uint16_t mavlink_msg_set_position_target_local_ned_get_type_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 48); +} + +/** + * @brief Get field x from set_position_target_local_ned message + * + * @return X Position in NED frame in meters + */ +static inline float mavlink_msg_set_position_target_local_ned_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field y from set_position_target_local_ned message + * + * @return Y Position in NED frame in meters + */ +static inline float mavlink_msg_set_position_target_local_ned_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field z from set_position_target_local_ned message + * + * @return Z Position in NED frame in meters (note, altitude is negative in NED) + */ +static inline float mavlink_msg_set_position_target_local_ned_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vx from set_position_target_local_ned message + * + * @return X velocity in NED frame in meter / s + */ +static inline float mavlink_msg_set_position_target_local_ned_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vy from set_position_target_local_ned message + * + * @return Y velocity in NED frame in meter / s + */ +static inline float mavlink_msg_set_position_target_local_ned_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vz from set_position_target_local_ned message + * + * @return Z velocity in NED frame in meter / s + */ +static inline float mavlink_msg_set_position_target_local_ned_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field afx from set_position_target_local_ned message + * + * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_set_position_target_local_ned_get_afx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field afy from set_position_target_local_ned message + * + * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_set_position_target_local_ned_get_afy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field afz from set_position_target_local_ned message + * + * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + */ +static inline float mavlink_msg_set_position_target_local_ned_get_afz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field yaw from set_position_target_local_ned message + * + * @return yaw setpoint in rad + */ +static inline float mavlink_msg_set_position_target_local_ned_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field yaw_rate from set_position_target_local_ned message + * + * @return yaw rate setpoint in rad/s + */ +static inline float mavlink_msg_set_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Decode a set_position_target_local_ned message into a struct + * + * @param msg The message to decode + * @param set_position_target_local_ned C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_set_position_target_local_ned_t* set_position_target_local_ned) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_position_target_local_ned->time_boot_ms = mavlink_msg_set_position_target_local_ned_get_time_boot_ms(msg); + set_position_target_local_ned->x = mavlink_msg_set_position_target_local_ned_get_x(msg); + set_position_target_local_ned->y = mavlink_msg_set_position_target_local_ned_get_y(msg); + set_position_target_local_ned->z = mavlink_msg_set_position_target_local_ned_get_z(msg); + set_position_target_local_ned->vx = mavlink_msg_set_position_target_local_ned_get_vx(msg); + set_position_target_local_ned->vy = mavlink_msg_set_position_target_local_ned_get_vy(msg); + set_position_target_local_ned->vz = mavlink_msg_set_position_target_local_ned_get_vz(msg); + set_position_target_local_ned->afx = mavlink_msg_set_position_target_local_ned_get_afx(msg); + set_position_target_local_ned->afy = mavlink_msg_set_position_target_local_ned_get_afy(msg); + set_position_target_local_ned->afz = mavlink_msg_set_position_target_local_ned_get_afz(msg); + set_position_target_local_ned->yaw = mavlink_msg_set_position_target_local_ned_get_yaw(msg); + set_position_target_local_ned->yaw_rate = mavlink_msg_set_position_target_local_ned_get_yaw_rate(msg); + set_position_target_local_ned->type_mask = mavlink_msg_set_position_target_local_ned_get_type_mask(msg); + set_position_target_local_ned->target_system = mavlink_msg_set_position_target_local_ned_get_target_system(msg); + set_position_target_local_ned->target_component = mavlink_msg_set_position_target_local_ned_get_target_component(msg); + set_position_target_local_ned->coordinate_frame = mavlink_msg_set_position_target_local_ned_get_coordinate_frame(msg); +#else + memcpy(set_position_target_local_ned, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_sim_state.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_sim_state.h new file mode 100644 index 0000000..ad6934d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_sim_state.h @@ -0,0 +1,689 @@ +// MESSAGE SIM_STATE PACKING + +#define MAVLINK_MSG_ID_SIM_STATE 108 + +typedef struct __mavlink_sim_state_t +{ + float q1; /*< True attitude quaternion component 1, w (1 in null-rotation)*/ + float q2; /*< True attitude quaternion component 2, x (0 in null-rotation)*/ + float q3; /*< True attitude quaternion component 3, y (0 in null-rotation)*/ + float q4; /*< True attitude quaternion component 4, z (0 in null-rotation)*/ + float roll; /*< Attitude roll expressed as Euler angles, not recommended except for human-readable outputs*/ + float pitch; /*< Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs*/ + float yaw; /*< Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs*/ + float xacc; /*< X acceleration m/s/s*/ + float yacc; /*< Y acceleration m/s/s*/ + float zacc; /*< Z acceleration m/s/s*/ + float xgyro; /*< Angular speed around X axis rad/s*/ + float ygyro; /*< Angular speed around Y axis rad/s*/ + float zgyro; /*< Angular speed around Z axis rad/s*/ + float lat; /*< Latitude in degrees*/ + float lon; /*< Longitude in degrees*/ + float alt; /*< Altitude in meters*/ + float std_dev_horz; /*< Horizontal position standard deviation*/ + float std_dev_vert; /*< Vertical position standard deviation*/ + float vn; /*< True velocity in m/s in NORTH direction in earth-fixed NED frame*/ + float ve; /*< True velocity in m/s in EAST direction in earth-fixed NED frame*/ + float vd; /*< True velocity in m/s in DOWN direction in earth-fixed NED frame*/ +} mavlink_sim_state_t; + +#define MAVLINK_MSG_ID_SIM_STATE_LEN 84 +#define MAVLINK_MSG_ID_108_LEN 84 + +#define MAVLINK_MSG_ID_SIM_STATE_CRC 32 +#define MAVLINK_MSG_ID_108_CRC 32 + + + +#define MAVLINK_MESSAGE_INFO_SIM_STATE { \ + "SIM_STATE", \ + 21, \ + { { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sim_state_t, q1) }, \ + { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sim_state_t, q2) }, \ + { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sim_state_t, q3) }, \ + { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sim_state_t, q4) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sim_state_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sim_state_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sim_state_t, yaw) }, \ + { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sim_state_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sim_state_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sim_state_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sim_state_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sim_state_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sim_state_t, zgyro) }, \ + { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sim_state_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sim_state_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sim_state_t, alt) }, \ + { "std_dev_horz", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sim_state_t, std_dev_horz) }, \ + { "std_dev_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sim_state_t, std_dev_vert) }, \ + { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sim_state_t, vn) }, \ + { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sim_state_t, ve) }, \ + { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sim_state_t, vd) }, \ + } \ +} + + +/** + * @brief Pack a sim_state message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param q1 True attitude quaternion component 1, w (1 in null-rotation) + * @param q2 True attitude quaternion component 2, x (0 in null-rotation) + * @param q3 True attitude quaternion component 3, y (0 in null-rotation) + * @param q4 True attitude quaternion component 4, z (0 in null-rotation) + * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + * @param xacc X acceleration m/s/s + * @param yacc Y acceleration m/s/s + * @param zacc Z acceleration m/s/s + * @param xgyro Angular speed around X axis rad/s + * @param ygyro Angular speed around Y axis rad/s + * @param zgyro Angular speed around Z axis rad/s + * @param lat Latitude in degrees + * @param lon Longitude in degrees + * @param alt Altitude in meters + * @param std_dev_horz Horizontal position standard deviation + * @param std_dev_vert Vertical position standard deviation + * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame + * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame + * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sim_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; + _mav_put_float(buf, 0, q1); + _mav_put_float(buf, 4, q2); + _mav_put_float(buf, 8, q3); + _mav_put_float(buf, 12, q4); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + _mav_put_float(buf, 28, xacc); + _mav_put_float(buf, 32, yacc); + _mav_put_float(buf, 36, zacc); + _mav_put_float(buf, 40, xgyro); + _mav_put_float(buf, 44, ygyro); + _mav_put_float(buf, 48, zgyro); + _mav_put_float(buf, 52, lat); + _mav_put_float(buf, 56, lon); + _mav_put_float(buf, 60, alt); + _mav_put_float(buf, 64, std_dev_horz); + _mav_put_float(buf, 68, std_dev_vert); + _mav_put_float(buf, 72, vn); + _mav_put_float(buf, 76, ve); + _mav_put_float(buf, 80, vd); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN); +#else + mavlink_sim_state_t packet; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.std_dev_horz = std_dev_horz; + packet.std_dev_vert = std_dev_vert; + packet.vn = vn; + packet.ve = ve; + packet.vd = vd; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SIM_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +} + +/** + * @brief Pack a sim_state message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param q1 True attitude quaternion component 1, w (1 in null-rotation) + * @param q2 True attitude quaternion component 2, x (0 in null-rotation) + * @param q3 True attitude quaternion component 3, y (0 in null-rotation) + * @param q4 True attitude quaternion component 4, z (0 in null-rotation) + * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + * @param xacc X acceleration m/s/s + * @param yacc Y acceleration m/s/s + * @param zacc Z acceleration m/s/s + * @param xgyro Angular speed around X axis rad/s + * @param ygyro Angular speed around Y axis rad/s + * @param zgyro Angular speed around Z axis rad/s + * @param lat Latitude in degrees + * @param lon Longitude in degrees + * @param alt Altitude in meters + * @param std_dev_horz Horizontal position standard deviation + * @param std_dev_vert Vertical position standard deviation + * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame + * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame + * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sim_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float q1,float q2,float q3,float q4,float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lon,float alt,float std_dev_horz,float std_dev_vert,float vn,float ve,float vd) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; + _mav_put_float(buf, 0, q1); + _mav_put_float(buf, 4, q2); + _mav_put_float(buf, 8, q3); + _mav_put_float(buf, 12, q4); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + _mav_put_float(buf, 28, xacc); + _mav_put_float(buf, 32, yacc); + _mav_put_float(buf, 36, zacc); + _mav_put_float(buf, 40, xgyro); + _mav_put_float(buf, 44, ygyro); + _mav_put_float(buf, 48, zgyro); + _mav_put_float(buf, 52, lat); + _mav_put_float(buf, 56, lon); + _mav_put_float(buf, 60, alt); + _mav_put_float(buf, 64, std_dev_horz); + _mav_put_float(buf, 68, std_dev_vert); + _mav_put_float(buf, 72, vn); + _mav_put_float(buf, 76, ve); + _mav_put_float(buf, 80, vd); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN); +#else + mavlink_sim_state_t packet; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.std_dev_horz = std_dev_horz; + packet.std_dev_vert = std_dev_vert; + packet.vn = vn; + packet.ve = ve; + packet.vd = vd; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SIM_STATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +} + +/** + * @brief Encode a sim_state struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param sim_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sim_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state) +{ + return mavlink_msg_sim_state_pack(system_id, component_id, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd); +} + +/** + * @brief Encode a sim_state struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param sim_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sim_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state) +{ + return mavlink_msg_sim_state_pack_chan(system_id, component_id, chan, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd); +} + +/** + * @brief Send a sim_state message + * @param chan MAVLink channel to send the message + * + * @param q1 True attitude quaternion component 1, w (1 in null-rotation) + * @param q2 True attitude quaternion component 2, x (0 in null-rotation) + * @param q3 True attitude quaternion component 3, y (0 in null-rotation) + * @param q4 True attitude quaternion component 4, z (0 in null-rotation) + * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + * @param xacc X acceleration m/s/s + * @param yacc Y acceleration m/s/s + * @param zacc Z acceleration m/s/s + * @param xgyro Angular speed around X axis rad/s + * @param ygyro Angular speed around Y axis rad/s + * @param zgyro Angular speed around Z axis rad/s + * @param lat Latitude in degrees + * @param lon Longitude in degrees + * @param alt Altitude in meters + * @param std_dev_horz Horizontal position standard deviation + * @param std_dev_vert Vertical position standard deviation + * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame + * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame + * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_sim_state_send(mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; + _mav_put_float(buf, 0, q1); + _mav_put_float(buf, 4, q2); + _mav_put_float(buf, 8, q3); + _mav_put_float(buf, 12, q4); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + _mav_put_float(buf, 28, xacc); + _mav_put_float(buf, 32, yacc); + _mav_put_float(buf, 36, zacc); + _mav_put_float(buf, 40, xgyro); + _mav_put_float(buf, 44, ygyro); + _mav_put_float(buf, 48, zgyro); + _mav_put_float(buf, 52, lat); + _mav_put_float(buf, 56, lon); + _mav_put_float(buf, 60, alt); + _mav_put_float(buf, 64, std_dev_horz); + _mav_put_float(buf, 68, std_dev_vert); + _mav_put_float(buf, 72, vn); + _mav_put_float(buf, 76, ve); + _mav_put_float(buf, 80, vd); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +#else + mavlink_sim_state_t packet; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.std_dev_horz = std_dev_horz; + packet.std_dev_vert = std_dev_vert; + packet.vn = vn; + packet.ve = ve; + packet.vd = vd; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SIM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_sim_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, q1); + _mav_put_float(buf, 4, q2); + _mav_put_float(buf, 8, q3); + _mav_put_float(buf, 12, q4); + _mav_put_float(buf, 16, roll); + _mav_put_float(buf, 20, pitch); + _mav_put_float(buf, 24, yaw); + _mav_put_float(buf, 28, xacc); + _mav_put_float(buf, 32, yacc); + _mav_put_float(buf, 36, zacc); + _mav_put_float(buf, 40, xgyro); + _mav_put_float(buf, 44, ygyro); + _mav_put_float(buf, 48, zgyro); + _mav_put_float(buf, 52, lat); + _mav_put_float(buf, 56, lon); + _mav_put_float(buf, 60, alt); + _mav_put_float(buf, 64, std_dev_horz); + _mav_put_float(buf, 68, std_dev_vert); + _mav_put_float(buf, 72, vn); + _mav_put_float(buf, 76, ve); + _mav_put_float(buf, 80, vd); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +#else + mavlink_sim_state_t *packet = (mavlink_sim_state_t *)msgbuf; + packet->q1 = q1; + packet->q2 = q2; + packet->q3 = q3; + packet->q4 = q4; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->lat = lat; + packet->lon = lon; + packet->alt = alt; + packet->std_dev_horz = std_dev_horz; + packet->std_dev_vert = std_dev_vert; + packet->vn = vn; + packet->ve = ve; + packet->vd = vd; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SIM_STATE UNPACKING + + +/** + * @brief Get field q1 from sim_state message + * + * @return True attitude quaternion component 1, w (1 in null-rotation) + */ +static inline float mavlink_msg_sim_state_get_q1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field q2 from sim_state message + * + * @return True attitude quaternion component 2, x (0 in null-rotation) + */ +static inline float mavlink_msg_sim_state_get_q2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field q3 from sim_state message + * + * @return True attitude quaternion component 3, y (0 in null-rotation) + */ +static inline float mavlink_msg_sim_state_get_q3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field q4 from sim_state message + * + * @return True attitude quaternion component 4, z (0 in null-rotation) + */ +static inline float mavlink_msg_sim_state_get_q4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field roll from sim_state message + * + * @return Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + */ +static inline float mavlink_msg_sim_state_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field pitch from sim_state message + * + * @return Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + */ +static inline float mavlink_msg_sim_state_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field yaw from sim_state message + * + * @return Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + */ +static inline float mavlink_msg_sim_state_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field xacc from sim_state message + * + * @return X acceleration m/s/s + */ +static inline float mavlink_msg_sim_state_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field yacc from sim_state message + * + * @return Y acceleration m/s/s + */ +static inline float mavlink_msg_sim_state_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field zacc from sim_state message + * + * @return Z acceleration m/s/s + */ +static inline float mavlink_msg_sim_state_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field xgyro from sim_state message + * + * @return Angular speed around X axis rad/s + */ +static inline float mavlink_msg_sim_state_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field ygyro from sim_state message + * + * @return Angular speed around Y axis rad/s + */ +static inline float mavlink_msg_sim_state_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field zgyro from sim_state message + * + * @return Angular speed around Z axis rad/s + */ +static inline float mavlink_msg_sim_state_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 48); +} + +/** + * @brief Get field lat from sim_state message + * + * @return Latitude in degrees + */ +static inline float mavlink_msg_sim_state_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 52); +} + +/** + * @brief Get field lon from sim_state message + * + * @return Longitude in degrees + */ +static inline float mavlink_msg_sim_state_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 56); +} + +/** + * @brief Get field alt from sim_state message + * + * @return Altitude in meters + */ +static inline float mavlink_msg_sim_state_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 60); +} + +/** + * @brief Get field std_dev_horz from sim_state message + * + * @return Horizontal position standard deviation + */ +static inline float mavlink_msg_sim_state_get_std_dev_horz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 64); +} + +/** + * @brief Get field std_dev_vert from sim_state message + * + * @return Vertical position standard deviation + */ +static inline float mavlink_msg_sim_state_get_std_dev_vert(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 68); +} + +/** + * @brief Get field vn from sim_state message + * + * @return True velocity in m/s in NORTH direction in earth-fixed NED frame + */ +static inline float mavlink_msg_sim_state_get_vn(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 72); +} + +/** + * @brief Get field ve from sim_state message + * + * @return True velocity in m/s in EAST direction in earth-fixed NED frame + */ +static inline float mavlink_msg_sim_state_get_ve(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 76); +} + +/** + * @brief Get field vd from sim_state message + * + * @return True velocity in m/s in DOWN direction in earth-fixed NED frame + */ +static inline float mavlink_msg_sim_state_get_vd(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 80); +} + +/** + * @brief Decode a sim_state message into a struct + * + * @param msg The message to decode + * @param sim_state C-struct to decode the message contents into + */ +static inline void mavlink_msg_sim_state_decode(const mavlink_message_t* msg, mavlink_sim_state_t* sim_state) +{ +#if MAVLINK_NEED_BYTE_SWAP + sim_state->q1 = mavlink_msg_sim_state_get_q1(msg); + sim_state->q2 = mavlink_msg_sim_state_get_q2(msg); + sim_state->q3 = mavlink_msg_sim_state_get_q3(msg); + sim_state->q4 = mavlink_msg_sim_state_get_q4(msg); + sim_state->roll = mavlink_msg_sim_state_get_roll(msg); + sim_state->pitch = mavlink_msg_sim_state_get_pitch(msg); + sim_state->yaw = mavlink_msg_sim_state_get_yaw(msg); + sim_state->xacc = mavlink_msg_sim_state_get_xacc(msg); + sim_state->yacc = mavlink_msg_sim_state_get_yacc(msg); + sim_state->zacc = mavlink_msg_sim_state_get_zacc(msg); + sim_state->xgyro = mavlink_msg_sim_state_get_xgyro(msg); + sim_state->ygyro = mavlink_msg_sim_state_get_ygyro(msg); + sim_state->zgyro = mavlink_msg_sim_state_get_zgyro(msg); + sim_state->lat = mavlink_msg_sim_state_get_lat(msg); + sim_state->lon = mavlink_msg_sim_state_get_lon(msg); + sim_state->alt = mavlink_msg_sim_state_get_alt(msg); + sim_state->std_dev_horz = mavlink_msg_sim_state_get_std_dev_horz(msg); + sim_state->std_dev_vert = mavlink_msg_sim_state_get_std_dev_vert(msg); + sim_state->vn = mavlink_msg_sim_state_get_vn(msg); + sim_state->ve = mavlink_msg_sim_state_get_ve(msg); + sim_state->vd = mavlink_msg_sim_state_get_vd(msg); +#else + memcpy(sim_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SIM_STATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_statustext.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_statustext.h new file mode 100644 index 0000000..9dcbff8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_statustext.h @@ -0,0 +1,225 @@ +// MESSAGE STATUSTEXT PACKING + +#define MAVLINK_MSG_ID_STATUSTEXT 253 + +typedef struct __mavlink_statustext_t +{ + uint8_t severity; /*< Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.*/ + char text[50]; /*< Status text message, without null termination character*/ +} mavlink_statustext_t; + +#define MAVLINK_MSG_ID_STATUSTEXT_LEN 51 +#define MAVLINK_MSG_ID_253_LEN 51 + +#define MAVLINK_MSG_ID_STATUSTEXT_CRC 83 +#define MAVLINK_MSG_ID_253_CRC 83 + +#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50 + +#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \ + "STATUSTEXT", \ + 2, \ + { { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \ + { "text", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_statustext_t, text) }, \ + } \ +} + + +/** + * @brief Pack a statustext message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + * @param text Status text message, without null termination character + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t severity, const char *text) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN]; + _mav_put_uint8_t(buf, 0, severity); + _mav_put_char_array(buf, 1, text, 50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#else + mavlink_statustext_t packet; + packet.severity = severity; + mav_array_memcpy(packet.text, text, sizeof(char)*50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif +} + +/** + * @brief Pack a statustext message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + * @param text Status text message, without null termination character + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t severity,const char *text) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN]; + _mav_put_uint8_t(buf, 0, severity); + _mav_put_char_array(buf, 1, text, 50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#else + mavlink_statustext_t packet; + packet.severity = severity; + mav_array_memcpy(packet.text, text, sizeof(char)*50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif +} + +/** + * @brief Encode a statustext struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param statustext C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_statustext_t* statustext) +{ + return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text); +} + +/** + * @brief Encode a statustext struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param statustext C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_statustext_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_statustext_t* statustext) +{ + return mavlink_msg_statustext_pack_chan(system_id, component_id, chan, msg, statustext->severity, statustext->text); +} + +/** + * @brief Send a statustext message + * @param chan MAVLink channel to send the message + * + * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + * @param text Status text message, without null termination character + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const char *text) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN]; + _mav_put_uint8_t(buf, 0, severity); + _mav_put_char_array(buf, 1, text, 50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif +#else + mavlink_statustext_t packet; + packet.severity = severity; + mav_array_memcpy(packet.text, text, sizeof(char)*50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_STATUSTEXT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_statustext_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t severity, const char *text) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, severity); + _mav_put_char_array(buf, 1, text, 50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif +#else + mavlink_statustext_t *packet = (mavlink_statustext_t *)msgbuf; + packet->severity = severity; + mav_array_memcpy(packet->text, text, sizeof(char)*50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)packet, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE STATUSTEXT UNPACKING + + +/** + * @brief Get field severity from statustext message + * + * @return Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + */ +static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field text from statustext message + * + * @return Status text message, without null termination character + */ +static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, char *text) +{ + return _MAV_RETURN_char_array(msg, text, 50, 1); +} + +/** + * @brief Decode a statustext message into a struct + * + * @param msg The message to decode + * @param statustext C-struct to decode the message contents into + */ +static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext) +{ +#if MAVLINK_NEED_BYTE_SWAP + statustext->severity = mavlink_msg_statustext_get_severity(msg); + mavlink_msg_statustext_get_text(msg, statustext->text); +#else + memcpy(statustext, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_STATUSTEXT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_sys_status.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_sys_status.h new file mode 100644 index 0000000..e4e4099 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_sys_status.h @@ -0,0 +1,497 @@ +// MESSAGE SYS_STATUS PACKING + +#define MAVLINK_MSG_ID_SYS_STATUS 1 + +typedef struct __mavlink_sys_status_t +{ + uint32_t onboard_control_sensors_present; /*< Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/ + uint32_t onboard_control_sensors_enabled; /*< Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/ + uint32_t onboard_control_sensors_health; /*< Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR*/ + uint16_t load; /*< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000*/ + uint16_t voltage_battery; /*< Battery voltage, in millivolts (1 = 1 millivolt)*/ + int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current*/ + uint16_t drop_rate_comm; /*< Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/ + uint16_t errors_comm; /*< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/ + uint16_t errors_count1; /*< Autopilot-specific errors*/ + uint16_t errors_count2; /*< Autopilot-specific errors*/ + uint16_t errors_count3; /*< Autopilot-specific errors*/ + uint16_t errors_count4; /*< Autopilot-specific errors*/ + int8_t battery_remaining; /*< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery*/ +} mavlink_sys_status_t; + +#define MAVLINK_MSG_ID_SYS_STATUS_LEN 31 +#define MAVLINK_MSG_ID_1_LEN 31 + +#define MAVLINK_MSG_ID_SYS_STATUS_CRC 124 +#define MAVLINK_MSG_ID_1_CRC 124 + + + +#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \ + "SYS_STATUS", \ + 13, \ + { { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \ + { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \ + { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \ + { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \ + { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \ + { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \ + { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \ + { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \ + { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \ + { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \ + { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \ + { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \ + { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \ + } \ +} + + +/** + * @brief Pack a sys_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_count1 Autopilot-specific errors + * @param errors_count2 Autopilot-specific errors + * @param errors_count3 Autopilot-specific errors + * @param errors_count4 Autopilot-specific errors + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN]; + _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); + _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); + _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); + _mav_put_uint16_t(buf, 12, load); + _mav_put_uint16_t(buf, 14, voltage_battery); + _mav_put_int16_t(buf, 16, current_battery); + _mav_put_uint16_t(buf, 18, drop_rate_comm); + _mav_put_uint16_t(buf, 20, errors_comm); + _mav_put_uint16_t(buf, 22, errors_count1); + _mav_put_uint16_t(buf, 24, errors_count2); + _mav_put_uint16_t(buf, 26, errors_count3); + _mav_put_uint16_t(buf, 28, errors_count4); + _mav_put_int8_t(buf, 30, battery_remaining); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#else + mavlink_sys_status_t packet; + packet.onboard_control_sensors_present = onboard_control_sensors_present; + packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; + packet.onboard_control_sensors_health = onboard_control_sensors_health; + packet.load = load; + packet.voltage_battery = voltage_battery; + packet.current_battery = current_battery; + packet.drop_rate_comm = drop_rate_comm; + packet.errors_comm = errors_comm; + packet.errors_count1 = errors_count1; + packet.errors_count2 = errors_count2; + packet.errors_count3 = errors_count3; + packet.errors_count4 = errors_count4; + packet.battery_remaining = battery_remaining; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif +} + +/** + * @brief Pack a sys_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_count1 Autopilot-specific errors + * @param errors_count2 Autopilot-specific errors + * @param errors_count3 Autopilot-specific errors + * @param errors_count4 Autopilot-specific errors + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t onboard_control_sensors_present,uint32_t onboard_control_sensors_enabled,uint32_t onboard_control_sensors_health,uint16_t load,uint16_t voltage_battery,int16_t current_battery,int8_t battery_remaining,uint16_t drop_rate_comm,uint16_t errors_comm,uint16_t errors_count1,uint16_t errors_count2,uint16_t errors_count3,uint16_t errors_count4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN]; + _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); + _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); + _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); + _mav_put_uint16_t(buf, 12, load); + _mav_put_uint16_t(buf, 14, voltage_battery); + _mav_put_int16_t(buf, 16, current_battery); + _mav_put_uint16_t(buf, 18, drop_rate_comm); + _mav_put_uint16_t(buf, 20, errors_comm); + _mav_put_uint16_t(buf, 22, errors_count1); + _mav_put_uint16_t(buf, 24, errors_count2); + _mav_put_uint16_t(buf, 26, errors_count3); + _mav_put_uint16_t(buf, 28, errors_count4); + _mav_put_int8_t(buf, 30, battery_remaining); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#else + mavlink_sys_status_t packet; + packet.onboard_control_sensors_present = onboard_control_sensors_present; + packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; + packet.onboard_control_sensors_health = onboard_control_sensors_health; + packet.load = load; + packet.voltage_battery = voltage_battery; + packet.current_battery = current_battery; + packet.drop_rate_comm = drop_rate_comm; + packet.errors_comm = errors_comm; + packet.errors_count1 = errors_count1; + packet.errors_count2 = errors_count2; + packet.errors_count3 = errors_count3; + packet.errors_count4 = errors_count4; + packet.battery_remaining = battery_remaining; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif +} + +/** + * @brief Encode a sys_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param sys_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) +{ + return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4); +} + +/** + * @brief Encode a sys_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param sys_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sys_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) +{ + return mavlink_msg_sys_status_pack_chan(system_id, component_id, chan, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4); +} + +/** + * @brief Send a sys_status message + * @param chan MAVLink channel to send the message + * + * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_count1 Autopilot-specific errors + * @param errors_count2 Autopilot-specific errors + * @param errors_count3 Autopilot-specific errors + * @param errors_count4 Autopilot-specific errors + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN]; + _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); + _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); + _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); + _mav_put_uint16_t(buf, 12, load); + _mav_put_uint16_t(buf, 14, voltage_battery); + _mav_put_int16_t(buf, 16, current_battery); + _mav_put_uint16_t(buf, 18, drop_rate_comm); + _mav_put_uint16_t(buf, 20, errors_comm); + _mav_put_uint16_t(buf, 22, errors_count1); + _mav_put_uint16_t(buf, 24, errors_count2); + _mav_put_uint16_t(buf, 26, errors_count3); + _mav_put_uint16_t(buf, 28, errors_count4); + _mav_put_int8_t(buf, 30, battery_remaining); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif +#else + mavlink_sys_status_t packet; + packet.onboard_control_sensors_present = onboard_control_sensors_present; + packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; + packet.onboard_control_sensors_health = onboard_control_sensors_health; + packet.load = load; + packet.voltage_battery = voltage_battery; + packet.current_battery = current_battery; + packet.drop_rate_comm = drop_rate_comm; + packet.errors_comm = errors_comm; + packet.errors_count1 = errors_count1; + packet.errors_count2 = errors_count2; + packet.errors_count3 = errors_count3; + packet.errors_count4 = errors_count4; + packet.battery_remaining = battery_remaining; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SYS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_sys_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); + _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); + _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); + _mav_put_uint16_t(buf, 12, load); + _mav_put_uint16_t(buf, 14, voltage_battery); + _mav_put_int16_t(buf, 16, current_battery); + _mav_put_uint16_t(buf, 18, drop_rate_comm); + _mav_put_uint16_t(buf, 20, errors_comm); + _mav_put_uint16_t(buf, 22, errors_count1); + _mav_put_uint16_t(buf, 24, errors_count2); + _mav_put_uint16_t(buf, 26, errors_count3); + _mav_put_uint16_t(buf, 28, errors_count4); + _mav_put_int8_t(buf, 30, battery_remaining); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif +#else + mavlink_sys_status_t *packet = (mavlink_sys_status_t *)msgbuf; + packet->onboard_control_sensors_present = onboard_control_sensors_present; + packet->onboard_control_sensors_enabled = onboard_control_sensors_enabled; + packet->onboard_control_sensors_health = onboard_control_sensors_health; + packet->load = load; + packet->voltage_battery = voltage_battery; + packet->current_battery = current_battery; + packet->drop_rate_comm = drop_rate_comm; + packet->errors_comm = errors_comm; + packet->errors_count1 = errors_count1; + packet->errors_count2 = errors_count2; + packet->errors_count3 = errors_count3; + packet->errors_count4 = errors_count4; + packet->battery_remaining = battery_remaining; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)packet, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SYS_STATUS UNPACKING + + +/** + * @brief Get field onboard_control_sensors_present from sys_status message + * + * @return Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + */ +static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field onboard_control_sensors_enabled from sys_status message + * + * @return Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + */ +static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Get field onboard_control_sensors_health from sys_status message + * + * @return Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + */ +static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field load from sys_status message + * + * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + */ +static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field voltage_battery from sys_status message + * + * @return Battery voltage, in millivolts (1 = 1 millivolt) + */ +static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field current_battery from sys_status message + * + * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + */ +static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field battery_remaining from sys_status message + * + * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + */ +static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 30); +} + +/** + * @brief Get field drop_rate_comm from sys_status message + * + * @return Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + */ +static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field errors_comm from sys_status message + * + * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field errors_count1 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field errors_count2 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field errors_count3 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field errors_count4 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Decode a sys_status message into a struct + * + * @param msg The message to decode + * @param sys_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + sys_status->onboard_control_sensors_present = mavlink_msg_sys_status_get_onboard_control_sensors_present(msg); + sys_status->onboard_control_sensors_enabled = mavlink_msg_sys_status_get_onboard_control_sensors_enabled(msg); + sys_status->onboard_control_sensors_health = mavlink_msg_sys_status_get_onboard_control_sensors_health(msg); + sys_status->load = mavlink_msg_sys_status_get_load(msg); + sys_status->voltage_battery = mavlink_msg_sys_status_get_voltage_battery(msg); + sys_status->current_battery = mavlink_msg_sys_status_get_current_battery(msg); + sys_status->drop_rate_comm = mavlink_msg_sys_status_get_drop_rate_comm(msg); + sys_status->errors_comm = mavlink_msg_sys_status_get_errors_comm(msg); + sys_status->errors_count1 = mavlink_msg_sys_status_get_errors_count1(msg); + sys_status->errors_count2 = mavlink_msg_sys_status_get_errors_count2(msg); + sys_status->errors_count3 = mavlink_msg_sys_status_get_errors_count3(msg); + sys_status->errors_count4 = mavlink_msg_sys_status_get_errors_count4(msg); + sys_status->battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg); +#else + memcpy(sys_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SYS_STATUS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_system_time.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_system_time.h new file mode 100644 index 0000000..e2aab67 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_system_time.h @@ -0,0 +1,233 @@ +// MESSAGE SYSTEM_TIME PACKING + +#define MAVLINK_MSG_ID_SYSTEM_TIME 2 + +typedef struct __mavlink_system_time_t +{ + uint64_t time_unix_usec; /*< Timestamp of the master clock in microseconds since UNIX epoch.*/ + uint32_t time_boot_ms; /*< Timestamp of the component clock since boot time in milliseconds.*/ +} mavlink_system_time_t; + +#define MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12 +#define MAVLINK_MSG_ID_2_LEN 12 + +#define MAVLINK_MSG_ID_SYSTEM_TIME_CRC 137 +#define MAVLINK_MSG_ID_2_CRC 137 + + + +#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \ + "SYSTEM_TIME", \ + 2, \ + { { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \ + { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \ + } \ +} + + +/** + * @brief Pack a system_time message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. + * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_unix_usec, uint32_t time_boot_ms) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN]; + _mav_put_uint64_t(buf, 0, time_unix_usec); + _mav_put_uint32_t(buf, 8, time_boot_ms); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#else + mavlink_system_time_t packet; + packet.time_unix_usec = time_unix_usec; + packet.time_boot_ms = time_boot_ms; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif +} + +/** + * @brief Pack a system_time message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. + * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_unix_usec,uint32_t time_boot_ms) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN]; + _mav_put_uint64_t(buf, 0, time_unix_usec); + _mav_put_uint32_t(buf, 8, time_boot_ms); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#else + mavlink_system_time_t packet; + packet.time_unix_usec = time_unix_usec; + packet.time_boot_ms = time_boot_ms; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif +} + +/** + * @brief Encode a system_time struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param system_time C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_t* system_time) +{ + return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_unix_usec, system_time->time_boot_ms); +} + +/** + * @brief Encode a system_time struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param system_time C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_system_time_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_system_time_t* system_time) +{ + return mavlink_msg_system_time_pack_chan(system_id, component_id, chan, msg, system_time->time_unix_usec, system_time->time_boot_ms); +} + +/** + * @brief Send a system_time message + * @param chan MAVLink channel to send the message + * + * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. + * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN]; + _mav_put_uint64_t(buf, 0, time_unix_usec); + _mav_put_uint32_t(buf, 8, time_boot_ms); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif +#else + mavlink_system_time_t packet; + packet.time_unix_usec = time_unix_usec; + packet.time_boot_ms = time_boot_ms; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)&packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)&packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SYSTEM_TIME_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_system_time_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_unix_usec); + _mav_put_uint32_t(buf, 8, time_boot_ms); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif +#else + mavlink_system_time_t *packet = (mavlink_system_time_t *)msgbuf; + packet->time_unix_usec = time_unix_usec; + packet->time_boot_ms = time_boot_ms; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SYSTEM_TIME UNPACKING + + +/** + * @brief Get field time_unix_usec from system_time message + * + * @return Timestamp of the master clock in microseconds since UNIX epoch. + */ +static inline uint64_t mavlink_msg_system_time_get_time_unix_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field time_boot_ms from system_time message + * + * @return Timestamp of the component clock since boot time in milliseconds. + */ +static inline uint32_t mavlink_msg_system_time_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Decode a system_time message into a struct + * + * @param msg The message to decode + * @param system_time C-struct to decode the message contents into + */ +static inline void mavlink_msg_system_time_decode(const mavlink_message_t* msg, mavlink_system_time_t* system_time) +{ +#if MAVLINK_NEED_BYTE_SWAP + system_time->time_unix_usec = mavlink_msg_system_time_get_time_unix_usec(msg); + system_time->time_boot_ms = mavlink_msg_system_time_get_time_boot_ms(msg); +#else + memcpy(system_time, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SYSTEM_TIME_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_terrain_check.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_terrain_check.h new file mode 100644 index 0000000..d4ecaf3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_terrain_check.h @@ -0,0 +1,233 @@ +// MESSAGE TERRAIN_CHECK PACKING + +#define MAVLINK_MSG_ID_TERRAIN_CHECK 135 + +typedef struct __mavlink_terrain_check_t +{ + int32_t lat; /*< Latitude (degrees *10^7)*/ + int32_t lon; /*< Longitude (degrees *10^7)*/ +} mavlink_terrain_check_t; + +#define MAVLINK_MSG_ID_TERRAIN_CHECK_LEN 8 +#define MAVLINK_MSG_ID_135_LEN 8 + +#define MAVLINK_MSG_ID_TERRAIN_CHECK_CRC 203 +#define MAVLINK_MSG_ID_135_CRC 203 + + + +#define MAVLINK_MESSAGE_INFO_TERRAIN_CHECK { \ + "TERRAIN_CHECK", \ + 2, \ + { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_check_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_check_t, lon) }, \ + } \ +} + + +/** + * @brief Pack a terrain_check message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param lat Latitude (degrees *10^7) + * @param lon Longitude (degrees *10^7) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_check_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int32_t lat, int32_t lon) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#else + mavlink_terrain_check_t packet; + packet.lat = lat; + packet.lon = lon; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_CHECK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif +} + +/** + * @brief Pack a terrain_check message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param lat Latitude (degrees *10^7) + * @param lon Longitude (degrees *10^7) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_check_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int32_t lat,int32_t lon) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#else + mavlink_terrain_check_t packet; + packet.lat = lat; + packet.lon = lon; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_CHECK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif +} + +/** + * @brief Encode a terrain_check struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param terrain_check C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_check_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_check_t* terrain_check) +{ + return mavlink_msg_terrain_check_pack(system_id, component_id, msg, terrain_check->lat, terrain_check->lon); +} + +/** + * @brief Encode a terrain_check struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param terrain_check C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_check_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_check_t* terrain_check) +{ + return mavlink_msg_terrain_check_pack_chan(system_id, component_id, chan, msg, terrain_check->lat, terrain_check->lon); +} + +/** + * @brief Send a terrain_check message + * @param chan MAVLink channel to send the message + * + * @param lat Latitude (degrees *10^7) + * @param lon Longitude (degrees *10^7) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_terrain_check_send(mavlink_channel_t chan, int32_t lat, int32_t lon) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif +#else + mavlink_terrain_check_t packet; + packet.lat = lat; + packet.lon = lon; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_TERRAIN_CHECK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_terrain_check_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif +#else + mavlink_terrain_check_t *packet = (mavlink_terrain_check_t *)msgbuf; + packet->lat = lat; + packet->lon = lon; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE TERRAIN_CHECK UNPACKING + + +/** + * @brief Get field lat from terrain_check message + * + * @return Latitude (degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_check_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field lon from terrain_check message + * + * @return Longitude (degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_check_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Decode a terrain_check message into a struct + * + * @param msg The message to decode + * @param terrain_check C-struct to decode the message contents into + */ +static inline void mavlink_msg_terrain_check_decode(const mavlink_message_t* msg, mavlink_terrain_check_t* terrain_check) +{ +#if MAVLINK_NEED_BYTE_SWAP + terrain_check->lat = mavlink_msg_terrain_check_get_lat(msg); + terrain_check->lon = mavlink_msg_terrain_check_get_lon(msg); +#else + memcpy(terrain_check, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_terrain_data.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_terrain_data.h new file mode 100644 index 0000000..2e2f05a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_terrain_data.h @@ -0,0 +1,297 @@ +// MESSAGE TERRAIN_DATA PACKING + +#define MAVLINK_MSG_ID_TERRAIN_DATA 134 + +typedef struct __mavlink_terrain_data_t +{ + int32_t lat; /*< Latitude of SW corner of first grid (degrees *10^7)*/ + int32_t lon; /*< Longitude of SW corner of first grid (in degrees *10^7)*/ + uint16_t grid_spacing; /*< Grid spacing in meters*/ + int16_t data[16]; /*< Terrain data in meters AMSL*/ + uint8_t gridbit; /*< bit within the terrain request mask*/ +} mavlink_terrain_data_t; + +#define MAVLINK_MSG_ID_TERRAIN_DATA_LEN 43 +#define MAVLINK_MSG_ID_134_LEN 43 + +#define MAVLINK_MSG_ID_TERRAIN_DATA_CRC 229 +#define MAVLINK_MSG_ID_134_CRC 229 + +#define MAVLINK_MSG_TERRAIN_DATA_FIELD_DATA_LEN 16 + +#define MAVLINK_MESSAGE_INFO_TERRAIN_DATA { \ + "TERRAIN_DATA", \ + 5, \ + { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \ + { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \ + { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \ + { "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \ + } \ +} + + +/** + * @brief Pack a terrain_data message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param lat Latitude of SW corner of first grid (degrees *10^7) + * @param lon Longitude of SW corner of first grid (in degrees *10^7) + * @param grid_spacing Grid spacing in meters + * @param gridbit bit within the terrain request mask + * @param data Terrain data in meters AMSL + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_uint16_t(buf, 8, grid_spacing); + _mav_put_uint8_t(buf, 42, gridbit); + _mav_put_int16_t_array(buf, 10, data, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#else + mavlink_terrain_data_t packet; + packet.lat = lat; + packet.lon = lon; + packet.grid_spacing = grid_spacing; + packet.gridbit = gridbit; + mav_array_memcpy(packet.data, data, sizeof(int16_t)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif +} + +/** + * @brief Pack a terrain_data message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param lat Latitude of SW corner of first grid (degrees *10^7) + * @param lon Longitude of SW corner of first grid (in degrees *10^7) + * @param grid_spacing Grid spacing in meters + * @param gridbit bit within the terrain request mask + * @param data Terrain data in meters AMSL + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int32_t lat,int32_t lon,uint16_t grid_spacing,uint8_t gridbit,const int16_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_uint16_t(buf, 8, grid_spacing); + _mav_put_uint8_t(buf, 42, gridbit); + _mav_put_int16_t_array(buf, 10, data, 16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#else + mavlink_terrain_data_t packet; + packet.lat = lat; + packet.lon = lon; + packet.grid_spacing = grid_spacing; + packet.gridbit = gridbit; + mav_array_memcpy(packet.data, data, sizeof(int16_t)*16); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif +} + +/** + * @brief Encode a terrain_data struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param terrain_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_data_t* terrain_data) +{ + return mavlink_msg_terrain_data_pack(system_id, component_id, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data); +} + +/** + * @brief Encode a terrain_data struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param terrain_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_data_t* terrain_data) +{ + return mavlink_msg_terrain_data_pack_chan(system_id, component_id, chan, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data); +} + +/** + * @brief Send a terrain_data message + * @param chan MAVLink channel to send the message + * + * @param lat Latitude of SW corner of first grid (degrees *10^7) + * @param lon Longitude of SW corner of first grid (in degrees *10^7) + * @param grid_spacing Grid spacing in meters + * @param gridbit bit within the terrain request mask + * @param data Terrain data in meters AMSL + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_terrain_data_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_uint16_t(buf, 8, grid_spacing); + _mav_put_uint8_t(buf, 42, gridbit); + _mav_put_int16_t_array(buf, 10, data, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif +#else + mavlink_terrain_data_t packet; + packet.lat = lat; + packet.lon = lon; + packet.grid_spacing = grid_spacing; + packet.gridbit = gridbit; + mav_array_memcpy(packet.data, data, sizeof(int16_t)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_TERRAIN_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_terrain_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_uint16_t(buf, 8, grid_spacing); + _mav_put_uint8_t(buf, 42, gridbit); + _mav_put_int16_t_array(buf, 10, data, 16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif +#else + mavlink_terrain_data_t *packet = (mavlink_terrain_data_t *)msgbuf; + packet->lat = lat; + packet->lon = lon; + packet->grid_spacing = grid_spacing; + packet->gridbit = gridbit; + mav_array_memcpy(packet->data, data, sizeof(int16_t)*16); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE TERRAIN_DATA UNPACKING + + +/** + * @brief Get field lat from terrain_data message + * + * @return Latitude of SW corner of first grid (degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_data_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field lon from terrain_data message + * + * @return Longitude of SW corner of first grid (in degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_data_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field grid_spacing from terrain_data message + * + * @return Grid spacing in meters + */ +static inline uint16_t mavlink_msg_terrain_data_get_grid_spacing(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field gridbit from terrain_data message + * + * @return bit within the terrain request mask + */ +static inline uint8_t mavlink_msg_terrain_data_get_gridbit(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 42); +} + +/** + * @brief Get field data from terrain_data message + * + * @return Terrain data in meters AMSL + */ +static inline uint16_t mavlink_msg_terrain_data_get_data(const mavlink_message_t* msg, int16_t *data) +{ + return _MAV_RETURN_int16_t_array(msg, data, 16, 10); +} + +/** + * @brief Decode a terrain_data message into a struct + * + * @param msg The message to decode + * @param terrain_data C-struct to decode the message contents into + */ +static inline void mavlink_msg_terrain_data_decode(const mavlink_message_t* msg, mavlink_terrain_data_t* terrain_data) +{ +#if MAVLINK_NEED_BYTE_SWAP + terrain_data->lat = mavlink_msg_terrain_data_get_lat(msg); + terrain_data->lon = mavlink_msg_terrain_data_get_lon(msg); + terrain_data->grid_spacing = mavlink_msg_terrain_data_get_grid_spacing(msg); + mavlink_msg_terrain_data_get_data(msg, terrain_data->data); + terrain_data->gridbit = mavlink_msg_terrain_data_get_gridbit(msg); +#else + memcpy(terrain_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_DATA_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_terrain_report.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_terrain_report.h new file mode 100644 index 0000000..2ed7db6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_terrain_report.h @@ -0,0 +1,353 @@ +// MESSAGE TERRAIN_REPORT PACKING + +#define MAVLINK_MSG_ID_TERRAIN_REPORT 136 + +typedef struct __mavlink_terrain_report_t +{ + int32_t lat; /*< Latitude (degrees *10^7)*/ + int32_t lon; /*< Longitude (degrees *10^7)*/ + float terrain_height; /*< Terrain height in meters AMSL*/ + float current_height; /*< Current vehicle height above lat/lon terrain height (meters)*/ + uint16_t spacing; /*< grid spacing (zero if terrain at this location unavailable)*/ + uint16_t pending; /*< Number of 4x4 terrain blocks waiting to be received or read from disk*/ + uint16_t loaded; /*< Number of 4x4 terrain blocks in memory*/ +} mavlink_terrain_report_t; + +#define MAVLINK_MSG_ID_TERRAIN_REPORT_LEN 22 +#define MAVLINK_MSG_ID_136_LEN 22 + +#define MAVLINK_MSG_ID_TERRAIN_REPORT_CRC 1 +#define MAVLINK_MSG_ID_136_CRC 1 + + + +#define MAVLINK_MESSAGE_INFO_TERRAIN_REPORT { \ + "TERRAIN_REPORT", \ + 7, \ + { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_report_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_report_t, lon) }, \ + { "terrain_height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_terrain_report_t, terrain_height) }, \ + { "current_height", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_terrain_report_t, current_height) }, \ + { "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \ + { "pending", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_terrain_report_t, pending) }, \ + { "loaded", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_terrain_report_t, loaded) }, \ + } \ +} + + +/** + * @brief Pack a terrain_report message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param lat Latitude (degrees *10^7) + * @param lon Longitude (degrees *10^7) + * @param spacing grid spacing (zero if terrain at this location unavailable) + * @param terrain_height Terrain height in meters AMSL + * @param current_height Current vehicle height above lat/lon terrain height (meters) + * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk + * @param loaded Number of 4x4 terrain blocks in memory + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_float(buf, 8, terrain_height); + _mav_put_float(buf, 12, current_height); + _mav_put_uint16_t(buf, 16, spacing); + _mav_put_uint16_t(buf, 18, pending); + _mav_put_uint16_t(buf, 20, loaded); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#else + mavlink_terrain_report_t packet; + packet.lat = lat; + packet.lon = lon; + packet.terrain_height = terrain_height; + packet.current_height = current_height; + packet.spacing = spacing; + packet.pending = pending; + packet.loaded = loaded; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif +} + +/** + * @brief Pack a terrain_report message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param lat Latitude (degrees *10^7) + * @param lon Longitude (degrees *10^7) + * @param spacing grid spacing (zero if terrain at this location unavailable) + * @param terrain_height Terrain height in meters AMSL + * @param current_height Current vehicle height above lat/lon terrain height (meters) + * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk + * @param loaded Number of 4x4 terrain blocks in memory + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int32_t lat,int32_t lon,uint16_t spacing,float terrain_height,float current_height,uint16_t pending,uint16_t loaded) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_float(buf, 8, terrain_height); + _mav_put_float(buf, 12, current_height); + _mav_put_uint16_t(buf, 16, spacing); + _mav_put_uint16_t(buf, 18, pending); + _mav_put_uint16_t(buf, 20, loaded); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#else + mavlink_terrain_report_t packet; + packet.lat = lat; + packet.lon = lon; + packet.terrain_height = terrain_height; + packet.current_height = current_height; + packet.spacing = spacing; + packet.pending = pending; + packet.loaded = loaded; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif +} + +/** + * @brief Encode a terrain_report struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param terrain_report C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_report_t* terrain_report) +{ + return mavlink_msg_terrain_report_pack(system_id, component_id, msg, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded); +} + +/** + * @brief Encode a terrain_report struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param terrain_report C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_report_t* terrain_report) +{ + return mavlink_msg_terrain_report_pack_chan(system_id, component_id, chan, msg, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded); +} + +/** + * @brief Send a terrain_report message + * @param chan MAVLink channel to send the message + * + * @param lat Latitude (degrees *10^7) + * @param lon Longitude (degrees *10^7) + * @param spacing grid spacing (zero if terrain at this location unavailable) + * @param terrain_height Terrain height in meters AMSL + * @param current_height Current vehicle height above lat/lon terrain height (meters) + * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk + * @param loaded Number of 4x4 terrain blocks in memory + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_terrain_report_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN]; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_float(buf, 8, terrain_height); + _mav_put_float(buf, 12, current_height); + _mav_put_uint16_t(buf, 16, spacing); + _mav_put_uint16_t(buf, 18, pending); + _mav_put_uint16_t(buf, 20, loaded); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif +#else + mavlink_terrain_report_t packet; + packet.lat = lat; + packet.lon = lon; + packet.terrain_height = terrain_height; + packet.current_height = current_height; + packet.spacing = spacing; + packet.pending = pending; + packet.loaded = loaded; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_TERRAIN_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_terrain_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int32_t(buf, 0, lat); + _mav_put_int32_t(buf, 4, lon); + _mav_put_float(buf, 8, terrain_height); + _mav_put_float(buf, 12, current_height); + _mav_put_uint16_t(buf, 16, spacing); + _mav_put_uint16_t(buf, 18, pending); + _mav_put_uint16_t(buf, 20, loaded); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif +#else + mavlink_terrain_report_t *packet = (mavlink_terrain_report_t *)msgbuf; + packet->lat = lat; + packet->lon = lon; + packet->terrain_height = terrain_height; + packet->current_height = current_height; + packet->spacing = spacing; + packet->pending = pending; + packet->loaded = loaded; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE TERRAIN_REPORT UNPACKING + + +/** + * @brief Get field lat from terrain_report message + * + * @return Latitude (degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_report_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field lon from terrain_report message + * + * @return Longitude (degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_report_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field spacing from terrain_report message + * + * @return grid spacing (zero if terrain at this location unavailable) + */ +static inline uint16_t mavlink_msg_terrain_report_get_spacing(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field terrain_height from terrain_report message + * + * @return Terrain height in meters AMSL + */ +static inline float mavlink_msg_terrain_report_get_terrain_height(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field current_height from terrain_report message + * + * @return Current vehicle height above lat/lon terrain height (meters) + */ +static inline float mavlink_msg_terrain_report_get_current_height(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field pending from terrain_report message + * + * @return Number of 4x4 terrain blocks waiting to be received or read from disk + */ +static inline uint16_t mavlink_msg_terrain_report_get_pending(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field loaded from terrain_report message + * + * @return Number of 4x4 terrain blocks in memory + */ +static inline uint16_t mavlink_msg_terrain_report_get_loaded(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Decode a terrain_report message into a struct + * + * @param msg The message to decode + * @param terrain_report C-struct to decode the message contents into + */ +static inline void mavlink_msg_terrain_report_decode(const mavlink_message_t* msg, mavlink_terrain_report_t* terrain_report) +{ +#if MAVLINK_NEED_BYTE_SWAP + terrain_report->lat = mavlink_msg_terrain_report_get_lat(msg); + terrain_report->lon = mavlink_msg_terrain_report_get_lon(msg); + terrain_report->terrain_height = mavlink_msg_terrain_report_get_terrain_height(msg); + terrain_report->current_height = mavlink_msg_terrain_report_get_current_height(msg); + terrain_report->spacing = mavlink_msg_terrain_report_get_spacing(msg); + terrain_report->pending = mavlink_msg_terrain_report_get_pending(msg); + terrain_report->loaded = mavlink_msg_terrain_report_get_loaded(msg); +#else + memcpy(terrain_report, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_terrain_request.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_terrain_request.h new file mode 100644 index 0000000..fdab6de --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_terrain_request.h @@ -0,0 +1,281 @@ +// MESSAGE TERRAIN_REQUEST PACKING + +#define MAVLINK_MSG_ID_TERRAIN_REQUEST 133 + +typedef struct __mavlink_terrain_request_t +{ + uint64_t mask; /*< Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)*/ + int32_t lat; /*< Latitude of SW corner of first grid (degrees *10^7)*/ + int32_t lon; /*< Longitude of SW corner of first grid (in degrees *10^7)*/ + uint16_t grid_spacing; /*< Grid spacing in meters*/ +} mavlink_terrain_request_t; + +#define MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN 18 +#define MAVLINK_MSG_ID_133_LEN 18 + +#define MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC 6 +#define MAVLINK_MSG_ID_133_CRC 6 + + + +#define MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST { \ + "TERRAIN_REQUEST", \ + 4, \ + { { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_terrain_request_t, lon) }, \ + { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_request_t, grid_spacing) }, \ + } \ +} + + +/** + * @brief Pack a terrain_request message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param lat Latitude of SW corner of first grid (degrees *10^7) + * @param lon Longitude of SW corner of first grid (in degrees *10^7) + * @param grid_spacing Grid spacing in meters + * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN]; + _mav_put_uint64_t(buf, 0, mask); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_uint16_t(buf, 16, grid_spacing); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#else + mavlink_terrain_request_t packet; + packet.mask = mask; + packet.lat = lat; + packet.lon = lon; + packet.grid_spacing = grid_spacing; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_REQUEST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif +} + +/** + * @brief Pack a terrain_request message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param lat Latitude of SW corner of first grid (degrees *10^7) + * @param lon Longitude of SW corner of first grid (in degrees *10^7) + * @param grid_spacing Grid spacing in meters + * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_terrain_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int32_t lat,int32_t lon,uint16_t grid_spacing,uint64_t mask) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN]; + _mav_put_uint64_t(buf, 0, mask); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_uint16_t(buf, 16, grid_spacing); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#else + mavlink_terrain_request_t packet; + packet.mask = mask; + packet.lat = lat; + packet.lon = lon; + packet.grid_spacing = grid_spacing; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TERRAIN_REQUEST; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif +} + +/** + * @brief Encode a terrain_request struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param terrain_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_request_t* terrain_request) +{ + return mavlink_msg_terrain_request_pack(system_id, component_id, msg, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask); +} + +/** + * @brief Encode a terrain_request struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param terrain_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_terrain_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_request_t* terrain_request) +{ + return mavlink_msg_terrain_request_pack_chan(system_id, component_id, chan, msg, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask); +} + +/** + * @brief Send a terrain_request message + * @param chan MAVLink channel to send the message + * + * @param lat Latitude of SW corner of first grid (degrees *10^7) + * @param lon Longitude of SW corner of first grid (in degrees *10^7) + * @param grid_spacing Grid spacing in meters + * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_terrain_request_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN]; + _mav_put_uint64_t(buf, 0, mask); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_uint16_t(buf, 16, grid_spacing); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif +#else + mavlink_terrain_request_t packet; + packet.mask = mask; + packet.lat = lat; + packet.lon = lon; + packet.grid_spacing = grid_spacing; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_terrain_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, mask); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_uint16_t(buf, 16, grid_spacing); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif +#else + mavlink_terrain_request_t *packet = (mavlink_terrain_request_t *)msgbuf; + packet->mask = mask; + packet->lat = lat; + packet->lon = lon; + packet->grid_spacing = grid_spacing; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE TERRAIN_REQUEST UNPACKING + + +/** + * @brief Get field lat from terrain_request message + * + * @return Latitude of SW corner of first grid (degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_request_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field lon from terrain_request message + * + * @return Longitude of SW corner of first grid (in degrees *10^7) + */ +static inline int32_t mavlink_msg_terrain_request_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field grid_spacing from terrain_request message + * + * @return Grid spacing in meters + */ +static inline uint16_t mavlink_msg_terrain_request_get_grid_spacing(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field mask from terrain_request message + * + * @return Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + */ +static inline uint64_t mavlink_msg_terrain_request_get_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Decode a terrain_request message into a struct + * + * @param msg The message to decode + * @param terrain_request C-struct to decode the message contents into + */ +static inline void mavlink_msg_terrain_request_decode(const mavlink_message_t* msg, mavlink_terrain_request_t* terrain_request) +{ +#if MAVLINK_NEED_BYTE_SWAP + terrain_request->mask = mavlink_msg_terrain_request_get_mask(msg); + terrain_request->lat = mavlink_msg_terrain_request_get_lat(msg); + terrain_request->lon = mavlink_msg_terrain_request_get_lon(msg); + terrain_request->grid_spacing = mavlink_msg_terrain_request_get_grid_spacing(msg); +#else + memcpy(terrain_request, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_timesync.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_timesync.h new file mode 100644 index 0000000..be28442 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_timesync.h @@ -0,0 +1,233 @@ +// MESSAGE TIMESYNC PACKING + +#define MAVLINK_MSG_ID_TIMESYNC 111 + +typedef struct __mavlink_timesync_t +{ + int64_t tc1; /*< Time sync timestamp 1*/ + int64_t ts1; /*< Time sync timestamp 2*/ +} mavlink_timesync_t; + +#define MAVLINK_MSG_ID_TIMESYNC_LEN 16 +#define MAVLINK_MSG_ID_111_LEN 16 + +#define MAVLINK_MSG_ID_TIMESYNC_CRC 34 +#define MAVLINK_MSG_ID_111_CRC 34 + + + +#define MAVLINK_MESSAGE_INFO_TIMESYNC { \ + "TIMESYNC", \ + 2, \ + { { "tc1", NULL, MAVLINK_TYPE_INT64_T, 0, 0, offsetof(mavlink_timesync_t, tc1) }, \ + { "ts1", NULL, MAVLINK_TYPE_INT64_T, 0, 8, offsetof(mavlink_timesync_t, ts1) }, \ + } \ +} + + +/** + * @brief Pack a timesync message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param tc1 Time sync timestamp 1 + * @param ts1 Time sync timestamp 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_timesync_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int64_t tc1, int64_t ts1) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TIMESYNC_LEN]; + _mav_put_int64_t(buf, 0, tc1); + _mav_put_int64_t(buf, 8, ts1); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TIMESYNC_LEN); +#else + mavlink_timesync_t packet; + packet.tc1 = tc1; + packet.ts1 = ts1; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TIMESYNC; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif +} + +/** + * @brief Pack a timesync message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param tc1 Time sync timestamp 1 + * @param ts1 Time sync timestamp 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_timesync_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int64_t tc1,int64_t ts1) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TIMESYNC_LEN]; + _mav_put_int64_t(buf, 0, tc1); + _mav_put_int64_t(buf, 8, ts1); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TIMESYNC_LEN); +#else + mavlink_timesync_t packet; + packet.tc1 = tc1; + packet.ts1 = ts1; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_TIMESYNC; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif +} + +/** + * @brief Encode a timesync struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param timesync C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_timesync_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_timesync_t* timesync) +{ + return mavlink_msg_timesync_pack(system_id, component_id, msg, timesync->tc1, timesync->ts1); +} + +/** + * @brief Encode a timesync struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param timesync C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_timesync_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_timesync_t* timesync) +{ + return mavlink_msg_timesync_pack_chan(system_id, component_id, chan, msg, timesync->tc1, timesync->ts1); +} + +/** + * @brief Send a timesync message + * @param chan MAVLink channel to send the message + * + * @param tc1 Time sync timestamp 1 + * @param ts1 Time sync timestamp 2 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_timesync_send(mavlink_channel_t chan, int64_t tc1, int64_t ts1) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_TIMESYNC_LEN]; + _mav_put_int64_t(buf, 0, tc1); + _mav_put_int64_t(buf, 8, ts1); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif +#else + mavlink_timesync_t packet; + packet.tc1 = tc1; + packet.ts1 = ts1; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)&packet, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)&packet, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_TIMESYNC_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_timesync_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int64_t tc1, int64_t ts1) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int64_t(buf, 0, tc1); + _mav_put_int64_t(buf, 8, ts1); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif +#else + mavlink_timesync_t *packet = (mavlink_timesync_t *)msgbuf; + packet->tc1 = tc1; + packet->ts1 = ts1; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)packet, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)packet, MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE TIMESYNC UNPACKING + + +/** + * @brief Get field tc1 from timesync message + * + * @return Time sync timestamp 1 + */ +static inline int64_t mavlink_msg_timesync_get_tc1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int64_t(msg, 0); +} + +/** + * @brief Get field ts1 from timesync message + * + * @return Time sync timestamp 2 + */ +static inline int64_t mavlink_msg_timesync_get_ts1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int64_t(msg, 8); +} + +/** + * @brief Decode a timesync message into a struct + * + * @param msg The message to decode + * @param timesync C-struct to decode the message contents into + */ +static inline void mavlink_msg_timesync_decode(const mavlink_message_t* msg, mavlink_timesync_t* timesync) +{ +#if MAVLINK_NEED_BYTE_SWAP + timesync->tc1 = mavlink_msg_timesync_get_tc1(msg); + timesync->ts1 = mavlink_msg_timesync_get_ts1(msg); +#else + memcpy(timesync, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TIMESYNC_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_v2_extension.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_v2_extension.h new file mode 100644 index 0000000..26f18ad --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_v2_extension.h @@ -0,0 +1,297 @@ +// MESSAGE V2_EXTENSION PACKING + +#define MAVLINK_MSG_ID_V2_EXTENSION 248 + +typedef struct __mavlink_v2_extension_t +{ + uint16_t message_type; /*< A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.*/ + uint8_t target_network; /*< Network ID (0 for broadcast)*/ + uint8_t target_system; /*< System ID (0 for broadcast)*/ + uint8_t target_component; /*< Component ID (0 for broadcast)*/ + uint8_t payload[249]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.*/ +} mavlink_v2_extension_t; + +#define MAVLINK_MSG_ID_V2_EXTENSION_LEN 254 +#define MAVLINK_MSG_ID_248_LEN 254 + +#define MAVLINK_MSG_ID_V2_EXTENSION_CRC 8 +#define MAVLINK_MSG_ID_248_CRC 8 + +#define MAVLINK_MSG_V2_EXTENSION_FIELD_PAYLOAD_LEN 249 + +#define MAVLINK_MESSAGE_INFO_V2_EXTENSION { \ + "V2_EXTENSION", \ + 5, \ + { { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \ + { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_v2_extension_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_v2_extension_t, target_component) }, \ + { "payload", NULL, MAVLINK_TYPE_UINT8_T, 249, 5, offsetof(mavlink_v2_extension_t, payload) }, \ + } \ +} + + +/** + * @brief Pack a v2_extension message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_v2_extension_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN]; + _mav_put_uint16_t(buf, 0, message_type); + _mav_put_uint8_t(buf, 2, target_network); + _mav_put_uint8_t(buf, 3, target_system); + _mav_put_uint8_t(buf, 4, target_component); + _mav_put_uint8_t_array(buf, 5, payload, 249); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#else + mavlink_v2_extension_t packet; + packet.message_type = message_type; + packet.target_network = target_network; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif +} + +/** + * @brief Pack a v2_extension message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_v2_extension_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_network,uint8_t target_system,uint8_t target_component,uint16_t message_type,const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN]; + _mav_put_uint16_t(buf, 0, message_type); + _mav_put_uint8_t(buf, 2, target_network); + _mav_put_uint8_t(buf, 3, target_system); + _mav_put_uint8_t(buf, 4, target_component); + _mav_put_uint8_t_array(buf, 5, payload, 249); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#else + mavlink_v2_extension_t packet; + packet.message_type = message_type; + packet.target_network = target_network; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif +} + +/** + * @brief Encode a v2_extension struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param v2_extension C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_v2_extension_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension) +{ + return mavlink_msg_v2_extension_pack(system_id, component_id, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload); +} + +/** + * @brief Encode a v2_extension struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param v2_extension C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_v2_extension_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension) +{ + return mavlink_msg_v2_extension_pack_chan(system_id, component_id, chan, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload); +} + +/** + * @brief Send a v2_extension message + * @param chan MAVLink channel to send the message + * + * @param target_network Network ID (0 for broadcast) + * @param target_system System ID (0 for broadcast) + * @param target_component Component ID (0 for broadcast) + * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_v2_extension_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN]; + _mav_put_uint16_t(buf, 0, message_type); + _mav_put_uint8_t(buf, 2, target_network); + _mav_put_uint8_t(buf, 3, target_system); + _mav_put_uint8_t(buf, 4, target_component); + _mav_put_uint8_t_array(buf, 5, payload, 249); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif +#else + mavlink_v2_extension_t packet; + packet.message_type = message_type; + packet.target_network = target_network; + packet.target_system = target_system; + packet.target_component = target_component; + mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)&packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)&packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_V2_EXTENSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_v2_extension_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint16_t(buf, 0, message_type); + _mav_put_uint8_t(buf, 2, target_network); + _mav_put_uint8_t(buf, 3, target_system); + _mav_put_uint8_t(buf, 4, target_component); + _mav_put_uint8_t_array(buf, 5, payload, 249); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif +#else + mavlink_v2_extension_t *packet = (mavlink_v2_extension_t *)msgbuf; + packet->message_type = message_type; + packet->target_network = target_network; + packet->target_system = target_system; + packet->target_component = target_component; + mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*249); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE V2_EXTENSION UNPACKING + + +/** + * @brief Get field target_network from v2_extension message + * + * @return Network ID (0 for broadcast) + */ +static inline uint8_t mavlink_msg_v2_extension_get_target_network(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_system from v2_extension message + * + * @return System ID (0 for broadcast) + */ +static inline uint8_t mavlink_msg_v2_extension_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field target_component from v2_extension message + * + * @return Component ID (0 for broadcast) + */ +static inline uint8_t mavlink_msg_v2_extension_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field message_type from v2_extension message + * + * @return A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + */ +static inline uint16_t mavlink_msg_v2_extension_get_message_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field payload from v2_extension message + * + * @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + */ +static inline uint16_t mavlink_msg_v2_extension_get_payload(const mavlink_message_t* msg, uint8_t *payload) +{ + return _MAV_RETURN_uint8_t_array(msg, payload, 249, 5); +} + +/** + * @brief Decode a v2_extension message into a struct + * + * @param msg The message to decode + * @param v2_extension C-struct to decode the message contents into + */ +static inline void mavlink_msg_v2_extension_decode(const mavlink_message_t* msg, mavlink_v2_extension_t* v2_extension) +{ +#if MAVLINK_NEED_BYTE_SWAP + v2_extension->message_type = mavlink_msg_v2_extension_get_message_type(msg); + v2_extension->target_network = mavlink_msg_v2_extension_get_target_network(msg); + v2_extension->target_system = mavlink_msg_v2_extension_get_target_system(msg); + v2_extension->target_component = mavlink_msg_v2_extension_get_target_component(msg); + mavlink_msg_v2_extension_get_payload(msg, v2_extension->payload); +#else + memcpy(v2_extension, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_V2_EXTENSION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_vfr_hud.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_vfr_hud.h new file mode 100644 index 0000000..0dc5b82 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_vfr_hud.h @@ -0,0 +1,329 @@ +// MESSAGE VFR_HUD PACKING + +#define MAVLINK_MSG_ID_VFR_HUD 74 + +typedef struct __mavlink_vfr_hud_t +{ + float airspeed; /*< Current airspeed in m/s*/ + float groundspeed; /*< Current ground speed in m/s*/ + float alt; /*< Current altitude (MSL), in meters*/ + float climb; /*< Current climb rate in meters/second*/ + int16_t heading; /*< Current heading in degrees, in compass units (0..360, 0=north)*/ + uint16_t throttle; /*< Current throttle setting in integer percent, 0 to 100*/ +} mavlink_vfr_hud_t; + +#define MAVLINK_MSG_ID_VFR_HUD_LEN 20 +#define MAVLINK_MSG_ID_74_LEN 20 + +#define MAVLINK_MSG_ID_VFR_HUD_CRC 20 +#define MAVLINK_MSG_ID_74_CRC 20 + + + +#define MAVLINK_MESSAGE_INFO_VFR_HUD { \ + "VFR_HUD", \ + 6, \ + { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \ + { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \ + { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \ + { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \ + { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \ + } \ +} + + +/** + * @brief Pack a vfr_hud message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param airspeed Current airspeed in m/s + * @param groundspeed Current ground speed in m/s + * @param heading Current heading in degrees, in compass units (0..360, 0=north) + * @param throttle Current throttle setting in integer percent, 0 to 100 + * @param alt Current altitude (MSL), in meters + * @param climb Current climb rate in meters/second + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VFR_HUD_LEN]; + _mav_put_float(buf, 0, airspeed); + _mav_put_float(buf, 4, groundspeed); + _mav_put_float(buf, 8, alt); + _mav_put_float(buf, 12, climb); + _mav_put_int16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, throttle); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN); +#else + mavlink_vfr_hud_t packet; + packet.airspeed = airspeed; + packet.groundspeed = groundspeed; + packet.alt = alt; + packet.climb = climb; + packet.heading = heading; + packet.throttle = throttle; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VFR_HUD; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif +} + +/** + * @brief Pack a vfr_hud message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param airspeed Current airspeed in m/s + * @param groundspeed Current ground speed in m/s + * @param heading Current heading in degrees, in compass units (0..360, 0=north) + * @param throttle Current throttle setting in integer percent, 0 to 100 + * @param alt Current altitude (MSL), in meters + * @param climb Current climb rate in meters/second + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float airspeed,float groundspeed,int16_t heading,uint16_t throttle,float alt,float climb) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VFR_HUD_LEN]; + _mav_put_float(buf, 0, airspeed); + _mav_put_float(buf, 4, groundspeed); + _mav_put_float(buf, 8, alt); + _mav_put_float(buf, 12, climb); + _mav_put_int16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, throttle); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN); +#else + mavlink_vfr_hud_t packet; + packet.airspeed = airspeed; + packet.groundspeed = groundspeed; + packet.alt = alt; + packet.climb = climb; + packet.heading = heading; + packet.throttle = throttle; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VFR_HUD; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif +} + +/** + * @brief Encode a vfr_hud struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vfr_hud C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud) +{ + return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); +} + +/** + * @brief Encode a vfr_hud struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param vfr_hud C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vfr_hud_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud) +{ + return mavlink_msg_vfr_hud_pack_chan(system_id, component_id, chan, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); +} + +/** + * @brief Send a vfr_hud message + * @param chan MAVLink channel to send the message + * + * @param airspeed Current airspeed in m/s + * @param groundspeed Current ground speed in m/s + * @param heading Current heading in degrees, in compass units (0..360, 0=north) + * @param throttle Current throttle setting in integer percent, 0 to 100 + * @param alt Current altitude (MSL), in meters + * @param climb Current climb rate in meters/second + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VFR_HUD_LEN]; + _mav_put_float(buf, 0, airspeed); + _mav_put_float(buf, 4, groundspeed); + _mav_put_float(buf, 8, alt); + _mav_put_float(buf, 12, climb); + _mav_put_int16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, throttle); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif +#else + mavlink_vfr_hud_t packet; + packet.airspeed = airspeed; + packet.groundspeed = groundspeed; + packet.alt = alt; + packet.climb = climb; + packet.heading = heading; + packet.throttle = throttle; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_VFR_HUD_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_vfr_hud_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, airspeed); + _mav_put_float(buf, 4, groundspeed); + _mav_put_float(buf, 8, alt); + _mav_put_float(buf, 12, climb); + _mav_put_int16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, throttle); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif +#else + mavlink_vfr_hud_t *packet = (mavlink_vfr_hud_t *)msgbuf; + packet->airspeed = airspeed; + packet->groundspeed = groundspeed; + packet->alt = alt; + packet->climb = climb; + packet->heading = heading; + packet->throttle = throttle; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)packet, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)packet, MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE VFR_HUD UNPACKING + + +/** + * @brief Get field airspeed from vfr_hud message + * + * @return Current airspeed in m/s + */ +static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field groundspeed from vfr_hud message + * + * @return Current ground speed in m/s + */ +static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field heading from vfr_hud message + * + * @return Current heading in degrees, in compass units (0..360, 0=north) + */ +static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field throttle from vfr_hud message + * + * @return Current throttle setting in integer percent, 0 to 100 + */ +static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field alt from vfr_hud message + * + * @return Current altitude (MSL), in meters + */ +static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field climb from vfr_hud message + * + * @return Current climb rate in meters/second + */ +static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a vfr_hud message into a struct + * + * @param msg The message to decode + * @param vfr_hud C-struct to decode the message contents into + */ +static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavlink_vfr_hud_t* vfr_hud) +{ +#if MAVLINK_NEED_BYTE_SWAP + vfr_hud->airspeed = mavlink_msg_vfr_hud_get_airspeed(msg); + vfr_hud->groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg); + vfr_hud->alt = mavlink_msg_vfr_hud_get_alt(msg); + vfr_hud->climb = mavlink_msg_vfr_hud_get_climb(msg); + vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg); + vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg); +#else + memcpy(vfr_hud, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VFR_HUD_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_vibration.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_vibration.h new file mode 100644 index 0000000..7b2d10c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_vibration.h @@ -0,0 +1,353 @@ +// MESSAGE VIBRATION PACKING + +#define MAVLINK_MSG_ID_VIBRATION 241 + +typedef struct __mavlink_vibration_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float vibration_x; /*< Vibration levels on X-axis*/ + float vibration_y; /*< Vibration levels on Y-axis*/ + float vibration_z; /*< Vibration levels on Z-axis*/ + uint32_t clipping_0; /*< first accelerometer clipping count*/ + uint32_t clipping_1; /*< second accelerometer clipping count*/ + uint32_t clipping_2; /*< third accelerometer clipping count*/ +} mavlink_vibration_t; + +#define MAVLINK_MSG_ID_VIBRATION_LEN 32 +#define MAVLINK_MSG_ID_241_LEN 32 + +#define MAVLINK_MSG_ID_VIBRATION_CRC 90 +#define MAVLINK_MSG_ID_241_CRC 90 + + + +#define MAVLINK_MESSAGE_INFO_VIBRATION { \ + "VIBRATION", \ + 7, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vibration_t, time_usec) }, \ + { "vibration_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vibration_t, vibration_x) }, \ + { "vibration_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vibration_t, vibration_y) }, \ + { "vibration_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vibration_t, vibration_z) }, \ + { "clipping_0", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_vibration_t, clipping_0) }, \ + { "clipping_1", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_vibration_t, clipping_1) }, \ + { "clipping_2", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_vibration_t, clipping_2) }, \ + } \ +} + + +/** + * @brief Pack a vibration message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param vibration_x Vibration levels on X-axis + * @param vibration_y Vibration levels on Y-axis + * @param vibration_z Vibration levels on Z-axis + * @param clipping_0 first accelerometer clipping count + * @param clipping_1 second accelerometer clipping count + * @param clipping_2 third accelerometer clipping count + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VIBRATION_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vibration_x); + _mav_put_float(buf, 12, vibration_y); + _mav_put_float(buf, 16, vibration_z); + _mav_put_uint32_t(buf, 20, clipping_0); + _mav_put_uint32_t(buf, 24, clipping_1); + _mav_put_uint32_t(buf, 28, clipping_2); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIBRATION_LEN); +#else + mavlink_vibration_t packet; + packet.time_usec = time_usec; + packet.vibration_x = vibration_x; + packet.vibration_y = vibration_y; + packet.vibration_z = vibration_z; + packet.clipping_0 = clipping_0; + packet.clipping_1 = clipping_1; + packet.clipping_2 = clipping_2; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VIBRATION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif +} + +/** + * @brief Pack a vibration message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param vibration_x Vibration levels on X-axis + * @param vibration_y Vibration levels on Y-axis + * @param vibration_z Vibration levels on Z-axis + * @param clipping_0 first accelerometer clipping count + * @param clipping_1 second accelerometer clipping count + * @param clipping_2 third accelerometer clipping count + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float vibration_x,float vibration_y,float vibration_z,uint32_t clipping_0,uint32_t clipping_1,uint32_t clipping_2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VIBRATION_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vibration_x); + _mav_put_float(buf, 12, vibration_y); + _mav_put_float(buf, 16, vibration_z); + _mav_put_uint32_t(buf, 20, clipping_0); + _mav_put_uint32_t(buf, 24, clipping_1); + _mav_put_uint32_t(buf, 28, clipping_2); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIBRATION_LEN); +#else + mavlink_vibration_t packet; + packet.time_usec = time_usec; + packet.vibration_x = vibration_x; + packet.vibration_y = vibration_y; + packet.vibration_z = vibration_z; + packet.clipping_0 = clipping_0; + packet.clipping_1 = clipping_1; + packet.clipping_2 = clipping_2; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VIBRATION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif +} + +/** + * @brief Encode a vibration struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vibration C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vibration_t* vibration) +{ + return mavlink_msg_vibration_pack(system_id, component_id, msg, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2); +} + +/** + * @brief Encode a vibration struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param vibration C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vibration_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vibration_t* vibration) +{ + return mavlink_msg_vibration_pack_chan(system_id, component_id, chan, msg, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2); +} + +/** + * @brief Send a vibration message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param vibration_x Vibration levels on X-axis + * @param vibration_y Vibration levels on Y-axis + * @param vibration_z Vibration levels on Z-axis + * @param clipping_0 first accelerometer clipping count + * @param clipping_1 second accelerometer clipping count + * @param clipping_2 third accelerometer clipping count + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vibration_send(mavlink_channel_t chan, uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VIBRATION_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vibration_x); + _mav_put_float(buf, 12, vibration_y); + _mav_put_float(buf, 16, vibration_z); + _mav_put_uint32_t(buf, 20, clipping_0); + _mav_put_uint32_t(buf, 24, clipping_1); + _mav_put_uint32_t(buf, 28, clipping_2); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif +#else + mavlink_vibration_t packet; + packet.time_usec = time_usec; + packet.vibration_x = vibration_x; + packet.vibration_y = vibration_y; + packet.vibration_z = vibration_z; + packet.clipping_0 = clipping_0; + packet.clipping_1 = clipping_1; + packet.clipping_2 = clipping_2; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)&packet, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)&packet, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_VIBRATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_vibration_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, vibration_x); + _mav_put_float(buf, 12, vibration_y); + _mav_put_float(buf, 16, vibration_z); + _mav_put_uint32_t(buf, 20, clipping_0); + _mav_put_uint32_t(buf, 24, clipping_1); + _mav_put_uint32_t(buf, 28, clipping_2); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif +#else + mavlink_vibration_t *packet = (mavlink_vibration_t *)msgbuf; + packet->time_usec = time_usec; + packet->vibration_x = vibration_x; + packet->vibration_y = vibration_y; + packet->vibration_z = vibration_z; + packet->clipping_0 = clipping_0; + packet->clipping_1 = clipping_1; + packet->clipping_2 = clipping_2; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)packet, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)packet, MAVLINK_MSG_ID_VIBRATION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE VIBRATION UNPACKING + + +/** + * @brief Get field time_usec from vibration message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_vibration_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field vibration_x from vibration message + * + * @return Vibration levels on X-axis + */ +static inline float mavlink_msg_vibration_get_vibration_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field vibration_y from vibration message + * + * @return Vibration levels on Y-axis + */ +static inline float mavlink_msg_vibration_get_vibration_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vibration_z from vibration message + * + * @return Vibration levels on Z-axis + */ +static inline float mavlink_msg_vibration_get_vibration_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field clipping_0 from vibration message + * + * @return first accelerometer clipping count + */ +static inline uint32_t mavlink_msg_vibration_get_clipping_0(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 20); +} + +/** + * @brief Get field clipping_1 from vibration message + * + * @return second accelerometer clipping count + */ +static inline uint32_t mavlink_msg_vibration_get_clipping_1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 24); +} + +/** + * @brief Get field clipping_2 from vibration message + * + * @return third accelerometer clipping count + */ +static inline uint32_t mavlink_msg_vibration_get_clipping_2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 28); +} + +/** + * @brief Decode a vibration message into a struct + * + * @param msg The message to decode + * @param vibration C-struct to decode the message contents into + */ +static inline void mavlink_msg_vibration_decode(const mavlink_message_t* msg, mavlink_vibration_t* vibration) +{ +#if MAVLINK_NEED_BYTE_SWAP + vibration->time_usec = mavlink_msg_vibration_get_time_usec(msg); + vibration->vibration_x = mavlink_msg_vibration_get_vibration_x(msg); + vibration->vibration_y = mavlink_msg_vibration_get_vibration_y(msg); + vibration->vibration_z = mavlink_msg_vibration_get_vibration_z(msg); + vibration->clipping_0 = mavlink_msg_vibration_get_clipping_0(msg); + vibration->clipping_1 = mavlink_msg_vibration_get_clipping_1(msg); + vibration->clipping_2 = mavlink_msg_vibration_get_clipping_2(msg); +#else + memcpy(vibration, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VIBRATION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h new file mode 100644 index 0000000..9fb41e7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h @@ -0,0 +1,353 @@ +// MESSAGE VICON_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 104 + +typedef struct __mavlink_vicon_position_estimate_t +{ + uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + float x; /*< Global X position*/ + float y; /*< Global Y position*/ + float z; /*< Global Z position*/ + float roll; /*< Roll angle in rad*/ + float pitch; /*< Pitch angle in rad*/ + float yaw; /*< Yaw angle in rad*/ +} mavlink_vicon_position_estimate_t; + +#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32 +#define MAVLINK_MSG_ID_104_LEN 32 + +#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC 56 +#define MAVLINK_MSG_ID_104_CRC 56 + + + +#define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \ + "VICON_POSITION_ESTIMATE", \ + 7, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vicon_position_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vicon_position_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vicon_position_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vicon_position_estimate_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vicon_position_estimate_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vicon_position_estimate_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vicon_position_estimate_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a vicon_position_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#else + mavlink_vicon_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif +} + +/** + * @brief Pack a vicon_position_estimate message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#else + mavlink_vicon_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif +} + +/** + * @brief Encode a vicon_position_estimate struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vicon_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) +{ + return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); +} + +/** + * @brief Encode a vicon_position_estimate struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param vicon_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) +{ + return mavlink_msg_vicon_position_estimate_pack_chan(system_id, component_id, chan, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); +} + +/** + * @brief Send a vicon_position_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif +#else + mavlink_vicon_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_vicon_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif +#else + mavlink_vicon_position_estimate_t *packet = (mavlink_vicon_position_estimate_t *)msgbuf; + packet->usec = usec; + packet->x = x; + packet->y = y; + packet->z = z; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE VICON_POSITION_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from vicon_position_estimate message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from vicon_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_vicon_position_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from vicon_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_vicon_position_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from vicon_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_vicon_position_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field roll from vicon_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitch from vicon_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yaw from vicon_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a vicon_position_estimate message into a struct + * + * @param msg The message to decode + * @param vicon_position_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_message_t* msg, mavlink_vicon_position_estimate_t* vicon_position_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + vicon_position_estimate->usec = mavlink_msg_vicon_position_estimate_get_usec(msg); + vicon_position_estimate->x = mavlink_msg_vicon_position_estimate_get_x(msg); + vicon_position_estimate->y = mavlink_msg_vicon_position_estimate_get_y(msg); + vicon_position_estimate->z = mavlink_msg_vicon_position_estimate_get_z(msg); + vicon_position_estimate->roll = mavlink_msg_vicon_position_estimate_get_roll(msg); + vicon_position_estimate->pitch = mavlink_msg_vicon_position_estimate_get_pitch(msg); + vicon_position_estimate->yaw = mavlink_msg_vicon_position_estimate_get_yaw(msg); +#else + memcpy(vicon_position_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h new file mode 100644 index 0000000..f3d8e5d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h @@ -0,0 +1,353 @@ +// MESSAGE VISION_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 102 + +typedef struct __mavlink_vision_position_estimate_t +{ + uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + float x; /*< Global X position*/ + float y; /*< Global Y position*/ + float z; /*< Global Z position*/ + float roll; /*< Roll angle in rad*/ + float pitch; /*< Pitch angle in rad*/ + float yaw; /*< Yaw angle in rad*/ +} mavlink_vision_position_estimate_t; + +#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32 +#define MAVLINK_MSG_ID_102_LEN 32 + +#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC 158 +#define MAVLINK_MSG_ID_102_CRC 158 + + + +#define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \ + "VISION_POSITION_ESTIMATE", \ + 7, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_position_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_position_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_position_estimate_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a vision_position_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#else + mavlink_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif +} + +/** + * @brief Pack a vision_position_estimate message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#else + mavlink_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif +} + +/** + * @brief Encode a vision_position_estimate struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vision_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) +{ + return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); +} + +/** + * @brief Encode a vision_position_estimate struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param vision_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vision_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) +{ + return mavlink_msg_vision_position_estimate_pack_chan(system_id, component_id, chan, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); +} + +/** + * @brief Send a vision_position_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif +#else + mavlink_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif +#else + mavlink_vision_position_estimate_t *packet = (mavlink_vision_position_estimate_t *)msgbuf; + packet->usec = usec; + packet->x = x; + packet->y = y; + packet->z = z; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE VISION_POSITION_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from vision_position_estimate message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from vision_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from vision_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from vision_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field roll from vision_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitch from vision_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yaw from vision_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a vision_position_estimate message into a struct + * + * @param msg The message to decode + * @param vision_position_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg); + vision_position_estimate->x = mavlink_msg_vision_position_estimate_get_x(msg); + vision_position_estimate->y = mavlink_msg_vision_position_estimate_get_y(msg); + vision_position_estimate->z = mavlink_msg_vision_position_estimate_get_z(msg); + vision_position_estimate->roll = mavlink_msg_vision_position_estimate_get_roll(msg); + vision_position_estimate->pitch = mavlink_msg_vision_position_estimate_get_pitch(msg); + vision_position_estimate->yaw = mavlink_msg_vision_position_estimate_get_yaw(msg); +#else + memcpy(vision_position_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h new file mode 100644 index 0000000..0154ea4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h @@ -0,0 +1,281 @@ +// MESSAGE VISION_SPEED_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103 + +typedef struct __mavlink_vision_speed_estimate_t +{ + uint64_t usec; /*< Timestamp (microseconds, synced to UNIX time or since system boot)*/ + float x; /*< Global X speed*/ + float y; /*< Global Y speed*/ + float z; /*< Global Z speed*/ +} mavlink_vision_speed_estimate_t; + +#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20 +#define MAVLINK_MSG_ID_103_LEN 20 + +#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC 208 +#define MAVLINK_MSG_ID_103_CRC 208 + + + +#define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \ + "VISION_SPEED_ESTIMATE", \ + 4, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \ + } \ +} + + +/** + * @brief Pack a vision_speed_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X speed + * @param y Global Y speed + * @param z Global Z speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#else + mavlink_vision_speed_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif +} + +/** + * @brief Pack a vision_speed_estimate message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X speed + * @param y Global Y speed + * @param z Global Z speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#else + mavlink_vision_speed_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif +} + +/** + * @brief Encode a vision_speed_estimate struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vision_speed_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) +{ + return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); +} + +/** + * @brief Encode a vision_speed_estimate struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param vision_speed_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vision_speed_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) +{ + return mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, chan, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); +} + +/** + * @brief Send a vision_speed_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) + * @param x Global X speed + * @param y Global Y speed + * @param z Global Z speed + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif +#else + mavlink_vision_speed_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_vision_speed_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif +#else + mavlink_vision_speed_estimate_t *packet = (mavlink_vision_speed_estimate_t *)msgbuf; + packet->usec = usec; + packet->x = x; + packet->y = y; + packet->z = z; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE VISION_SPEED_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from vision_speed_estimate message + * + * @return Timestamp (microseconds, synced to UNIX time or since system boot) + */ +static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from vision_speed_estimate message + * + * @return Global X speed + */ +static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from vision_speed_estimate message + * + * @return Global Y speed + */ +static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from vision_speed_estimate message + * + * @return Global Z speed + */ +static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a vision_speed_estimate message into a struct + * + * @param msg The message to decode + * @param vision_speed_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg); + vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg); + vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg); + vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg); +#else + memcpy(vision_speed_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_wind_cov.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_wind_cov.h new file mode 100644 index 0000000..9a6b1aa --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/mavlink_msg_wind_cov.h @@ -0,0 +1,401 @@ +// MESSAGE WIND_COV PACKING + +#define MAVLINK_MSG_ID_WIND_COV 231 + +typedef struct __mavlink_wind_cov_t +{ + uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ + float wind_x; /*< Wind in X (NED) direction in m/s*/ + float wind_y; /*< Wind in Y (NED) direction in m/s*/ + float wind_z; /*< Wind in Z (NED) direction in m/s*/ + float var_horiz; /*< Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate.*/ + float var_vert; /*< Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate.*/ + float wind_alt; /*< AMSL altitude (m) this measurement was taken at*/ + float horiz_accuracy; /*< Horizontal speed 1-STD accuracy*/ + float vert_accuracy; /*< Vertical speed 1-STD accuracy*/ +} mavlink_wind_cov_t; + +#define MAVLINK_MSG_ID_WIND_COV_LEN 40 +#define MAVLINK_MSG_ID_231_LEN 40 + +#define MAVLINK_MSG_ID_WIND_COV_CRC 105 +#define MAVLINK_MSG_ID_231_CRC 105 + + + +#define MAVLINK_MESSAGE_INFO_WIND_COV { \ + "WIND_COV", \ + 9, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_wind_cov_t, time_usec) }, \ + { "wind_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_cov_t, wind_x) }, \ + { "wind_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_wind_cov_t, wind_y) }, \ + { "wind_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_wind_cov_t, wind_z) }, \ + { "var_horiz", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_wind_cov_t, var_horiz) }, \ + { "var_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_wind_cov_t, var_vert) }, \ + { "wind_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_wind_cov_t, wind_alt) }, \ + { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_wind_cov_t, horiz_accuracy) }, \ + { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_wind_cov_t, vert_accuracy) }, \ + } \ +} + + +/** + * @brief Pack a wind_cov message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param wind_x Wind in X (NED) direction in m/s + * @param wind_y Wind in Y (NED) direction in m/s + * @param wind_z Wind in Z (NED) direction in m/s + * @param var_horiz Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. + * @param var_vert Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. + * @param wind_alt AMSL altitude (m) this measurement was taken at + * @param horiz_accuracy Horizontal speed 1-STD accuracy + * @param vert_accuracy Vertical speed 1-STD accuracy + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_wind_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_WIND_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, wind_x); + _mav_put_float(buf, 12, wind_y); + _mav_put_float(buf, 16, wind_z); + _mav_put_float(buf, 20, var_horiz); + _mav_put_float(buf, 24, var_vert); + _mav_put_float(buf, 28, wind_alt); + _mav_put_float(buf, 32, horiz_accuracy); + _mav_put_float(buf, 36, vert_accuracy); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_COV_LEN); +#else + mavlink_wind_cov_t packet; + packet.time_usec = time_usec; + packet.wind_x = wind_x; + packet.wind_y = wind_y; + packet.wind_z = wind_z; + packet.var_horiz = var_horiz; + packet.var_vert = var_vert; + packet.wind_alt = wind_alt; + packet.horiz_accuracy = horiz_accuracy; + packet.vert_accuracy = vert_accuracy; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_WIND_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif +} + +/** + * @brief Pack a wind_cov message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param wind_x Wind in X (NED) direction in m/s + * @param wind_y Wind in Y (NED) direction in m/s + * @param wind_z Wind in Z (NED) direction in m/s + * @param var_horiz Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. + * @param var_vert Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. + * @param wind_alt AMSL altitude (m) this measurement was taken at + * @param horiz_accuracy Horizontal speed 1-STD accuracy + * @param vert_accuracy Vertical speed 1-STD accuracy + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_wind_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float wind_x,float wind_y,float wind_z,float var_horiz,float var_vert,float wind_alt,float horiz_accuracy,float vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_WIND_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, wind_x); + _mav_put_float(buf, 12, wind_y); + _mav_put_float(buf, 16, wind_z); + _mav_put_float(buf, 20, var_horiz); + _mav_put_float(buf, 24, var_vert); + _mav_put_float(buf, 28, wind_alt); + _mav_put_float(buf, 32, horiz_accuracy); + _mav_put_float(buf, 36, vert_accuracy); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_COV_LEN); +#else + mavlink_wind_cov_t packet; + packet.time_usec = time_usec; + packet.wind_x = wind_x; + packet.wind_y = wind_y; + packet.wind_z = wind_z; + packet.var_horiz = var_horiz; + packet.var_vert = var_vert; + packet.wind_alt = wind_alt; + packet.horiz_accuracy = horiz_accuracy; + packet.vert_accuracy = vert_accuracy; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_WIND_COV; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif +} + +/** + * @brief Encode a wind_cov struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param wind_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_wind_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wind_cov_t* wind_cov) +{ + return mavlink_msg_wind_cov_pack(system_id, component_id, msg, wind_cov->time_usec, wind_cov->wind_x, wind_cov->wind_y, wind_cov->wind_z, wind_cov->var_horiz, wind_cov->var_vert, wind_cov->wind_alt, wind_cov->horiz_accuracy, wind_cov->vert_accuracy); +} + +/** + * @brief Encode a wind_cov struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param wind_cov C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_wind_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wind_cov_t* wind_cov) +{ + return mavlink_msg_wind_cov_pack_chan(system_id, component_id, chan, msg, wind_cov->time_usec, wind_cov->wind_x, wind_cov->wind_y, wind_cov->wind_z, wind_cov->var_horiz, wind_cov->var_vert, wind_cov->wind_alt, wind_cov->horiz_accuracy, wind_cov->vert_accuracy); +} + +/** + * @brief Send a wind_cov message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (micros since boot or Unix epoch) + * @param wind_x Wind in X (NED) direction in m/s + * @param wind_y Wind in Y (NED) direction in m/s + * @param wind_z Wind in Z (NED) direction in m/s + * @param var_horiz Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. + * @param var_vert Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. + * @param wind_alt AMSL altitude (m) this measurement was taken at + * @param horiz_accuracy Horizontal speed 1-STD accuracy + * @param vert_accuracy Vertical speed 1-STD accuracy + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_wind_cov_send(mavlink_channel_t chan, uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_WIND_COV_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, wind_x); + _mav_put_float(buf, 12, wind_y); + _mav_put_float(buf, 16, wind_z); + _mav_put_float(buf, 20, var_horiz); + _mav_put_float(buf, 24, var_vert); + _mav_put_float(buf, 28, wind_alt); + _mav_put_float(buf, 32, horiz_accuracy); + _mav_put_float(buf, 36, vert_accuracy); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, buf, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, buf, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif +#else + mavlink_wind_cov_t packet; + packet.time_usec = time_usec; + packet.wind_x = wind_x; + packet.wind_y = wind_y; + packet.wind_z = wind_z; + packet.var_horiz = var_horiz; + packet.var_vert = var_vert; + packet.wind_alt = wind_alt; + packet.horiz_accuracy = horiz_accuracy; + packet.vert_accuracy = vert_accuracy; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)&packet, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)&packet, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_WIND_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_wind_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, wind_x); + _mav_put_float(buf, 12, wind_y); + _mav_put_float(buf, 16, wind_z); + _mav_put_float(buf, 20, var_horiz); + _mav_put_float(buf, 24, var_vert); + _mav_put_float(buf, 28, wind_alt); + _mav_put_float(buf, 32, horiz_accuracy); + _mav_put_float(buf, 36, vert_accuracy); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, buf, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, buf, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif +#else + mavlink_wind_cov_t *packet = (mavlink_wind_cov_t *)msgbuf; + packet->time_usec = time_usec; + packet->wind_x = wind_x; + packet->wind_y = wind_y; + packet->wind_z = wind_z; + packet->var_horiz = var_horiz; + packet->var_vert = var_vert; + packet->wind_alt = wind_alt; + packet->horiz_accuracy = horiz_accuracy; + packet->vert_accuracy = vert_accuracy; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)packet, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)packet, MAVLINK_MSG_ID_WIND_COV_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE WIND_COV UNPACKING + + +/** + * @brief Get field time_usec from wind_cov message + * + * @return Timestamp (micros since boot or Unix epoch) + */ +static inline uint64_t mavlink_msg_wind_cov_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field wind_x from wind_cov message + * + * @return Wind in X (NED) direction in m/s + */ +static inline float mavlink_msg_wind_cov_get_wind_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field wind_y from wind_cov message + * + * @return Wind in Y (NED) direction in m/s + */ +static inline float mavlink_msg_wind_cov_get_wind_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field wind_z from wind_cov message + * + * @return Wind in Z (NED) direction in m/s + */ +static inline float mavlink_msg_wind_cov_get_wind_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field var_horiz from wind_cov message + * + * @return Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. + */ +static inline float mavlink_msg_wind_cov_get_var_horiz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field var_vert from wind_cov message + * + * @return Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. + */ +static inline float mavlink_msg_wind_cov_get_var_vert(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field wind_alt from wind_cov message + * + * @return AMSL altitude (m) this measurement was taken at + */ +static inline float mavlink_msg_wind_cov_get_wind_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field horiz_accuracy from wind_cov message + * + * @return Horizontal speed 1-STD accuracy + */ +static inline float mavlink_msg_wind_cov_get_horiz_accuracy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field vert_accuracy from wind_cov message + * + * @return Vertical speed 1-STD accuracy + */ +static inline float mavlink_msg_wind_cov_get_vert_accuracy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Decode a wind_cov message into a struct + * + * @param msg The message to decode + * @param wind_cov C-struct to decode the message contents into + */ +static inline void mavlink_msg_wind_cov_decode(const mavlink_message_t* msg, mavlink_wind_cov_t* wind_cov) +{ +#if MAVLINK_NEED_BYTE_SWAP + wind_cov->time_usec = mavlink_msg_wind_cov_get_time_usec(msg); + wind_cov->wind_x = mavlink_msg_wind_cov_get_wind_x(msg); + wind_cov->wind_y = mavlink_msg_wind_cov_get_wind_y(msg); + wind_cov->wind_z = mavlink_msg_wind_cov_get_wind_z(msg); + wind_cov->var_horiz = mavlink_msg_wind_cov_get_var_horiz(msg); + wind_cov->var_vert = mavlink_msg_wind_cov_get_var_vert(msg); + wind_cov->wind_alt = mavlink_msg_wind_cov_get_wind_alt(msg); + wind_cov->horiz_accuracy = mavlink_msg_wind_cov_get_horiz_accuracy(msg); + wind_cov->vert_accuracy = mavlink_msg_wind_cov_get_vert_accuracy(msg); +#else + memcpy(wind_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_WIND_COV_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/testsuite.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/testsuite.h new file mode 100644 index 0000000..ae50f9a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/common/testsuite.h @@ -0,0 +1,6620 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from common.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef COMMON_TESTSUITE_H +#define COMMON_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL + +static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + + mavlink_test_common(system_id, component_id, last_msg); +} +#endif + + + + +static void mavlink_test_heartbeat(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_heartbeat_t packet_in = { + 963497464,17,84,151,218,3 + }; + mavlink_heartbeat_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.custom_mode = packet_in.custom_mode; + packet1.type = packet_in.type; + packet1.autopilot = packet_in.autopilot; + packet1.base_mode = packet_in.base_mode; + packet1.system_status = packet_in.system_status; + packet1.mavlink_version = packet_in.mavlink_version; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_heartbeat_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_heartbeat_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_heartbeat_pack(system_id, component_id, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); + mavlink_msg_heartbeat_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); + mavlink_msg_heartbeat_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; i + +#ifndef M_PI_2 + #define M_PI_2 ((float)asin(1)) +#endif + +/** + * @file mavlink_conversions.h + * + * These conversion functions follow the NASA rotation standards definition file + * available online. + * + * Their intent is to lower the barrier for MAVLink adopters to use gimbal-lock free + * (both rotation matrices, sometimes called DCM, and quaternions are gimbal-lock free) + * rotation representations. Euler angles (roll, pitch, yaw) will be phased out of the + * protocol as widely as possible. + * + * @author James Goppert + * @author Thomas Gubler + */ + + +/** + * Converts a quaternion to a rotation matrix + * + * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) + * @param dcm a 3x3 rotation matrix + */ +MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3]) +{ + double a = quaternion[0]; + double b = quaternion[1]; + double c = quaternion[2]; + double d = quaternion[3]; + double aSq = a * a; + double bSq = b * b; + double cSq = c * c; + double dSq = d * d; + dcm[0][0] = aSq + bSq - cSq - dSq; + dcm[0][1] = 2 * (b * c - a * d); + dcm[0][2] = 2 * (a * c + b * d); + dcm[1][0] = 2 * (b * c + a * d); + dcm[1][1] = aSq - bSq + cSq - dSq; + dcm[1][2] = 2 * (c * d - a * b); + dcm[2][0] = 2 * (b * d - a * c); + dcm[2][1] = 2 * (a * b + c * d); + dcm[2][2] = aSq - bSq - cSq + dSq; +} + + +/** + * Converts a rotation matrix to euler angles + * + * @param dcm a 3x3 rotation matrix + * @param roll the roll angle in radians + * @param pitch the pitch angle in radians + * @param yaw the yaw angle in radians + */ +MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw) +{ + float phi, theta, psi; + theta = asin(-dcm[2][0]); + + if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) { + phi = 0.0f; + psi = (atan2f(dcm[1][2] - dcm[0][1], + dcm[0][2] + dcm[1][1]) + phi); + + } else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) { + phi = 0.0f; + psi = atan2f(dcm[1][2] - dcm[0][1], + dcm[0][2] + dcm[1][1] - phi); + + } else { + phi = atan2f(dcm[2][1], dcm[2][2]); + psi = atan2f(dcm[1][0], dcm[0][0]); + } + + *roll = phi; + *pitch = theta; + *yaw = psi; +} + + +/** + * Converts a quaternion to euler angles + * + * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) + * @param roll the roll angle in radians + * @param pitch the pitch angle in radians + * @param yaw the yaw angle in radians + */ +MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float* roll, float* pitch, float* yaw) +{ + float dcm[3][3]; + mavlink_quaternion_to_dcm(quaternion, dcm); + mavlink_dcm_to_euler((const float(*)[3])dcm, roll, pitch, yaw); +} + + +/** + * Converts euler angles to a quaternion + * + * @param roll the roll angle in radians + * @param pitch the pitch angle in radians + * @param yaw the yaw angle in radians + * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) + */ +MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4]) +{ + float cosPhi_2 = cosf(roll / 2); + float sinPhi_2 = sinf(roll / 2); + float cosTheta_2 = cosf(pitch / 2); + float sinTheta_2 = sinf(pitch / 2); + float cosPsi_2 = cosf(yaw / 2); + float sinPsi_2 = sinf(yaw / 2); + quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 + + sinPhi_2 * sinTheta_2 * sinPsi_2); + quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 - + cosPhi_2 * sinTheta_2 * sinPsi_2); + quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 + + sinPhi_2 * cosTheta_2 * sinPsi_2); + quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 - + sinPhi_2 * sinTheta_2 * cosPsi_2); +} + + +/** + * Converts a rotation matrix to a quaternion + * Reference: + * - Shoemake, Quaternions, + * http://www.cs.ucr.edu/~vbz/resources/quatut.pdf + * + * @param dcm a 3x3 rotation matrix + * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) + */ +MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4]) +{ + float tr = dcm[0][0] + dcm[1][1] + dcm[2][2]; + if (tr > 0.0f) { + float s = sqrtf(tr + 1.0f); + quaternion[0] = s * 0.5f; + s = 0.5f / s; + quaternion[1] = (dcm[2][1] - dcm[1][2]) * s; + quaternion[2] = (dcm[0][2] - dcm[2][0]) * s; + quaternion[3] = (dcm[1][0] - dcm[0][1]) * s; + } else { + /* Find maximum diagonal element in dcm + * store index in dcm_i */ + int dcm_i = 0; + int i; + for (i = 1; i < 3; i++) { + if (dcm[i][i] > dcm[dcm_i][dcm_i]) { + dcm_i = i; + } + } + + int dcm_j = (dcm_i + 1) % 3; + int dcm_k = (dcm_i + 2) % 3; + + float s = sqrtf((dcm[dcm_i][dcm_i] - dcm[dcm_j][dcm_j] - + dcm[dcm_k][dcm_k]) + 1.0f); + quaternion[dcm_i + 1] = s * 0.5f; + s = 0.5f / s; + quaternion[dcm_j + 1] = (dcm[dcm_i][dcm_j] + dcm[dcm_j][dcm_i]) * s; + quaternion[dcm_k + 1] = (dcm[dcm_k][dcm_i] + dcm[dcm_i][dcm_k]) * s; + quaternion[0] = (dcm[dcm_k][dcm_j] - dcm[dcm_j][dcm_k]) * s; + } +} + + +/** + * Converts euler angles to a rotation matrix + * + * @param roll the roll angle in radians + * @param pitch the pitch angle in radians + * @param yaw the yaw angle in radians + * @param dcm a 3x3 rotation matrix + */ +MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3]) +{ + float cosPhi = cosf(roll); + float sinPhi = sinf(roll); + float cosThe = cosf(pitch); + float sinThe = sinf(pitch); + float cosPsi = cosf(yaw); + float sinPsi = sinf(yaw); + + dcm[0][0] = cosThe * cosPsi; + dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi; + dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi; + + dcm[1][0] = cosThe * sinPsi; + dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi; + dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi; + + dcm[2][0] = -sinThe; + dcm[2][1] = sinPhi * cosThe; + dcm[2][2] = cosPhi * cosThe; +} + +#endif diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/mavlink_helpers.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/mavlink_helpers.h new file mode 100644 index 0000000..0fa87fc --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/mavlink_helpers.h @@ -0,0 +1,676 @@ +#ifndef _MAVLINK_HELPERS_H_ +#define _MAVLINK_HELPERS_H_ + +#include "string.h" +#include "checksum.h" +#include "mavlink_types.h" +#include "mavlink_conversions.h" + +#ifndef MAVLINK_HELPER +#define MAVLINK_HELPER +#endif + +/* + * Internal function to give access to the channel status for each channel + */ +#ifndef MAVLINK_GET_CHANNEL_STATUS +MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan) +{ +#ifdef MAVLINK_EXTERNAL_RX_STATUS + // No m_mavlink_status array defined in function, + // has to be defined externally +#else + static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; +#endif + return &m_mavlink_status[chan]; +} +#endif + +/* + * Internal function to give access to the channel buffer for each channel + */ +#ifndef MAVLINK_GET_CHANNEL_BUFFER +MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) +{ + +#ifdef MAVLINK_EXTERNAL_RX_BUFFER + // No m_mavlink_buffer array defined in function, + // has to be defined externally +#else + static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS]; +#endif + return &m_mavlink_buffer[chan]; +} +#endif + +/** + * @brief Reset the status of a channel. + */ +MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan) +{ + mavlink_status_t *status = mavlink_get_channel_status(chan); + status->parse_state = MAVLINK_PARSE_STATE_IDLE; +} + +/** + * @brief Finalize a MAVLink message with channel assignment + * + * This function calculates the checksum and sets length and aircraft id correctly. + * It assumes that the message id and the payload are already correctly set. This function + * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack + * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. + * + * @param msg Message to finalize + * @param system_id Id of the sending (this) system, 1-127 + * @param length Message length + */ +#if MAVLINK_CRC_EXTRA +MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length, uint8_t crc_extra) +#else +MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length) +#endif +{ + // This code part is the same for all messages; + msg->magic = MAVLINK_STX; + msg->len = length; + msg->sysid = system_id; + msg->compid = component_id; + // One sequence number per channel + msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; + mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1; + msg->checksum = crc_calculate(((const uint8_t*)(msg)) + 3, MAVLINK_CORE_HEADER_LEN); + crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len); +#if MAVLINK_CRC_EXTRA + crc_accumulate(crc_extra, &msg->checksum); +#endif + mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF); + mavlink_ck_b(msg) = (uint8_t)(msg->checksum >> 8); + + return length + MAVLINK_NUM_NON_PAYLOAD_BYTES; +} + + +/** + * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel + */ +#if MAVLINK_CRC_EXTRA +MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length, uint8_t crc_extra) +{ + return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra); +} +#else +MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length) +{ + return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length); +} +#endif + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS +MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); + +/** + * @brief Finalize a MAVLink message with channel assignment and send + */ +#if MAVLINK_CRC_EXTRA +MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, + uint8_t length, uint8_t crc_extra) +#else +MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length) +#endif +{ + uint16_t checksum; + uint8_t buf[MAVLINK_NUM_HEADER_BYTES]; + uint8_t ck[2]; + mavlink_status_t *status = mavlink_get_channel_status(chan); + buf[0] = MAVLINK_STX; + buf[1] = length; + buf[2] = status->current_tx_seq; + buf[3] = mavlink_system.sysid; + buf[4] = mavlink_system.compid; + buf[5] = msgid; + status->current_tx_seq++; + checksum = crc_calculate((const uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN); + crc_accumulate_buffer(&checksum, packet, length); +#if MAVLINK_CRC_EXTRA + crc_accumulate(crc_extra, &checksum); +#endif + ck[0] = (uint8_t)(checksum & 0xFF); + ck[1] = (uint8_t)(checksum >> 8); + + MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); + _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES); + _mavlink_send_uart(chan, packet, length); + _mavlink_send_uart(chan, (const char *)ck, 2); + MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); +} + +/** + * @brief re-send a message over a uart channel + * this is more stack efficient than re-marshalling the message + */ +MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg) +{ + uint8_t ck[2]; + + ck[0] = (uint8_t)(msg->checksum & 0xFF); + ck[1] = (uint8_t)(msg->checksum >> 8); + // XXX use the right sequence here + + MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len); + _mavlink_send_uart(chan, (const char *)&msg->magic, MAVLINK_NUM_HEADER_BYTES); + _mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len); + _mavlink_send_uart(chan, (const char *)ck, 2); + MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len); +} +#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS + +/** + * @brief Pack a message to send it over a serial byte stream + */ +MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg) +{ + memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len); + + uint8_t *ck = buffer + (MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len); + + ck[0] = (uint8_t)(msg->checksum & 0xFF); + ck[1] = (uint8_t)(msg->checksum >> 8); + + return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; +} + +union __mavlink_bitfield { + uint8_t uint8; + int8_t int8; + uint16_t uint16; + int16_t int16; + uint32_t uint32; + int32_t int32; +}; + + +MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg) +{ + crc_init(&msg->checksum); +} + +MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) +{ + crc_accumulate(c, &msg->checksum); +} + +/** + * This is a varient of mavlink_frame_char() but with caller supplied + * parsing buffers. It is useful when you want to create a MAVLink + * parser in a library that doesn't use any global variables + * + * @param rxmsg parsing message buffer + * @param status parsing starus buffer + * @param c The char to parse + * + * @param returnMsg NULL if no message could be decoded, the message data else + * @param returnStats if a message was decoded, this is filled with the channel's stats + * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC + * + * A typical use scenario of this function call is: + * + * @code + * #include + * + * mavlink_message_t msg; + * int chan = 0; + * + * + * while(serial.bytesAvailable > 0) + * { + * uint8_t byte = serial.getNextByte(); + * if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE) + * { + * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); + * } + * } + * + * + * @endcode + */ +MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, + mavlink_status_t* status, + uint8_t c, + mavlink_message_t* r_message, + mavlink_status_t* r_mavlink_status) +{ + /* + default message crc function. You can override this per-system to + put this data in a different memory segment + */ +#if MAVLINK_CRC_EXTRA +#ifndef MAVLINK_MESSAGE_CRC + static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; +#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid] +#endif +#endif + + /* Enable this option to check the length of each message. + This allows invalid messages to be caught much sooner. Use if the transmission + medium is prone to missing (or extra) characters (e.g. a radio that fades in + and out). Only use if the channel will only contain messages types listed in + the headers. + */ +#ifdef MAVLINK_CHECK_MESSAGE_LENGTH +#ifndef MAVLINK_MESSAGE_LENGTH + static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS; +#define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid] +#endif +#endif + + int bufferIndex = 0; + + status->msg_received = MAVLINK_FRAMING_INCOMPLETE; + + switch (status->parse_state) + { + case MAVLINK_PARSE_STATE_UNINIT: + case MAVLINK_PARSE_STATE_IDLE: + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + rxmsg->len = 0; + rxmsg->magic = c; + mavlink_start_checksum(rxmsg); + } + break; + + case MAVLINK_PARSE_STATE_GOT_STX: + if (status->msg_received +/* Support shorter buffers than the + default maximum packet size */ +#if (MAVLINK_MAX_PAYLOAD_LEN < 255) + || c > MAVLINK_MAX_PAYLOAD_LEN +#endif + ) + { + status->buffer_overrun++; + status->parse_error++; + status->msg_received = 0; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + } + else + { + // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 + rxmsg->len = c; + status->packet_idx = 0; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; + } + break; + + case MAVLINK_PARSE_STATE_GOT_LENGTH: + rxmsg->seq = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; + break; + + case MAVLINK_PARSE_STATE_GOT_SEQ: + rxmsg->sysid = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; + break; + + case MAVLINK_PARSE_STATE_GOT_SYSID: + rxmsg->compid = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; + break; + + case MAVLINK_PARSE_STATE_GOT_COMPID: +#ifdef MAVLINK_CHECK_MESSAGE_LENGTH + if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c)) + { + status->parse_error++; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + break; + } +#endif + rxmsg->msgid = c; + mavlink_update_checksum(rxmsg, c); + if (rxmsg->len == 0) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; + } + else + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; + } + break; + + case MAVLINK_PARSE_STATE_GOT_MSGID: + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c; + mavlink_update_checksum(rxmsg, c); + if (status->packet_idx == rxmsg->len) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; + } + break; + + case MAVLINK_PARSE_STATE_GOT_PAYLOAD: +#if MAVLINK_CRC_EXTRA + mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid)); +#endif + if (c != (rxmsg->checksum & 0xFF)) { + status->parse_state = MAVLINK_PARSE_STATE_GOT_BAD_CRC1; + } else { + status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; + } + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c; + break; + + case MAVLINK_PARSE_STATE_GOT_CRC1: + case MAVLINK_PARSE_STATE_GOT_BAD_CRC1: + if (status->parse_state == MAVLINK_PARSE_STATE_GOT_BAD_CRC1 || c != (rxmsg->checksum >> 8)) { + // got a bad CRC message + status->msg_received = MAVLINK_FRAMING_BAD_CRC; + } else { + // Successfully got message + status->msg_received = MAVLINK_FRAMING_OK; + } + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c; + memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); + break; + } + + bufferIndex++; + // If a message has been sucessfully decoded, check index + if (status->msg_received == MAVLINK_FRAMING_OK) + { + //while(status->current_seq != rxmsg->seq) + //{ + // status->packet_rx_drop_count++; + // status->current_seq++; + //} + status->current_rx_seq = rxmsg->seq; + // Initial condition: If no packet has been received so far, drop count is undefined + if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; + // Count this packet as received + status->packet_rx_success_count++; + } + + r_message->len = rxmsg->len; // Provide visibility on how far we are into current msg + r_mavlink_status->parse_state = status->parse_state; + r_mavlink_status->packet_idx = status->packet_idx; + r_mavlink_status->current_rx_seq = status->current_rx_seq+1; + r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; + r_mavlink_status->packet_rx_drop_count = status->parse_error; + status->parse_error = 0; + + if (status->msg_received == MAVLINK_FRAMING_BAD_CRC) { + /* + the CRC came out wrong. We now need to overwrite the + msg CRC with the one on the wire so that if the + caller decides to forward the message anyway that + mavlink_msg_to_send_buffer() won't overwrite the + checksum + */ + r_message->checksum = _MAV_PAYLOAD(rxmsg)[status->packet_idx] | (_MAV_PAYLOAD(rxmsg)[status->packet_idx+1]<<8); + } + + return status->msg_received; +} + +/** + * This is a convenience function which handles the complete MAVLink parsing. + * the function will parse one byte at a time and return the complete packet once + * it could be successfully decoded. This function will return 0, 1 or + * 2 (MAVLINK_FRAMING_INCOMPLETE, MAVLINK_FRAMING_OK or MAVLINK_FRAMING_BAD_CRC) + * + * Messages are parsed into an internal buffer (one for each channel). When a complete + * message is received it is copies into *returnMsg and the channel's status is + * copied into *returnStats. + * + * @param chan ID of the current channel. This allows to parse different channels with this function. + * a channel is not a physical message channel like a serial port, but a logic partition of + * the communication streams in this case. COMM_NB is the limit for the number of channels + * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows + * @param c The char to parse + * + * @param returnMsg NULL if no message could be decoded, the message data else + * @param returnStats if a message was decoded, this is filled with the channel's stats + * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC + * + * A typical use scenario of this function call is: + * + * @code + * #include + * + * mavlink_message_t msg; + * int chan = 0; + * + * + * while(serial.bytesAvailable > 0) + * { + * uint8_t byte = serial.getNextByte(); + * if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE) + * { + * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); + * } + * } + * + * + * @endcode + */ +MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) +{ + return mavlink_frame_char_buffer(mavlink_get_channel_buffer(chan), + mavlink_get_channel_status(chan), + c, + r_message, + r_mavlink_status); +} + + +/** + * This is a convenience function which handles the complete MAVLink parsing. + * the function will parse one byte at a time and return the complete packet once + * it could be successfully decoded. This function will return 0 or 1. + * + * Messages are parsed into an internal buffer (one for each channel). When a complete + * message is received it is copies into *returnMsg and the channel's status is + * copied into *returnStats. + * + * @param chan ID of the current channel. This allows to parse different channels with this function. + * a channel is not a physical message channel like a serial port, but a logic partition of + * the communication streams in this case. COMM_NB is the limit for the number of channels + * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows + * @param c The char to parse + * + * @param returnMsg NULL if no message could be decoded, the message data else + * @param returnStats if a message was decoded, this is filled with the channel's stats + * @return 0 if no message could be decoded or bad CRC, 1 on good message and CRC + * + * A typical use scenario of this function call is: + * + * @code + * #include + * + * mavlink_message_t msg; + * int chan = 0; + * + * + * while(serial.bytesAvailable > 0) + * { + * uint8_t byte = serial.getNextByte(); + * if (mavlink_parse_char(chan, byte, &msg)) + * { + * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); + * } + * } + * + * + * @endcode + */ +MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) +{ + uint8_t msg_received = mavlink_frame_char(chan, c, r_message, r_mavlink_status); + if (msg_received == MAVLINK_FRAMING_BAD_CRC) { + // we got a bad CRC. Treat as a parse failure + mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); + mavlink_status_t* status = mavlink_get_channel_status(chan); + status->parse_error++; + status->msg_received = MAVLINK_FRAMING_INCOMPLETE; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + rxmsg->len = 0; + mavlink_start_checksum(rxmsg); + } + return 0; + } + return msg_received; +} + +/** + * @brief Put a bitfield of length 1-32 bit into the buffer + * + * @param b the value to add, will be encoded in the bitfield + * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. + * @param packet_index the position in the packet (the index of the first byte to use) + * @param bit_index the position in the byte (the index of the first bit to use) + * @param buffer packet buffer to write into + * @return new position of the last used byte in the buffer + */ +MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer) +{ + uint16_t bits_remain = bits; + // Transform number into network order + int32_t v; + uint8_t i_bit_index, i_byte_index, curr_bits_n; +#if MAVLINK_NEED_BYTE_SWAP + union { + int32_t i; + uint8_t b[4]; + } bin, bout; + bin.i = b; + bout.b[0] = bin.b[3]; + bout.b[1] = bin.b[2]; + bout.b[2] = bin.b[1]; + bout.b[3] = bin.b[0]; + v = bout.i; +#else + v = b; +#endif + + // buffer in + // 01100000 01000000 00000000 11110001 + // buffer out + // 11110001 00000000 01000000 01100000 + + // Existing partly filled byte (four free slots) + // 0111xxxx + + // Mask n free bits + // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1 + // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1 + + // Shift n bits into the right position + // out = in >> n; + + // Mask and shift bytes + i_bit_index = bit_index; + i_byte_index = packet_index; + if (bit_index > 0) + { + // If bits were available at start, they were available + // in the byte before the current index + i_byte_index--; + } + + // While bits have not been packed yet + while (bits_remain > 0) + { + // Bits still have to be packed + // there can be more than 8 bits, so + // we might have to pack them into more than one byte + + // First pack everything we can into the current 'open' byte + //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 + //FIXME + if (bits_remain <= (uint8_t)(8 - i_bit_index)) + { + // Enough space + curr_bits_n = (uint8_t)bits_remain; + } + else + { + curr_bits_n = (8 - i_bit_index); + } + + // Pack these n bits into the current byte + // Mask out whatever was at that position with ones (xxx11111) + buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n)); + // Put content to this position, by masking out the non-used part + buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v); + + // Increment the bit index + i_bit_index += curr_bits_n; + + // Now proceed to the next byte, if necessary + bits_remain -= curr_bits_n; + if (bits_remain > 0) + { + // Offer another 8 bits / one byte + i_byte_index++; + i_bit_index = 0; + } + } + + *r_bit_index = i_bit_index; + // If a partly filled byte is present, mark this as consumed + if (i_bit_index != 7) i_byte_index++; + return i_byte_index - packet_index; +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +// To make MAVLink work on your MCU, define comm_send_ch() if you wish +// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a +// whole packet at a time + +/* + +#include "mavlink_types.h" + +void comm_send_ch(mavlink_channel_t chan, uint8_t ch) +{ + if (chan == MAVLINK_COMM_0) + { + uart0_transmit(ch); + } + if (chan == MAVLINK_COMM_1) + { + uart1_transmit(ch); + } +} + */ + +MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len) +{ +#ifdef MAVLINK_SEND_UART_BYTES + /* this is the more efficient approach, if the platform + defines it */ + MAVLINK_SEND_UART_BYTES(chan, (const uint8_t *)buf, len); +#else + /* fallback to one byte at a time */ + uint16_t i; + for (i = 0; i < len; i++) { + comm_send_ch(chan, (uint8_t)buf[i]); + } +#endif +} +#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS + +#endif /* _MAVLINK_HELPERS_H_ */ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/mavlink_types.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/mavlink_types.h new file mode 100644 index 0000000..0a98ccc --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/mavlink_types.h @@ -0,0 +1,228 @@ +#ifndef MAVLINK_TYPES_H_ +#define MAVLINK_TYPES_H_ + +// Visual Studio versions before 2010 don't have stdint.h, so we just error out. +#if (defined _MSC_VER) && (_MSC_VER < 1600) +#error "The C-MAVLink implementation requires Visual Studio 2010 or greater" +#endif + +#include + +// Macro to define packed structures +#ifdef __GNUC__ + #define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed)) +#else + #define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) ) +#endif + +#ifndef MAVLINK_MAX_PAYLOAD_LEN +// it is possible to override this, but be careful! +#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length +#endif + +#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte) +#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum +#define MAVLINK_NUM_CHECKSUM_BYTES 2 +#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) + +#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length + +#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 +#define MAVLINK_EXTENDED_HEADER_LEN 14 + +#if (defined _MSC_VER) || ((defined __APPLE__) && (defined __MACH__)) || (defined __linux__) + /* full fledged 32bit++ OS */ + #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507 +#else + /* small microcontrollers */ + #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048 +#endif + +#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES) + + +/** + * Old-style 4 byte param union + * + * This struct is the data format to be used when sending + * parameters. The parameter should be copied to the native + * type (without type conversion) + * and re-instanted on the receiving side using the + * native type as well. + */ +MAVPACKED( +typedef struct param_union { + union { + float param_float; + int32_t param_int32; + uint32_t param_uint32; + int16_t param_int16; + uint16_t param_uint16; + int8_t param_int8; + uint8_t param_uint8; + uint8_t bytes[4]; + }; + uint8_t type; +}) mavlink_param_union_t; + + +/** + * New-style 8 byte param union + * mavlink_param_union_double_t will be 8 bytes long, and treated as needing 8 byte alignment for the purposes of MAVLink 1.0 field ordering. + * The mavlink_param_union_double_t will be treated as a little-endian structure. + * + * If is_double is 1 then the type is a double, and the remaining 63 bits are the double, with the lowest bit of the mantissa zero. + * The intention is that by replacing the is_double bit with 0 the type can be directly used as a double (as the is_double bit corresponds to the + * lowest mantissa bit of a double). If is_double is 0 then mavlink_type gives the type in the union. + * The mavlink_types.h header will also need to have shifts/masks to define the bit boundaries in the above, + * as bitfield ordering isn’t consistent between platforms. The above is intended to be for gcc on x86, + * which should be the same as gcc on little-endian arm. When using shifts/masks the value will be treated as a 64 bit unsigned number, + * and the bits pulled out using the shifts/masks. +*/ +MAVPACKED( +typedef struct param_union_extended { + union { + struct { + uint8_t is_double:1; + uint8_t mavlink_type:7; + union { + char c; + uint8_t uint8; + int8_t int8; + uint16_t uint16; + int16_t int16; + uint32_t uint32; + int32_t int32; + float f; + uint8_t align[7]; + }; + }; + uint8_t data[8]; + }; +}) mavlink_param_union_double_t; + +/** + * This structure is required to make the mavlink_send_xxx convenience functions + * work, as it tells the library what the current system and component ID are. + */ +MAVPACKED( +typedef struct __mavlink_system { + uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function + uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function +}) mavlink_system_t; + +MAVPACKED( +typedef struct __mavlink_message { + uint16_t checksum; ///< sent at end of packet + uint8_t magic; ///< protocol magic marker + uint8_t len; ///< Length of payload + uint8_t seq; ///< Sequence of packet + uint8_t sysid; ///< ID of message sender system/aircraft + uint8_t compid; ///< ID of the message sender component + uint8_t msgid; ///< ID of message in payload + uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; +}) mavlink_message_t; + +MAVPACKED( +typedef struct __mavlink_extended_message { + mavlink_message_t base_msg; + int32_t extended_payload_len; ///< Length of extended payload if any + uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN]; +}) mavlink_extended_message_t; + +typedef enum { + MAVLINK_TYPE_CHAR = 0, + MAVLINK_TYPE_UINT8_T = 1, + MAVLINK_TYPE_INT8_T = 2, + MAVLINK_TYPE_UINT16_T = 3, + MAVLINK_TYPE_INT16_T = 4, + MAVLINK_TYPE_UINT32_T = 5, + MAVLINK_TYPE_INT32_T = 6, + MAVLINK_TYPE_UINT64_T = 7, + MAVLINK_TYPE_INT64_T = 8, + MAVLINK_TYPE_FLOAT = 9, + MAVLINK_TYPE_DOUBLE = 10 +} mavlink_message_type_t; + +#define MAVLINK_MAX_FIELDS 64 + +typedef struct __mavlink_field_info { + const char *name; // name of this field + const char *print_format; // printing format hint, or NULL + mavlink_message_type_t type; // type of this field + unsigned int array_length; // if non-zero, field is an array + unsigned int wire_offset; // offset of each field in the payload + unsigned int structure_offset; // offset in a C structure +} mavlink_field_info_t; + +// note that in this structure the order of fields is the order +// in the XML file, not necessary the wire order +typedef struct __mavlink_message_info { + const char *name; // name of the message + unsigned num_fields; // how many fields in this message + mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information +} mavlink_message_info_t; + +#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0]))) +#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0]))) + +// checksum is immediately after the payload bytes +#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) +#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) + +typedef enum { + MAVLINK_COMM_0, + MAVLINK_COMM_1, + MAVLINK_COMM_2, + MAVLINK_COMM_3 +} mavlink_channel_t; + +/* + * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number + * of buffers they will use. If more are used, then the result will be + * a stack overrun + */ +#ifndef MAVLINK_COMM_NUM_BUFFERS +#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) +# define MAVLINK_COMM_NUM_BUFFERS 16 +#else +# define MAVLINK_COMM_NUM_BUFFERS 4 +#endif +#endif + +typedef enum { + MAVLINK_PARSE_STATE_UNINIT=0, + MAVLINK_PARSE_STATE_IDLE, + MAVLINK_PARSE_STATE_GOT_STX, + MAVLINK_PARSE_STATE_GOT_SEQ, + MAVLINK_PARSE_STATE_GOT_LENGTH, + MAVLINK_PARSE_STATE_GOT_SYSID, + MAVLINK_PARSE_STATE_GOT_COMPID, + MAVLINK_PARSE_STATE_GOT_MSGID, + MAVLINK_PARSE_STATE_GOT_PAYLOAD, + MAVLINK_PARSE_STATE_GOT_CRC1, + MAVLINK_PARSE_STATE_GOT_BAD_CRC1 +} mavlink_parse_state_t; ///< The state machine for the comm parser + +typedef enum { + MAVLINK_FRAMING_INCOMPLETE=0, + MAVLINK_FRAMING_OK=1, + MAVLINK_FRAMING_BAD_CRC=2 +} mavlink_framing_t; + +typedef struct __mavlink_status { + uint8_t msg_received; ///< Number of received messages + uint8_t buffer_overrun; ///< Number of buffer overruns + uint8_t parse_error; ///< Number of parse errors + mavlink_parse_state_t parse_state; ///< Parsing state machine + uint8_t packet_idx; ///< Index in current packet + uint8_t current_rx_seq; ///< Sequence number of last packet received + uint8_t current_tx_seq; ///< Sequence number of last packet sent + uint16_t packet_rx_success_count; ///< Received packets + uint16_t packet_rx_drop_count; ///< Number of packet drops +} mavlink_status_t; + +#define MAVLINK_BIG_ENDIAN 0 +#define MAVLINK_LITTLE_ENDIAN 1 + +#endif /* MAVLINK_TYPES_H_ */ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/ASLUAV.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/ASLUAV.xml new file mode 100644 index 0000000..0c3e394 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/ASLUAV.xml @@ -0,0 +1,176 @@ + + + + + common.xml + + + + + Mission command to reset Maximum Power Point Tracker (MPPT) + MPPT number + Empty + Empty + Empty + Empty + Empty + Empty + + + Mission command to perform a power cycle on payload + Complete power cycle + VISensor power cycle + Empty + Empty + Empty + Empty + Empty + + + + + + Voltage and current sensor data + Power board voltage sensor reading in volts + Power board current sensor reading in amps + Board current sensor 1 reading in amps + Board current sensor 2 reading in amps + + + Maximum Power Point Tracker (MPPT) sensor data for solar module power performance tracking + MPPT last timestamp + MPPT1 voltage + MPPT1 current + MPPT1 pwm + MPPT1 status + MPPT2 voltage + MPPT2 current + MPPT2 pwm + MPPT2 status + MPPT3 voltage + MPPT3 current + MPPT3 pwm + MPPT3 status + + + ASL-fixed-wing controller data + Timestamp + ASLCTRL control-mode (manual, stabilized, auto, etc...) + See sourcecode for a description of these values... + + + Pitch angle [deg] + Pitch angle reference[deg] + + + + + + + Airspeed reference [m/s] + + Yaw angle [deg] + Yaw angle reference[deg] + Roll angle [deg] + Roll angle reference[deg] + + + + + + + + + ASL-fixed-wing controller debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + Debug data + + + Extended state information for ASLUAVs + Status of the position-indicator LEDs + Status of the IRIDIUM satellite communication system + Status vector for up to 8 servos + Motor RPM + + + + Extended EKF state estimates for ASLUAVs + Time since system start [us] + Magnitude of wind velocity (in lateral inertial plane) [m/s] + Wind heading angle from North [rad] + Z (Down) component of inertial wind velocity [m/s] + Magnitude of air velocity [m/s] + Sideslip angle [rad] + Angle of attack [rad] + + + Off-board controls/commands for ASLUAVs + Time since system start [us] + Elevator command [~] + Throttle command [~] + Throttle 2 command [~] + Left aileron command [~] + Right aileron command [~] + Rudder command [~] + Off-board computer status + + + Atmospheric sensors (temperature, humidity, ...) + Ambient temperature [degrees Celsius] + Relative humidity [%] + + + Battery pack monitoring data for Li-Ion batteries + Battery pack temperature in [deg C] + Battery pack voltage in [mV] + Battery pack current in [mA] + Battery pack state-of-charge + Battery monitor status report bits in Hex + Battery monitor serial number in Hex + Battery monitor sensor host FET control in Hex + Battery pack cell 1 voltage in [mV] + Battery pack cell 2 voltage in [mV] + Battery pack cell 3 voltage in [mV] + Battery pack cell 4 voltage in [mV] + Battery pack cell 5 voltage in [mV] + Battery pack cell 6 voltage in [mV] + + + Fixed-wing soaring (i.e. thermal seeking) data + Timestamp [ms] + Timestamp since last mode change[ms] + Updraft speed at current/local airplane position [m/s] + Thermal core updraft strength [m/s] + Thermal radius [m] + Thermal center latitude [deg] + Thermal center longitude [deg] + Variance W + Variance R + Variance Lat + Variance Lon + Suggested loiter radius [m] + Control Mode [-] + Data valid [-] + + + Monitoring of sensorpod status + Timestamp in linuxtime [ms] (since 1.1.1970) + Rate of ROS topic 1 + Rate of ROS topic 2 + Rate of ROS topic 3 + Rate of ROS topic 4 + Number of recording nodes + Temperature of sensorpod CPU in [deg C] + Free space available in recordings directory in [Gb] * 1e2 + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/ardupilotmega.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/ardupilotmega.xml new file mode 100644 index 0000000..e04c0b1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/ardupilotmega.xml @@ -0,0 +1,1564 @@ + + + common.xml + + + + + + Mission command to perform motor test + motor sequence number (a number from 1 to max number of motors on the vehicle) + throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum) + throttle + timeout (in seconds) + Empty + Empty + Empty + + + + Mission command to operate EPM gripper + gripper number (a number from 1 to max number of grippers on the vehicle) + gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum) + Empty + Empty + Empty + Empty + Empty + + + + Enable/disable autotune + enable (1: enable, 0:disable) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up. + altitude (m) + descent speed (m/s) + Wiggle Time (s) + Empty + Empty + Empty + Empty + + + + A system wide power-off event has been initiated. + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + + FLY button has been clicked. + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + FLY button has been held for 1.5 seconds. + Takeoff altitude + Empty + Empty + Empty + Empty + Empty + Empty + + + + PAUSE button has been clicked. + 1 if Solo is in a shot mode, 0 otherwise + Empty + Empty + Empty + Empty + Empty + Empty + + + + Initiate a magnetometer calibration + uint8_t bitmask of magnetometers (0 means all) + Automatically retry on failure (0=no retry, 1=retry). + Save without user input (0=require input, 1=autosave). + Delay (seconds) + Autoreboot (0=user reboot, 1=autoreboot) + Empty + Empty + + + + Initiate a magnetometer calibration + uint8_t bitmask of magnetometers (0 means all) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Cancel a running magnetometer calibration + uint8_t bitmask of magnetometers (0 means all) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Reply with the version banner + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + Causes the gimbal to reset and boot as if it was just powered on + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + Command autopilot to get into factory test/diagnostic mode + 0 means get out of test mode, 1 means get into test mode + Empty + Empty + Empty + Empty + Empty + Empty + + + + Reports progress and success or failure of gimbal axis calibration procedure + Gimbal axis we're reporting calibration progress for + Current calibration progress for this axis, 0x64=100% + Status of the calibration + Empty + Empty + Empty + Empty + + + + Starts commutation calibration on the gimbal + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + Erases gimbal application and parameters + Magic number + Magic number + Magic number + Magic number + Magic number + Magic number + Magic number + + + + + + + pre-initialization + + + + disabled + + + + checking limits + + + + a limit has been breached + + + + taking action eg. RTL + + + + we're no longer in breach of a limit + + + + + + + pre-initialization + + + + disabled + + + + checking limits + + + + + + Flags in RALLY_POINT message + + Flag set when requiring favorable winds for landing. + + + + Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land. + + + + + + + Disable parachute release + + + + Enable parachute release + + + + Release parachute + + + + + + + throttle as a percentage from 0 ~ 100 + + + + throttle as an absolute PWM value (normally in range of 1000~2000) + + + + throttle pass-through from pilot's transmitter + + + + + + Gripper actions. + + gripper release of cargo + + + + gripper grabs onto cargo + + + + + + + Camera heartbeat, announce camera component ID at 1hz + + + + Camera image triggered + + + + Camera connection lost + + + + Camera unknown error + + + + Camera battery low. Parameter p1 shows reported voltage + + + + Camera storage low. Parameter p1 shows reported shots remaining + + + + Camera storage low. Parameter p1 shows reported video minutes remaining + + + + + + + Shooting photos, not video + + + + Shooting video, not stills + + + + Unable to achieve requested exposure (e.g. shutter speed too low) + + + + Closed loop feedback from camera, we know for sure it has successfully taken a picture + + + + Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture + + + + + + + Gimbal is powered on but has not started initializing yet + + + + Gimbal is currently running calibration on the pitch axis + + + + Gimbal is currently running calibration on the roll axis + + + + Gimbal is currently running calibration on the yaw axis + + + + Gimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter + + + + Gimbal is actively stabilizing + + + + Gimbal is relaxed because it missed more than 10 expected rate command messages in a row. Gimbal will move back to active mode when it receives a new rate command + + + + + + Gimbal yaw axis + + + + Gimbal pitch axis + + + + Gimbal roll axis + + + + + + Axis calibration is in progress + + + + Axis calibration succeeded + + + + Axis calibration failed + + + + + + Whether or not this axis requires calibration is unknown at this time + + + + This axis requires calibration + + + + This axis does not require calibration + + + + + + + No GoPro connected + + + + The detected GoPro is not HeroBus compatible + + + + A HeroBus compatible GoPro is connected + + + + An unrecoverable error was encountered with the connected GoPro, it may require a power cycle + + + + + + + GoPro is currently recording + + + + + + The write message with ID indicated succeeded + + + + The write message with ID indicated failed + + + + + + (Get/Set) + + + + (Get/Set) + + + + (___/Set) + + + + (Get/___) + + + + (Get/___) + + + + (Get/Set) + + + + + (Get/Set) + + + + (Get/Set) + + + + (Get/Set) + + + + (Get/Set) + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) Hero 3+ Only + + + + (Get/Set) + + + + + (Get/Set) + + + + + + Video mode + + + + Photo mode + + + + Burst mode, hero 3+ only + + + + Time lapse mode, hero 3+ only + + + + Multi shot mode, hero 4 only + + + + Playback mode, hero 4 only, silver only except when LCD or HDMI is connected to black + + + + Playback mode, hero 4 only + + + + Mode not yet known + + + + + + 848 x 480 (480p) + + + + 1280 x 720 (720p) + + + + 1280 x 960 (960p) + + + + 1920 x 1080 (1080p) + + + + 1920 x 1440 (1440p) + + + + 2704 x 1440 (2.7k-17:9) + + + + 2704 x 1524 (2.7k-16:9) + + + + 2704 x 2028 (2.7k-4:3) + + + + 3840 x 2160 (4k-16:9) + + + + 4096 x 2160 (4k-17:9) + + + + 1280 x 720 (720p-SuperView) + + + + 1920 x 1080 (1080p-SuperView) + + + + 2704 x 1520 (2.7k-SuperView) + + + + 3840 x 2160 (4k-SuperView) + + + + + + 12 FPS + + + + 15 FPS + + + + 24 FPS + + + + 25 FPS + + + + 30 FPS + + + + 48 FPS + + + + 50 FPS + + + + 60 FPS + + + + 80 FPS + + + + 90 FPS + + + + 100 FPS + + + + 120 FPS + + + + 240 FPS + + + + 12.5 FPS + + + + + + 0x00: Wide + + + + 0x01: Medium + + + + 0x02: Narrow + + + + + + 0=NTSC, 1=PAL + + + + + + 5MP Medium + + + + 7MP Medium + + + + 7MP Wide + + + + 10MP Wide + + + + 12MP Wide + + + + + + Auto + + + + 3000K + + + + 5500K + + + + 6500K + + + + Camera Raw + + + + + + Auto + + + + Neutral + + + + + + ISO 400 + + + + ISO 800 (Only Hero 4) + + + + ISO 1600 + + + + ISO 3200 (Only Hero 4) + + + + ISO 6400 + + + + + + Low Sharpness + + + + Medium Sharpness + + + + High Sharpness + + + + + + -5.0 EV (Hero 3+ Only) + + + + -4.5 EV (Hero 3+ Only) + + + + -4.0 EV (Hero 3+ Only) + + + + -3.5 EV (Hero 3+ Only) + + + + -3.0 EV (Hero 3+ Only) + + + + -2.5 EV (Hero 3+ Only) + + + + -2.0 EV + + + + -1.5 EV + + + + -1.0 EV + + + + -0.5 EV + + + + 0.0 EV + + + + +0.5 EV + + + + +1.0 EV + + + + +1.5 EV + + + + +2.0 EV + + + + +2.5 EV (Hero 3+ Only) + + + + +3.0 EV (Hero 3+ Only) + + + + +3.5 EV (Hero 3+ Only) + + + + +4.0 EV (Hero 3+ Only) + + + + +4.5 EV (Hero 3+ Only) + + + + +5.0 EV (Hero 3+ Only) + + + + + + Charging disabled + + + + Charging enabled + + + + + + Unknown gopro model + + + + Hero 3+ Silver (HeroBus not supported by GoPro) + + + + Hero 3+ Black + + + + Hero 4 Silver + + + + Hero 4 Black + + + + + + 3 Shots / 1 Second + + + + 5 Shots / 1 Second + + + + 10 Shots / 1 Second + + + + 10 Shots / 2 Second + + + + 10 Shots / 3 Second (Hero 4 Only) + + + + 30 Shots / 1 Second + + + + 30 Shots / 2 Second + + + + 30 Shots / 3 Second + + + + 30 Shots / 6 Second + + + + + + + LED patterns off (return control to regular vehicle control) + + + + LEDs show pattern during firmware update + + + + Custom Pattern using custom bytes fields + + + + + + Flags in EKF_STATUS message + + set if EKF's attitude estimate is good + + + + set if EKF's horizontal velocity estimate is good + + + + set if EKF's vertical velocity estimate is good + + + + set if EKF's horizontal position (relative) estimate is good + + + + set if EKF's horizontal position (absolute) estimate is good + + + + set if EKF's vertical position (absolute) estimate is good + + + + set if EKF's vertical position (above ground) estimate is good + + + + EKF is in constant position mode and does not know it's absolute or relative position + + + + set if EKF's predicted horizontal position (relative) estimate is good + + + + set if EKF's predicted horizontal position (absolute) estimate is good + + + + + + + + + + + + + + + + + + + + + + Special ACK block numbers control activation of dataflash log streaming + + + + UAV to stop sending DataFlash blocks + + + + + UAV to start sending DataFlash blocks + + + + + + + Possible remote log data block statuses + + This block has NOT been received + + + + This block has been received + + + + + + + Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process. + magnetometer X offset + magnetometer Y offset + magnetometer Z offset + magnetic declination (radians) + raw pressure from barometer + raw temperature from barometer + gyro X calibration + gyro Y calibration + gyro Z calibration + accel X calibration + accel Y calibration + accel Z calibration + + + + Deprecated. Use MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS instead. Set the magnetometer offsets + System ID + Component ID + magnetometer X offset + magnetometer Y offset + magnetometer Z offset + + + + state of APM memory + heap top + free memory + + + + raw ADC output + ADC output 1 + ADC output 2 + ADC output 3 + ADC output 4 + ADC output 5 + ADC output 6 + + + + + Configure on-board Camera Control System. + System ID + Component ID + Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) + Divisor number //e.g. 1000 means 1/1000 (0 means ignore) + F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) + ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) + Exposure type enumeration from 1 to N (0 means ignore) + Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + Extra parameters enumeration (0 means ignore) + Correspondent value to given extra_param + + + + Control on-board Camera Control System to take shots. + System ID + Component ID + 0: stop, 1: start or keep it up //Session control e.g. show/hide lens + 1 to N //Zoom's absolute position (0 means ignore) + -100 to 100 //Zooming step value to offset zoom from the current position + 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus + 0: ignore, 1: shot or start filming + Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once + Extra parameters enumeration (0 means ignore) + Correspondent value to given extra_param + + + + + Message to configure a camera mount, directional antenna, etc. + System ID + Component ID + mount operating mode (see MAV_MOUNT_MODE enum) + (1 = yes, 0 = no) + (1 = yes, 0 = no) + (1 = yes, 0 = no) + + + + Message to control a camera mount, directional antenna, etc. + System ID + Component ID + pitch(deg*100) or lat, depending on mount mode + roll(deg*100) or lon depending on mount mode + yaw(deg*100) or alt (in cm) depending on mount mode + if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) + + + + Message with some status from APM to GCS about camera or antenna mount + System ID + Component ID + pitch(deg*100) + roll(deg*100) + yaw(deg*100) + + + + + A fence point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS + System ID + Component ID + point index (first point is 1, 0 is for return point) + total number of points (for sanity checking) + Latitude of point + Longitude of point + + + + Request a current fence point from MAV + System ID + Component ID + point index (first point is 1, 0 is for return point) + + + + Status of geo-fencing. Sent in extended status stream when fencing enabled + 0 if currently inside fence, 1 if outside + number of fence breaches + last breach type (see FENCE_BREACH_* enum) + time of last breach in milliseconds since boot + + + + Status of DCM attitude estimator + X gyro drift estimate rad/s + Y gyro drift estimate rad/s + Z gyro drift estimate rad/s + average accel_weight + average renormalisation value + average error_roll_pitch value + average error_yaw value + + + + Status of simulation environment, if used + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + X acceleration m/s/s + Y acceleration m/s/s + Z acceleration m/s/s + Angular speed around X axis rad/s + Angular speed around Y axis rad/s + Angular speed around Z axis rad/s + Latitude in degrees * 1E7 + Longitude in degrees * 1E7 + + + + Status of key hardware + board voltage (mV) + I2C error count + + + + Status generated by radio + local signal strength + remote signal strength + how full the tx buffer is as a percentage + background noise level + remote background noise level + receive errors + count of error corrected packets + + + + + Status of AP_Limits. Sent in extended status stream when AP_Limits is enabled + state of AP_Limits, (see enum LimitState, LIMITS_STATE) + time of last breach in milliseconds since boot + time of last recovery action in milliseconds since boot + time of last successful recovery in milliseconds since boot + time of last all-clear in milliseconds since boot + number of fence breaches + AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE) + AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE) + AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE) + + + + Wind estimation + wind direction that wind is coming from (degrees) + wind speed in ground plane (m/s) + vertical wind speed (m/s) + + + + Data packet, size 16 + data type + data length + raw data + + + + Data packet, size 32 + data type + data length + raw data + + + + Data packet, size 64 + data type + data length + raw data + + + + Data packet, size 96 + data type + data length + raw data + + + + Rangefinder reporting + distance in meters + raw voltage if available, zero otherwise + + + + Airspeed auto-calibration + GPS velocity north m/s + GPS velocity east m/s + GPS velocity down m/s + Differential pressure pascals + Estimated to true airspeed ratio + Airspeed ratio + EKF state x + EKF state y + EKF state z + EKF Pax + EKF Pby + EKF Pcz + + + + + A rally point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS + System ID + Component ID + point index (first point is 0) + total number of points (for sanity checking) + Latitude of point in degrees * 1E7 + Longitude of point in degrees * 1E7 + Transit / loiter altitude in meters relative to home + + Break altitude in meters relative to home + Heading to aim for when landing. In centi-degrees. + See RALLY_FLAGS enum for definition of the bitmask. + + + + Request a current rally point from MAV. MAV should respond with a RALLY_POINT message. MAV should not respond if the request is invalid. + System ID + Component ID + point index (first point is 0) + + + + Status of compassmot calibration + throttle (percent*10) + current (amps) + interference (percent) + Motor Compensation X + Motor Compensation Y + Motor Compensation Z + + + + + Status of secondary AHRS filter if available + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Altitude (MSL) + Latitude in degrees * 1E7 + Longitude in degrees * 1E7 + + + + + Camera Event + Image timestamp (microseconds since UNIX epoch, according to camera clock) + System ID + + Camera ID + + Image index + + See CAMERA_STATUS_TYPES enum for definition of the bitmask + Parameter 1 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + Parameter 2 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + Parameter 3 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + Parameter 4 (meaning depends on event, see CAMERA_STATUS_TYPES enum) + + + + + Camera Capture Feedback + Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB) + System ID + + Camera ID + + Image index + + Latitude in (deg * 1E7) + Longitude in (deg * 1E7) + Altitude Absolute (meters AMSL) + Altitude Relative (meters above HOME location) + Camera Roll angle (earth frame, degrees, +-180) + + Camera Pitch angle (earth frame, degrees, +-180) + + Camera Yaw (earth frame, degrees, 0-360, true) + + Focal Length (mm) + + See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask + + + + + 2nd Battery status + voltage in millivolts + Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + + + + Status of third AHRS filter if available. This is for ANU research group (Ali and Sean) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Altitude (MSL) + Latitude in degrees * 1E7 + Longitude in degrees * 1E7 + test variable1 + test variable2 + test variable3 + test variable4 + + + + Request the autopilot version from the system/component. + System ID + Component ID + + + + + Send a block of log data to remote location + System ID + Component ID + log data block sequence number + log data block + + + + Send Status of each log block that autopilot board might have sent + System ID + Component ID + log data block sequence number + log data block status + + + + Control vehicle LEDs + System ID + Component ID + Instance (LED instance to control or 255 for all LEDs) + Pattern (see LED_PATTERN_ENUM) + Custom Byte Length + Custom Bytes + + + + Reports progress of compass calibration. + Compass being calibrated + Bitmask of compasses being calibrated + Status (see MAG_CAL_STATUS enum) + Attempt number + Completion percentage + Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid) + Body frame direction vector for display + Body frame direction vector for display + Body frame direction vector for display + + + + Reports results of completed compass calibration. Sent until MAG_CAL_ACK received. + Compass being calibrated + Bitmask of compasses being calibrated + Status (see MAG_CAL_STATUS enum) + 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters + RMS milligauss residuals + X offset + Y offset + Z offset + X diagonal (matrix 11) + Y diagonal (matrix 22) + Z diagonal (matrix 33) + X off-diagonal (matrix 12 and 21) + Y off-diagonal (matrix 13 and 31) + Z off-diagonal (matrix 32 and 23) + + + + + EKF Status message including flags and variances + Flags + + Velocity variance + + Horizontal Position variance + Vertical Position variance + Compass variance + Terrain Altitude variance + + + + + PID tuning information + axis + desired rate (degrees/s) + achieved rate (degrees/s) + FF component + P component + I component + D component + + + + 3 axis gimbal mesuraments + System ID + Component ID + Time since last update (seconds) + Delta angle X (radians) + Delta angle Y (radians) + Delta angle X (radians) + Delta velocity X (m/s) + Delta velocity Y (m/s) + Delta velocity Z (m/s) + Joint ROLL (radians) + Joint EL (radians) + Joint AZ (radians) + + + + Control message for rate gimbal + System ID + Component ID + Demanded angular rate X (rad/s) + Demanded angular rate Y (rad/s) + Demanded angular rate Z (rad/s) + + + + 100 Hz gimbal torque command telemetry + System ID + Component ID + Roll Torque Command + Elevation Torque Command + Azimuth Torque Command + + + + + Heartbeat from a HeroBus attached GoPro + Status + Current capture mode + additional status bits + + + + + Request a GOPRO_COMMAND response from the GoPro + System ID + Component ID + Command ID + + + + Response from a GOPRO_COMMAND get request + Command ID + Status + Value + + + + Request to set a GOPRO_COMMAND with a desired + System ID + Component ID + Command ID + Value + + + + Response from a GOPRO_COMMAND set request + Command ID + Status + + + + + RPM sensor output + RPM Sensor1 + RPM Sensor2 + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/autoquad.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/autoquad.xml new file mode 100644 index 0000000..8c22478 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/autoquad.xml @@ -0,0 +1,169 @@ + + + common.xml + 3 + + + Track current version of these definitions (can be used by checking value of AUTOQUAD_MAVLINK_DEFS_VERSION_ENUM_END). Append a new entry for each published change. + + + + Available operating modes/statuses for AutoQuad flight controller. + Bitmask up to 32 bits. Low side bits for base modes, high side for + additional active features/modifiers/constraints. + + System is initializing + + + + System is *armed* and standing by, with no throttle input and no autonomous mode + + + Flying (throttle input detected), assumed under manual control unless other mode bits are set + + + Altitude hold engaged + + + Position hold engaged + + + Externally-guided (eg. GCS) navigation mode + + + Autonomous mission execution mode + + + + Ready but *not armed* + + + Calibration mode active + + + + No valid control input (eg. no radio link) + + + Battery is low (stage 1 warning) + + + Battery is depleted (stage 2 warning) + + + + Dynamic Velocity Hold is active (PH with proportional manual direction override) + + + ynamic Altitude Override is active (AH with proportional manual adjustment) + + + + Craft is at ceiling altitude + + + Ceiling altitude is set + + + Heading-Free dynamic mode active + + + Heading-Free locked mode active + + + Automatic Return to Home is active + + + System is in failsafe recovery mode + + + + + Orbit a waypoint. + Orbit radius in meters + Loiter time in decimal seconds + Maximum horizontal speed in m/s + Desired yaw angle at waypoint + Latitude + Longitude + Altitude + + + Start/stop AutoQuad telemetry values stream. + Start or stop (1 or 0) + Stream frequency in us + Dataset ID (refer to aq_mavlink.h::mavlinkCustomDataSets enum in AQ flight controller code) + Empty + Empty + Empty + Empty + + + + Request AutoQuad firmware version number. + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + + + + Motor/ESC telemetry data. + + + + + + Sends up to 20 raw float values. + Index of message + value1 + value2 + value3 + value4 + value5 + value6 + value7 + value8 + value9 + value10 + value11 + value12 + value13 + value14 + value15 + value16 + value17 + value18 + value19 + value20 + + + Sends ESC32 telemetry data for up to 4 motors. Multiple messages may be sent in sequence when system has > 4 motors. Data is described as follows: + // unsigned int state : 3; + // unsigned int vin : 12; // x 100 + // unsigned int amps : 14; // x 100 + // unsigned int rpm : 15; + // unsigned int duty : 8; // x (255/100) + // - Data Version 2 - + // unsigned int errors : 9; // Bad detects error count + // - Data Version 3 - + // unsigned int temp : 9; // (Deg C + 32) * 4 + // unsigned int errCode : 3; + + Timestamp of the component clock since boot time in ms. + Sequence number of message (first set of 4 motors is #1, next 4 is #2, etc). + Total number of active ESCs/motors on the system. + Number of active ESCs in this sequence (1 through this many array members will be populated with data) + ESC/Motor ID + Age of each ESC telemetry reading in ms compared to boot time. A value of 0xFFFF means timeout/no data. + Version of data structure (determines contents). + Data bits 1-32 for each ESC. + Data bits 33-64 for each ESC. + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/common.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/common.xml new file mode 100644 index 0000000..7b043aa --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/common.xml @@ -0,0 +1,3440 @@ + + + 3 + + + Micro air vehicle / autopilot classes. This identifies the individual model. + + Generic autopilot, full support for everything + + + Reserved for future use. + + + SLUGS autopilot, http://slugsuav.soe.ucsc.edu + + + ArduPilotMega / ArduCopter, http://diydrones.com + + + OpenPilot, http://openpilot.org + + + Generic autopilot only supporting simple waypoints + + + Generic autopilot supporting waypoints and other simple navigation commands + + + Generic autopilot supporting the full mission command set + + + No valid autopilot, e.g. a GCS or other MAVLink component + + + PPZ UAV - http://nongnu.org/paparazzi + + + UAV Dev Board + + + FlexiPilot + + + PX4 Autopilot - http://pixhawk.ethz.ch/px4/ + + + SMACCMPilot - http://smaccmpilot.org + + + AutoQuad -- http://autoquad.org + + + Armazila -- http://armazila.com + + + Aerob -- http://aerob.ru + + + ASLUAV autopilot -- http://www.asl.ethz.ch + + + + + Generic micro air vehicle. + + + Fixed wing aircraft. + + + Quadrotor + + + Coaxial helicopter + + + Normal helicopter with tail rotor. + + + Ground installation + + + Operator control unit / ground control station + + + Airship, controlled + + + Free balloon, uncontrolled + + + Rocket + + + Ground rover + + + Surface vessel, boat, ship + + + Submarine + + + Hexarotor + + + Octorotor + + + Octorotor + + + Flapping wing + + + Flapping wing + + + Onboard companion controller + + + Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. + + + Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. + + + Tiltrotor VTOL + + + + VTOL reserved 2 + + + VTOL reserved 3 + + + VTOL reserved 4 + + + VTOL reserved 5 + + + Onboard gimbal + + + Onboard ADSB peripheral + + + + These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65. + + development release + + + alpha release + + + beta release + + + release candidate + + + official stable release + + + + + These flags encode the MAV mode. + + 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. + + + 0b01000000 remote control input is enabled. + + + 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. + + + 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. + + + 0b00001000 guided mode enabled, system flies MISSIONs / mission items. + + + 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. + + + 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. + + + 0b00000001 Reserved for future use. + + + + These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. + + First bit: 10000000 + + + Second bit: 01000000 + + + Third bit: 00100000 + + + Fourth bit: 00010000 + + + Fifth bit: 00001000 + + + Sixt bit: 00000100 + + + Seventh bit: 00000010 + + + Eighth bit: 00000001 + + + + Override command, pauses current mission execution and moves immediately to a position + + Hold at the current position. + + + Continue with the next item in mission execution. + + + Hold at the current position of the system + + + Hold at the position specified in the parameters of the DO_HOLD action + + + + These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it + simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. + + System is not ready to fly, booting, calibrating, etc. No flag is set. + + + System is allowed to be active, under assisted RC control. + + + System is allowed to be active, under assisted RC control. + + + System is allowed to be active, under manual (RC) control, no stabilization + + + System is allowed to be active, under manual (RC) control, no stabilization + + + System is allowed to be active, under autonomous control, manual setpoint + + + System is allowed to be active, under autonomous control, manual setpoint + + + System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) + + + System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) + + + UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. + + + UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. + + + + + Uninitialized system, state is unknown. + + + System is booting up. + + + System is calibrating and not flight-ready. + + + System is grounded and on standby. It can be launched any time. + + + System is active and might be already airborne. Motors are engaged. + + + System is in a non-normal flight mode. It can however still navigate. + + + System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. + + + System just initialized its power-down sequence, will shut down now. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + On Screen Display (OSD) devices for video links + + + Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol + + + + These encode the sensors whose status is sent as part of the SYS_STATUS message. + + 0x01 3D gyro + + + 0x02 3D accelerometer + + + 0x04 3D magnetometer + + + 0x08 absolute pressure + + + 0x10 differential pressure + + + 0x20 GPS + + + 0x40 optical flow + + + 0x80 computer vision position + + + 0x100 laser based position + + + 0x200 external ground truth (Vicon or Leica) + + + 0x400 3D angular rate control + + + 0x800 attitude stabilization + + + 0x1000 yaw position + + + 0x2000 z/altitude control + + + 0x4000 x/y position control + + + 0x8000 motor outputs / control + + + 0x10000 rc receiver + + + 0x20000 2nd 3D gyro + + + 0x40000 2nd 3D accelerometer + + + 0x80000 2nd 3D magnetometer + + + 0x100000 geofence + + + 0x200000 AHRS subsystem health + + + 0x400000 Terrain subsystem health + + + 0x800000 Motors are reversed + + + + + Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) + + + Local coordinate frame, Z-up (x: north, y: east, z: down). + + + NOT a coordinate frame, indicates a mission command. + + + Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. + + + Local coordinate frame, Z-down (x: east, y: north, z: up) + + + Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL) + + + Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location. + + + Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. + + + Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. + + + Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. + + + Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. + + + Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. + + + + + + + + + + + + + + + + + + + + + + + + + + Disable fenced mode + + + Switched to guided mode to return point (fence point 0) + + + Report fence breach, but don't take action + + + Switched to guided mode to return point (fence point 0) with manual throttle control + + + + + + No last fence breach + + + Breached minimum altitude + + + Breached maximum altitude + + + Breached fence boundary + + + + + Enumeration of possible mount operation modes + Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization + Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. + Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization + Load neutral position and start RC Roll,Pitch,Yaw control with stabilization + Load neutral position and start to point to Lat,Lon,Alt + + + Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. + + Navigate to MISSION. + Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing) + Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached) + 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. + Desired yaw angle at MISSION (rotary wing) + Latitude + Longitude + Altitude + + + Loiter around this MISSION an unlimited amount of time + Empty + Empty + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this MISSION for X turns + Turns + Empty + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle + Latitude + Longitude + Altitude + + + Loiter around this MISSION for X seconds + Seconds (decimal) + Empty + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle + Latitude + Longitude + Altitude + + + Return to launch location + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Land at location + Abort Alt + Empty + Empty + Desired yaw angle + Latitude + Longitude + Altitude + + + Takeoff from ground / hand + Minimum pitch (if airspeed sensor present), desired pitch without sensor + Empty + Empty + Yaw angle (if magnetometer present), ignored without magnetometer + Latitude + Longitude + Altitude + + + Land at local position (local frame only) + Landing target number (if available) + Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land + Landing descend rate [ms^-1] + Desired yaw angle [rad] + Y-axis position [m] + X-axis position [m] + Z-axis / ground level position [m] + + + Takeoff from local position (local frame only) + Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad] + Empty + Takeoff ascend rate [ms^-1] + Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these + Y-axis position [m] + X-axis position [m] + Z-axis position [m] + + + Vehicle following, i.e. this waypoint represents the position of a moving vehicle + Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation + Ground speed of vehicle to be followed + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. + Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. + Empty + Empty + Empty + Empty + Empty + Desired altitude in meters + + + Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. + Heading Required (0 = False) + Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter. + Empty + Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location + Latitude + Longitude + Altitude + + + Being following a target + System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode + RESERVED + RESERVED + altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home + altitude + RESERVED + TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout + + + Reposition the MAV after a follow target command has been sent + Camera q1 (where 0 is on the ray from the camera to the tracking device) + Camera q2 + Camera q3 + Camera q4 + altitude offset from target (m) + X offset from target (m) + Y offset from target (m) + + + Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. + Region of intereset mode. (see MAV_ROI enum) + MISSION index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple ROI's) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + + Control autonomous path planning on the MAV. + 0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning + 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid + Empty + Yaw angle at goal, in compass degrees, [0..360] + Latitude/X of goal + Longitude/Y of goal + Altitude/Z of goal + + + Navigate to MISSION using a spline path. + Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing) + Empty + Empty + Empty + Latitude/X of goal + Longitude/Y of goal + Altitude/Z of goal + + + Takeoff from ground using VTOL mode + Empty + Empty + Empty + Yaw angle in degrees + Latitude + Longitude + Altitude + + + Land using VTOL mode + Empty + Empty + Empty + Yaw angle in degrees + Latitude + Longitude + Altitude + + + + + + hand control over to an external controller + On / Off (> 0.5f on) + Empty + Empty + Empty + Empty + Empty + Empty + + + Delay the next navigation command a number of seconds or until a specified time + Delay in seconds (decimal, -1 to enable time-of-day fields) + hour (24h format, UTC, -1 to ignore) + minute (24h format, UTC, -1 to ignore) + second (24h format, UTC) + Empty + Empty + Empty + + + NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Delay mission state machine. + Delay in seconds (decimal) + Empty + Empty + Empty + Empty + Empty + Empty + + + Ascend/descend at rate. Delay mission state machine until desired altitude reached. + Descent / Ascend rate (m/s) + Empty + Empty + Empty + Empty + Empty + Finish Altitude + + + Delay mission state machine until within desired distance of next NAV point. + Distance (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + Reach a certain target angle. + target angle: [0-360], 0 is north + speed during yaw change:[deg per second] + direction: negative: counter clockwise, positive: clockwise [-1,1] + relative offset or absolute angle: [ 1,0] + Empty + Empty + Empty + + + NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Set system mode. + Mode, as defined by ENUM MAV_MODE + Custom mode - this is system specific, please refer to the individual autopilot specifications for details. + Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details. + Empty + Empty + Empty + Empty + + + Jump to the desired command in the mission list. Repeat this action only the specified number of times + Sequence number + Repeat count + Empty + Empty + Empty + Empty + Empty + + + Change speed and/or throttle set points. + Speed type (0=Airspeed, 1=Ground Speed) + Speed (m/s, -1 indicates no change) + Throttle ( Percent, -1 indicates no change) + absolute or relative [0,1] + Empty + Empty + Empty + + + Changes the home location either to the current location or a specified location. + Use current (1=use current location, 0=use specified location) + Empty + Empty + Empty + Latitude + Longitude + Altitude + + + Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. + Parameter number + Parameter value + Empty + Empty + Empty + Empty + Empty + + + Set a relay to a condition. + Relay number + Setting (1=on, 0=off, others possible depending on system hardware) + Empty + Empty + Empty + Empty + Empty + + + Cycle a relay on and off for a desired number of cyles with a desired period. + Relay number + Cycle count + Cycle time (seconds, decimal) + Empty + Empty + Empty + Empty + + + Set a servo to a desired PWM value. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Empty + Empty + Empty + Empty + Empty + + + Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Cycle count + Cycle time (seconds) + Empty + Empty + Empty + + + Terminate flight immediately + Flight termination activated if > 0.5 + Empty + Empty + Empty + Empty + Empty + Empty + + + Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. + Empty + Empty + Empty + Empty + Latitude + Longitude + Empty + + + Mission command to perform a landing from a rally point. + Break altitude (meters) + Landing speed (m/s) + Empty + Empty + Empty + Empty + Empty + + + Mission command to safely abort an autonmous landing. + Altitude (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Reposition the vehicle to a specific WGS84 global position. + Ground speed, less than 0 (-1) for default + Bitmask of option flags, see the MAV_DO_REPOSITION_FLAGS enum. + Reserved + Yaw heading, NaN for unchanged. For planes indicates loiter direction (0: clockwise, 1: counter clockwise) + Latitude (deg * 1E7) + Longitude (deg * 1E7) + Altitude (meters) + + + If in a GPS controlled position mode, hold the current position or continue. + 0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + Control onboard camera system. + Camera ID (-1 for all) + Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw + Transmission mode: 0: video stream, >0: single images every n seconds (decimal) + Recording: 0: disabled, 1: enabled compressed, 2: enabled raw + Empty + Empty + Empty + + + Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. + Region of intereset mode. (see MAV_ROI enum) + MISSION index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple ROI's) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + + + + Mission command to configure an on-board camera controller system. + Modes: P, TV, AV, M, Etc + Shutter speed: Divisor number for one second + Aperture: F stop number + ISO number e.g. 80, 100, 200, Etc + Exposure type enumerator + Command Identity + Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) + + + + Mission command to control an on-board camera controller system. + Session control e.g. show/hide lens + Zoom's absolute position + Zooming step value to offset zoom from the current position + Focus Locking, Unlocking or Re-locking + Shooting Command + Command Identity + Empty + + + + + Mission command to configure a camera or antenna mount + Mount operation mode (see MAV_MOUNT_MODE enum) + stabilize roll? (1 = yes, 0 = no) + stabilize pitch? (1 = yes, 0 = no) + stabilize yaw? (1 = yes, 0 = no) + Empty + Empty + Empty + + + + Mission command to control a camera or antenna mount + pitch or lat in degrees, depending on mount mode. + roll or lon in degrees depending on mount mode + yaw or alt (in meters) depending on mount mode + reserved + reserved + reserved + MAV_MOUNT_MODE enum value + + + + Mission command to set CAM_TRIGG_DIST for this flight + Camera trigger distance (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to enable the geofence + enable? (0=disable, 1=enable, 2=disable_floor_only) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to trigger a parachute + action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Change to/from inverted flight + inverted (0=normal, 1=inverted) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to control a camera or antenna mount, using a quaternion as reference. + q1 - quaternion param #1, w (1 in null-rotation) + q2 - quaternion param #2, x (0 in null-rotation) + q3 - quaternion param #3, y (0 in null-rotation) + q4 - quaternion param #4, z (0 in null-rotation) + Empty + Empty + Empty + + + + set id of master controller + System ID + Component ID + Empty + Empty + Empty + Empty + Empty + + + + set limits for external control + timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout + absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit + absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit + horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit + Empty + Empty + Empty + + + + NOP - This command is only used to mark the upper limit of the DO commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Trigger calibration. This command will be only accepted if in pre-flight mode. + Gyro calibration: 0: no, 1: yes + Magnetometer calibration: 0: no, 1: yes + Ground pressure: 0: no, 1: yes + Radio calibration: 0: no, 1: yes + Accelerometer calibration: 0: no, 1: yes + Compass/Motor interference calibration: 0: no, 1: yes + Empty + + + Set sensor offsets. This command will be only accepted if in pre-flight mode. + Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer + X axis offset (or generic dimension 1), in the sensor's raw units + Y axis offset (or generic dimension 2), in the sensor's raw units + Z axis offset (or generic dimension 3), in the sensor's raw units + Generic dimension 4, in the sensor's raw units + Generic dimension 5, in the sensor's raw units + Generic dimension 6, in the sensor's raw units + + + Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. + 1: Trigger actuator ID assignment and direction mapping. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. + Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults + Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults + Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging) + Reserved + Empty + Empty + Empty + + + Request the reboot or shutdown of system components. + 0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded. + 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded. + Reserved, send 0 + Reserved, send 0 + Reserved, send 0 + Reserved, send 0 + Reserved, send 0 + + + Hold / continue the current action + MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan + MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position + MAV_FRAME coordinate frame of hold point + Desired yaw angle in degrees + Latitude / X position + Longitude / Y position + Altitude / Z position + + + start running a mission + first_item: the first mission item to run + last_item: the last mission item to run (after this item is run, the mission ends) + + + Arms / Disarms a component + 1 to arm, 0 to disarm + + + Request the home position from the vehicle. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + Starts receiver pairing + 0:Spektrum + 0:Spektrum DSM2, 1:Spektrum DSMX + + + Request the interval between messages for a particular MAVLink message ID + The MAVLink message ID + + + Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM + The MAVLink message ID + The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate. + + + Request autopilot capabilities + 1: Request autopilot version + Reserved (all remaining params) + + + Start image capture sequence + Duration between two consecutive pictures (in seconds) + Number of images to capture total - 0 for unlimited capture + Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc) + + + + Stop image capture sequence + Reserved + Reserved + + + + Enable or disable on-board camera triggering system. + Trigger enable/disable (0 for disable, 1 for start) + Shutter integration time (in ms) + Reserved + + + + Starts video capture + Camera ID (0 for all cameras), 1 for first, 2 for second, etc. + Frames per second + Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc) + + + + Stop the current video capture + Reserved + Reserved + + + + Create a panorama at the current position + Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle) + Viewing angle vertical of panorama (in degrees) + Speed of the horizontal rotation (in degrees per second) + Speed of the vertical rotation (in degrees per second) + + + + Request VTOL transition + The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used. + + + + + + + Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. + Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list. + Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will. + Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will. + Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will. + Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT + Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT + Altitude, in meters AMSL + + + Control the payload deployment. + Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests. + Reserved + Reserved + Reserved + Reserved + Reserved + Reserved + + + + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined waypoint item. Ground Station will show the Vehicle as flying through this item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. + User defined + User defined + User defined + User defined + Latitude unscaled + Longitude unscaled + Altitude, in meters AMSL + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. + User defined + User defined + User defined + User defined + User defined + User defined + User defined + + + + + THIS INTERFACE IS DEPRECATED AS OF JULY 2015. Please use MESSAGE_INTERVAL instead. A data stream is not a fixed set of messages, but rather a + recommendation to the autopilot software. Individual autopilots may or may not obey + the recommended messages. + + Enable all data streams + + + Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. + + + Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS + + + Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW + + + Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. + + + Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. + + + Dependent on the autopilot + + + Dependent on the autopilot + + + Dependent on the autopilot + + + + The ROI (region of interest) for the vehicle. This can be + be used by the vehicle for camera/vehicle attitude alignment (see + MAV_CMD_NAV_ROI). + + No region of interest. + + + Point toward next MISSION. + + + Point toward given MISSION. + + + Point toward fixed location. + + + Point toward of given id. + + + + ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. + + Command / mission item is ok. + + + Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. + + + The system is refusing to accept this command from this source / communication partner. + + + Command or mission item is not supported, other commands would be accepted. + + + The coordinate frame of this command / mission item is not supported. + + + The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. + + + The X or latitude value is out of range. + + + The Y or longitude value is out of range. + + + The Z or altitude value is out of range. + + + + Specifies the datatype of a MAVLink parameter. + + 8-bit unsigned integer + + + 8-bit signed integer + + + 16-bit unsigned integer + + + 16-bit signed integer + + + 32-bit unsigned integer + + + 32-bit signed integer + + + 64-bit unsigned integer + + + 64-bit signed integer + + + 32-bit floating-point + + + 64-bit floating-point + + + + result from a mavlink command + + Command ACCEPTED and EXECUTED + + + Command TEMPORARY REJECTED/DENIED + + + Command PERMANENTLY DENIED + + + Command UNKNOWN/UNSUPPORTED + + + Command executed, but failed + + + + result in a mavlink mission ack + + mission accepted OK + + + generic error / not accepting mission commands at all right now + + + coordinate frame is not supported + + + command is not supported + + + mission item exceeds storage space + + + one of the parameters has an invalid value + + + param1 has an invalid value + + + param2 has an invalid value + + + param3 has an invalid value + + + param4 has an invalid value + + + x/param5 has an invalid value + + + y/param6 has an invalid value + + + param7 has an invalid value + + + received waypoint out of sequence + + + not accepting any mission commands from this communication partner + + + + Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. + + System is unusable. This is a "panic" condition. + + + Action should be taken immediately. Indicates error in non-critical systems. + + + Action must be taken immediately. Indicates failure in a primary system. + + + Indicates an error in secondary/redundant systems. + + + Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. + + + An unusual event has occured, though not an error condition. This should be investigated for the root cause. + + + Normal operational messages. Useful for logging. No action is required for these messages. + + + Useful non-operational messages that can assist in debugging. These should not occur during normal operation. + + + + Power supply status flags (bitmask) + + main brick power supply valid + + + main servo power supply valid for FMU + + + USB power is connected + + + peripheral supply is in over-current state + + + hi-power peripheral supply is in over-current state + + + Power status has changed since boot + + + + SERIAL_CONTROL device types + + First telemetry port + + + Second telemetry port + + + First GPS port + + + Second GPS port + + + system shell + + + + SERIAL_CONTROL flags (bitmask) + + Set if this is a reply + + + Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message + + + Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set + + + Block on writes to the serial port + + + Send multiple replies until port is drained + + + + Enumeration of distance sensor types + + Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units + + + Ultrasound rangefinder, e.g. MaxBotix units + + + Infrared rangefinder, e.g. Sharp units + + + + Enumeration of sensor orientation, according to its rotations + + Roll: 0, Pitch: 0, Yaw: 0 + + + Roll: 0, Pitch: 0, Yaw: 45 + + + Roll: 0, Pitch: 0, Yaw: 90 + + + Roll: 0, Pitch: 0, Yaw: 135 + + + Roll: 0, Pitch: 0, Yaw: 180 + + + Roll: 0, Pitch: 0, Yaw: 225 + + + Roll: 0, Pitch: 0, Yaw: 270 + + + Roll: 0, Pitch: 0, Yaw: 315 + + + Roll: 180, Pitch: 0, Yaw: 0 + + + Roll: 180, Pitch: 0, Yaw: 45 + + + Roll: 180, Pitch: 0, Yaw: 90 + + + Roll: 180, Pitch: 0, Yaw: 135 + + + Roll: 0, Pitch: 180, Yaw: 0 + + + Roll: 180, Pitch: 0, Yaw: 225 + + + Roll: 180, Pitch: 0, Yaw: 270 + + + Roll: 180, Pitch: 0, Yaw: 315 + + + Roll: 90, Pitch: 0, Yaw: 0 + + + Roll: 90, Pitch: 0, Yaw: 45 + + + Roll: 90, Pitch: 0, Yaw: 90 + + + Roll: 90, Pitch: 0, Yaw: 135 + + + Roll: 270, Pitch: 0, Yaw: 0 + + + Roll: 270, Pitch: 0, Yaw: 45 + + + Roll: 270, Pitch: 0, Yaw: 90 + + + Roll: 270, Pitch: 0, Yaw: 135 + + + Roll: 0, Pitch: 90, Yaw: 0 + + + Roll: 0, Pitch: 270, Yaw: 0 + + + Roll: 0, Pitch: 180, Yaw: 90 + + + Roll: 0, Pitch: 180, Yaw: 270 + + + Roll: 90, Pitch: 90, Yaw: 0 + + + Roll: 180, Pitch: 90, Yaw: 0 + + + Roll: 270, Pitch: 90, Yaw: 0 + + + Roll: 90, Pitch: 180, Yaw: 0 + + + Roll: 270, Pitch: 180, Yaw: 0 + + + Roll: 90, Pitch: 270, Yaw: 0 + + + Roll: 180, Pitch: 270, Yaw: 0 + + + Roll: 270, Pitch: 270, Yaw: 0 + + + Roll: 90, Pitch: 180, Yaw: 90 + + + Roll: 90, Pitch: 0, Yaw: 270 + + + Roll: 315, Pitch: 315, Yaw: 315 + + + + Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability. + + Autopilot supports MISSION float message type. + + + Autopilot supports the new param float message type. + + + Autopilot supports MISSION_INT scaled integer message type. + + + Autopilot supports COMMAND_INT scaled integer message type. + + + Autopilot supports the new param union message type. + + + Autopilot supports the new FILE_TRANSFER_PROTOCOL message type. + + + Autopilot supports commanding attitude offboard. + + + Autopilot supports commanding position and velocity targets in local NED frame. + + + Autopilot supports commanding position and velocity targets in global scaled integers. + + + Autopilot supports terrain protocol / data handling. + + + Autopilot supports direct actuator control. + + + Autopilot supports the flight termination command. + + + Autopilot supports onboard compass calibration. + + + + Enumeration of estimator types + + This is a naive estimator without any real covariance feedback. + + + Computer vision based estimate. Might be up to scale. + + + Visual-inertial estimate. + + + Plain GPS estimate. + + + Estimator integrating GPS and inertial sensing. + + + + Enumeration of battery types + + Not specified. + + + Lithium polymer battery + + + Lithium-iron-phosphate battery + + + Lithium-ION battery + + + Nickel metal hydride battery + + + + Enumeration of battery functions + + Battery function is unknown + + + Battery supports all flight systems + + + Battery for the propulsion system + + + Avionics battery + + + Payload battery + + + + Enumeration of VTOL states + + MAV is not configured as VTOL + + + VTOL is in transition from multicopter to fixed-wing + + + VTOL is in transition from fixed-wing to multicopter + + + VTOL is in multicopter state + + + VTOL is in fixed-wing state + + + + Enumeration of landed detector states + + MAV landed state is unknown + + + MAV is landed (on ground) + + + MAV is in air + + + + Enumeration of the ADSB altimeter types + + Altitude reported from a Baro source using QNH reference + + + Altitude reported from a GNSS source + + + + ADSB classification for the type of vehicle emitting the transponder signal + + + + + + + + + + + + + + + + + + + + + + + These flags indicate status such as data validity of each data source. Set = data valid + + + + + + + + + + Bitmask of options for the MAV_CMD_DO_REPOSITION + + The aircraft should immediately transition into guided. This should not be set for follow me applications + + + + + Flags in EKF_STATUS message + + True if the attitude estimate is good + + + + True if the horizontal velocity estimate is good + + + + True if the vertical velocity estimate is good + + + + True if the horizontal position (relative) estimate is good + + + + True if the horizontal position (absolute) estimate is good + + + + True if the vertical position (absolute) estimate is good + + + + True if the vertical position (above ground) estimate is good + + + + True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) + + + + True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate + + + + True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate + + + + True if the EKF has detected a GPS glitch + + + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Autopilot type / class. defined in MAV_AUTOPILOT ENUM + System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h + A bitfield for use for autopilot-specific flags. + System status flag, see MAV_STATE ENUM + MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version + + + The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout. + Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR + Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + Battery voltage, in millivolts (1 = 1 millivolt) + Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + Autopilot-specific errors + Autopilot-specific errors + Autopilot-specific errors + Autopilot-specific errors + + + The system time is the time of the master clock, typically the computer clock of the main onboard computer. + Timestamp of the master clock in microseconds since UNIX epoch. + Timestamp of the component clock since boot time in milliseconds. + + + + A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. + Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009) + PING sequence + 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + + + Request to control this MAV + System the GCS requests control for + 0: request control of this MAV, 1: Release control of this MAV + 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + + + Accept / deny control of this MAV + ID of the GCS this message + 0: request control of this MAV, 1: Release control of this MAV + 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + + + Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety. + key + + + THIS INTERFACE IS DEPRECATED. USE COMMAND_LONG with MAV_CMD_DO_SET_MODE INSTEAD. Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. + The system setting the mode + The new base mode + The new autopilot-specific mode. This field can be ignored by an autopilot. + + + + Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code. + System ID + Component ID + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) + + + Request all parameters of this component. After his request, all parameters are emitted. + System ID + Component ID + + + Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Onboard parameter value + Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + Total number of onboard parameters + Index of this onboard parameter + + + Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message. + System ID + Component ID + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Onboard parameter value + Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. + + + The global position, as returned by the Global Positioning System (GPS). This is + NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude. + GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX + GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX + GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + Number of satellites visible. If unknown, set to 255 + + + The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites. + Number of satellites visible + Global satellite ID + 0: Satellite not used, 1: used for localization + Elevation (0: right on top of receiver, 90: on the horizon) of satellite + Direction of satellite, 0: 0 deg, 255: 360 deg. + Signal to noise ratio of satellite + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (milliseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X acceleration (raw) + Y acceleration (raw) + Z acceleration (raw) + Angular speed around X axis (raw) + Angular speed around Y axis (raw) + Angular speed around Z axis (raw) + X Magnetic field (raw) + Y Magnetic field (raw) + Z Magnetic field (raw) + + + The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Absolute pressure (raw) + Differential pressure 1 (raw, 0 if nonexistant) + Differential pressure 2 (raw, 0 if nonexistant) + Raw Temperature measurement (raw) + + + The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. + Timestamp (milliseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). + Timestamp (milliseconds since system boot) + Roll angle (rad, -pi..+pi) + Pitch angle (rad, -pi..+pi) + Yaw angle (rad, -pi..+pi) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). + Timestamp (milliseconds since system boot) + Quaternion component 1, w (1 in null-rotation) + Quaternion component 2, x (0 in null-rotation) + Quaternion component 3, y (0 in null-rotation) + Quaternion component 4, z (0 in null-rotation) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + + + The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + Timestamp (milliseconds since system boot) + X Position + Y Position + Z Position + X Speed + Y Speed + Z Speed + + + The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the resolution of float is not sufficient. + Timestamp (milliseconds since system boot) + Latitude, expressed as degrees * 1E7 + Longitude, expressed as degrees * 1E7 + Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well) + Altitude above ground in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude, positive north), expressed as m/s * 100 + Ground Y Speed (Longitude, positive east), expressed as m/s * 100 + Ground Z Speed (Altitude, positive down), expressed as m/s * 100 + Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + + + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX. + Timestamp (milliseconds since system boot) + Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + + + The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + Timestamp (milliseconds since system boot) + Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. + RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + + + The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. + Timestamp (microseconds since system boot) + Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + Servo output 1 value, in microseconds + Servo output 2 value, in microseconds + Servo output 3 value, in microseconds + Servo output 4 value, in microseconds + Servo output 5 value, in microseconds + Servo output 6 value, in microseconds + Servo output 7 value, in microseconds + Servo output 8 value, in microseconds + + + Request a partial list of mission items from the system/component. http://qgroundcontrol.org/mavlink/waypoint_protocol. If start and end index are the same, just send one waypoint. + System ID + Component ID + Start index, 0 by default + End index, -1 by default (-1: send list to end). Else a valid index of the list + + + This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED! + System ID + Component ID + Start index, 0 by default and smaller / equal to the largest index of the current onboard list. + End index, equal or greater than start index. + + + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See also http://qgroundcontrol.org/mavlink/waypoint_protocol. + System ID + Component ID + Sequence + The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1, see MAV_CMD enum + PARAM2, see MAV_CMD enum + PARAM3, see MAV_CMD enum + PARAM4, see MAV_CMD enum + PARAM5 / local: x position, global: latitude + PARAM6 / y position: global: longitude + PARAM7 / z position: global: altitude (relative or absolute, depending on frame. + + + Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. http://qgroundcontrol.org/mavlink/waypoint_protocol + System ID + Component ID + Sequence + + + Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between). + System ID + Component ID + Sequence + + + Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item. + Sequence + + + Request the overall list of mission items from the system/component. + System ID + Component ID + + + This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of MISSIONs. + System ID + Component ID + Number of mission items in the sequence + + + Delete all mission items at once. + System ID + Component ID + + + A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next MISSION. + Sequence + + + Ack message during MISSION handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). + System ID + Component ID + See MAV_MISSION_RESULT enum + + + As local waypoints exist, the global MISSION reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor. + System ID + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84, in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + + + Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + + + Bind a RC channel to a parameter. The parameter should change accoding to the RC channel value. + System ID + Component ID + Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string + Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. + Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC. + Initial parameter value + Scale, maps the RC range [-1, 1] to a parameter value + Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) + Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) + + + Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. http://qgroundcontrol.org/mavlink/waypoint_protocol + System ID + Component ID + Sequence + + + Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/MISSIONs to accept and which to reject. Safety areas are often enforced by national or competition regulations. + System ID + Component ID + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + Read out the safety zone the MAV currently assumes. + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). + Timestamp (milliseconds since system boot) + Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + Attitude covariance + + + The state of the fixed wing navigation and position controller. + Current desired roll in degrees + Current desired pitch in degrees + Current desired heading in degrees + Bearing to current MISSION/target in degrees + Distance to active MISSION in meters + Current altitude error in meters + Current airspeed error in meters/second + Current crosstrack error on x-y plane in meters + + + The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset. + Timestamp (milliseconds since system boot) + Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + Class id of the estimator this estimate originated from. + Latitude, expressed as degrees * 1E7 + Longitude, expressed as degrees * 1E7 + Altitude in meters, expressed as * 1000 (millimeters), above MSL + Altitude above ground in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s + Ground Y Speed (Longitude), expressed as m/s + Ground Z Speed (Altitude), expressed as m/s + Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) + + + The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp + Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver. + Class id of the estimator this estimate originated from. + X Position + Y Position + Z Position + X Speed (m/s) + Y Speed (m/s) + Z Speed (m/s) + X Acceleration (m/s^2) + Y Acceleration (m/s^2) + Z Acceleration (m/s^2) + Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) + + + The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + Timestamp (milliseconds since system boot) + Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. + RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. + + + THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD. + The target requested to send the message stream. + The target requested to send the message stream. + The ID of the requested data stream + The requested message rate + 1 to start sending, 0 to stop sending. + + + THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD. + The ID of the requested data stream + The message rate + 1 stream is enabled, 0 stream is stopped. + + + This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled an buttons are also transmit as boolean values of their + The system to be controlled. + X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. + Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. + Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. + R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. + A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. + + + The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of UINT16_MAX means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + System ID + Component ID + RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. + + + Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See alsohttp://qgroundcontrol.org/mavlink/waypoint_protocol. + System ID + Component ID + Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). + The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1, see MAV_CMD enum + PARAM2, see MAV_CMD enum + PARAM3, see MAV_CMD enum + PARAM4, see MAV_CMD enum + PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 + PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + + + Metrics typically displayed on a HUD for fixed wing aircraft + Current airspeed in m/s + Current ground speed in m/s + Current heading in degrees, in compass units (0..360, 0=north) + Current throttle setting in integer percent, 0 to 100 + Current altitude (MSL), in meters + Current climb rate in meters/second + + + Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value. + System ID + Component ID + The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h + The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1, see MAV_CMD enum + PARAM2, see MAV_CMD enum + PARAM3, see MAV_CMD enum + PARAM4, see MAV_CMD enum + PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 + PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 + PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. + + + Send a command with up to seven parameters to the MAV + System which should execute the command + Component which should execute the command, 0 for all components + Command ID, as defined by MAV_CMD enum. + 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + Parameter 1, as defined by MAV_CMD enum. + Parameter 2, as defined by MAV_CMD enum. + Parameter 3, as defined by MAV_CMD enum. + Parameter 4, as defined by MAV_CMD enum. + Parameter 5, as defined by MAV_CMD enum. + Parameter 6, as defined by MAV_CMD enum. + Parameter 7, as defined by MAV_CMD enum. + + + Report status of a command. Includes feedback wether the command was executed. + Command ID, as defined by MAV_CMD enum. + See MAV_RESULT enum + + + Setpoint in roll, pitch, yaw and thrust from the operator + Timestamp in milliseconds since system boot + Desired roll rate in radians per second + Desired pitch rate in radians per second + Desired yaw rate in radians per second + Collective thrust, normalized to 0 .. 1 + Flight mode switch position, 0.. 255 + Override mode switch position, 0.. 255 + + + Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system). + Timestamp in milliseconds since system boot + System ID + Component ID + Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude + Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + Body roll rate in radians per second + Body roll rate in radians per second + Body roll rate in radians per second + Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + + + Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way. + Timestamp in milliseconds since system boot + Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude + Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + Body roll rate in radians per second + Body roll rate in radians per second + Body roll rate in radians per second + Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + + + Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system). + Timestamp in milliseconds since system boot + System ID + Component ID + Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in NED frame in meters + Y Position in NED frame in meters + Z Position in NED frame in meters (note, altitude is negative in NED) + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way. + Timestamp in milliseconds since system boot + Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in NED frame in meters + Y Position in NED frame in meters + Z Position in NED frame in meters (note, altitude is negative in NED) + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system). + Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + System ID + Component ID + Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in WGS84 frame in 1e7 * meters + Y Position in WGS84 frame in 1e7 * meters + Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way. + Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 + Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate + X Position in WGS84 frame in 1e7 * meters + Y Position in WGS84 frame in 1e7 * meters + Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT + X velocity in NED frame in meter / s + Y velocity in NED frame in meter / s + Z velocity in NED frame in meter / s + X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + yaw setpoint in rad + yaw rate setpoint in rad/s + + + The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + Timestamp (milliseconds since system boot) + X Position + Y Position + Z Position + Roll + Pitch + Yaw + + + DEPRECATED PACKET! Suffers from missing airspeed fields and singularities due to Euler angles. Please use HIL_STATE_QUATERNION instead. Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Body frame roll / phi angular speed (rad/s) + Body frame pitch / theta angular speed (rad/s) + Body frame yaw / psi angular speed (rad/s) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + + + Sent from autopilot to simulation. Hardware in the loop control outputs + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Control output -1 .. 1 + Control output -1 .. 1 + Control output -1 .. 1 + Throttle 0 .. 1 + Aux 1, -1 .. 1 + Aux 2, -1 .. 1 + Aux 3, -1 .. 1 + Aux 4, -1 .. 1 + System mode (MAV_MODE) + Navigation mode (MAV_NAV_MODE) + + + Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + RC channel 1 value, in microseconds + RC channel 2 value, in microseconds + RC channel 3 value, in microseconds + RC channel 4 value, in microseconds + RC channel 5 value, in microseconds + RC channel 6 value, in microseconds + RC channel 7 value, in microseconds + RC channel 8 value, in microseconds + RC channel 9 value, in microseconds + RC channel 10 value, in microseconds + RC channel 11 value, in microseconds + RC channel 12 value, in microseconds + Receive signal strength indicator, 0: 0%, 255: 100% + + + Optical flow from a flow sensor (e.g. optical mouse sensor) + Timestamp (UNIX) + Sensor ID + Flow in pixels * 10 in x-sensor direction (dezi-pixels) + Flow in pixels * 10 in y-sensor direction (dezi-pixels) + Flow in meters in x-sensor direction, angular-speed compensated + Flow in meters in y-sensor direction, angular-speed compensated + Optical flow quality / confidence. 0: bad, 255: maximum quality + Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X speed + Global Y speed + Global Z speed + + + Timestamp (microseconds, synced to UNIX time or since system boot) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + The IMU readings in SI units in NED body frame + Timestamp (microseconds, synced to UNIX time or since system boot) + X acceleration (m/s^2) + Y acceleration (m/s^2) + Z acceleration (m/s^2) + Angular speed around X axis (rad / sec) + Angular speed around Y axis (rad / sec) + Angular speed around Z axis (rad / sec) + X Magnetic field (Gauss) + Y Magnetic field (Gauss) + Z Magnetic field (Gauss) + Absolute pressure in millibar + Differential pressure in millibar + Altitude calculated from pressure + Temperature in degrees celsius + Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature + + + Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor) + Timestamp (microseconds, synced to UNIX time or since system boot) + Sensor ID + Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + RH rotation around X axis (rad) + RH rotation around Y axis (rad) + RH rotation around Z axis (rad) + Temperature * 100 in centi-degrees Celsius + Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + Time in microseconds since the distance was sampled. + Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + + + The IMU readings in SI units in NED body frame + Timestamp (microseconds, synced to UNIX time or since system boot) + X acceleration (m/s^2) + Y acceleration (m/s^2) + Z acceleration (m/s^2) + Angular speed around X axis in body frame (rad / sec) + Angular speed around Y axis in body frame (rad / sec) + Angular speed around Z axis in body frame (rad / sec) + X Magnetic field (Gauss) + Y Magnetic field (Gauss) + Z Magnetic field (Gauss) + Absolute pressure in millibar + Differential pressure (airspeed) in millibar + Altitude calculated from pressure + Temperature in degrees celsius + Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim. + + + + Status of simulation environment, if used + True attitude quaternion component 1, w (1 in null-rotation) + True attitude quaternion component 2, x (0 in null-rotation) + True attitude quaternion component 3, y (0 in null-rotation) + True attitude quaternion component 4, z (0 in null-rotation) + Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs + X acceleration m/s/s + Y acceleration m/s/s + Z acceleration m/s/s + Angular speed around X axis rad/s + Angular speed around Y axis rad/s + Angular speed around Z axis rad/s + Latitude in degrees + Longitude in degrees + Altitude in meters + Horizontal position standard deviation + Vertical position standard deviation + True velocity in m/s in NORTH direction in earth-fixed NED frame + True velocity in m/s in EAST direction in earth-fixed NED frame + True velocity in m/s in DOWN direction in earth-fixed NED frame + + + + Status generated by radio and injected into MAVLink stream. + Local signal strength + Remote signal strength + Remaining free buffer space in percent. + Background noise level + Remote background noise level + Receive errors + Count of error corrected packets + + + File transfer message + Network ID (0 for broadcast) + System ID (0 for broadcast) + Component ID (0 for broadcast) + Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + + + Time synchronization message. + Time sync timestamp 1 + Time sync timestamp 2 + + + Camera-IMU triggering and synchronisation message. + Timestamp for the image frame in microseconds + Image frame sequence + + + The global position, as returned by the Global Positioning System (GPS). This is + NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 + GPS ground speed (m/s * 100). If unknown, set to: 65535 + GPS velocity in cm/s in NORTH direction in earth-fixed NED frame + GPS velocity in cm/s in EAST direction in earth-fixed NED frame + GPS velocity in cm/s in DOWN direction in earth-fixed NED frame + Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + Number of satellites visible. If unknown, set to 255 + + + Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor) + Timestamp (microseconds, synced to UNIX time or since system boot) + Sensor ID + Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. + Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) + Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) + RH rotation around X axis (rad) + RH rotation around Y axis (rad) + RH rotation around Z axis (rad) + Temperature * 100 in centi-degrees Celsius + Optical flow quality / confidence. 0: no valid flow, 255: maximum quality + Time in microseconds since the distance was sampled. + Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. + + + Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) + Body frame roll / phi angular speed (rad/s) + Body frame pitch / theta angular speed (rad/s) + Body frame yaw / psi angular speed (rad/s) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + Indicated airspeed, expressed as m/s * 100 + True airspeed, expressed as m/s * 100 + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + + + The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (milliseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. + System ID + Component ID + First log id (0 for first available) + Last log id (0xffff for last available) + + + Reply to LOG_REQUEST_LIST + Log id + Total number of logs + High log number + UTC timestamp of log in seconds since 1970, or 0 if not available + Size of the log (may be approximate) in bytes + + + Request a chunk of a log + System ID + Component ID + Log id (from LOG_ENTRY reply) + Offset into the log + Number of bytes + + + Reply to LOG_REQUEST_DATA + Log id (from LOG_ENTRY reply) + Offset into the log + Number of bytes (zero for end of log) + log data + + + Erase all logs + System ID + Component ID + + + Stop log transfer and resume normal logging + System ID + Component ID + + + data for injecting into the onboard GPS (used for DGPS) + System ID + Component ID + data length + raw data (110 is enough for 12 satellites of RTCMv2) + + + Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS frame). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (AMSL, not WGS84), in meters * 1000 (positive for up) + GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX + Number of satellites visible. If unknown, set to 255 + Number of DGPS satellites + Age of DGPS info + + + Power supply status + 5V rail voltage in millivolts + servo rail voltage in millivolts + power supply status flags (see MAV_POWER_STATUS enum) + + + Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate. + See SERIAL_CONTROL_DEV enum + See SERIAL_CONTROL_FLAG enum + Timeout for reply data in milliseconds + Baudrate of transfer. Zero means no change. + how many bytes in this transfer + serial data + + + RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting + Time since boot of last baseline message received in ms. + Identification of connected RTK receiver. + GPS Week Number of last baseline + GPS Time of Week of last baseline + GPS-specific health report for RTK data. + Rate of baseline messages being received by GPS, in HZ + Current number of sats used for RTK calculation. + Coordinate system of baseline. 0 == ECEF, 1 == NED + Current baseline in ECEF x or NED north component in mm. + Current baseline in ECEF y or NED east component in mm. + Current baseline in ECEF z or NED down component in mm. + Current estimate of baseline accuracy. + Current number of integer ambiguity hypotheses. + + + RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting + Time since boot of last baseline message received in ms. + Identification of connected RTK receiver. + GPS Week Number of last baseline + GPS Time of Week of last baseline + GPS-specific health report for RTK data. + Rate of baseline messages being received by GPS, in HZ + Current number of sats used for RTK calculation. + Coordinate system of baseline. 0 == ECEF, 1 == NED + Current baseline in ECEF x or NED north component in mm. + Current baseline in ECEF y or NED east component in mm. + Current baseline in ECEF z or NED down component in mm. + Current estimate of baseline accuracy. + Current number of integer ambiguity hypotheses. + + + The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (milliseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + total data size in bytes (set on ACK only) + Width of a matrix or image + Height of a matrix or image + number of packets beeing sent (set on ACK only) + payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + JPEG quality out of [1,100] + + + sequence number (starting with 0 on every transmission) + image data bytes + + + Time since system boot + Minimum distance the sensor can measure in centimeters + Maximum distance the sensor can measure in centimeters + Current distance reading + Type from MAV_DISTANCE_SENSOR enum. + Onboard ID of the sensor + Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. + Measurement covariance in centimeters, 0 for unknown / invalid readings + + + Request for terrain data and terrain status + Latitude of SW corner of first grid (degrees *10^7) + Longitude of SW corner of first grid (in degrees *10^7) + Grid spacing in meters + Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) + + + Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST + Latitude of SW corner of first grid (degrees *10^7) + Longitude of SW corner of first grid (in degrees *10^7) + Grid spacing in meters + bit within the terrain request mask + Terrain data in meters AMSL + + + Request that the vehicle report terrain height at the given location. Used by GCS to check if vehicle has all terrain data needed for a mission. + Latitude (degrees *10^7) + Longitude (degrees *10^7) + + + Response from a TERRAIN_CHECK request + Latitude (degrees *10^7) + Longitude (degrees *10^7) + grid spacing (zero if terrain at this location unavailable) + Terrain height in meters AMSL + Current vehicle height above lat/lon terrain height (meters) + Number of 4x4 terrain blocks waiting to be received or read from disk + Number of 4x4 terrain blocks in memory + + + Barometer readings for 2nd barometer + Timestamp (milliseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + Motion capture attitude and position + Timestamp (micros since boot or Unix epoch) + Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + X position in meters (NED) + Y position in meters (NED) + Z position in meters (NED) + + + Set the vehicle attitude and body angular rates. + Timestamp (micros since boot or Unix epoch) + Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + System ID + Component ID + Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + + + Set the vehicle attitude and body angular rates. + Timestamp (micros since boot or Unix epoch) + Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + + + The current system altitude. + Timestamp (milliseconds since system boot) + This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. + This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude. + This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. + This is the altitude above the home position. It resets on each change of the current home position. + This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. + This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. + + + The autopilot is requesting a resource (file, binary, other type of data) + Request ID. This ID should be re-used when sending back URI contents + The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary + The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) + The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. + The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). + + + Barometer readings for 3rd barometer + Timestamp (milliseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + current motion information from a designated system + Timestamp in milliseconds since system boot + bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + AMSL, in meters + target velocity (0,0,0) for unknown + linear target acceleration (0,0,0) for unknown + (1 0 0 0 for unknown) + (0 0 0 for unknown) + eph epv + button states or switches of a tracker device + + + The smoothed, monotonic system state used to feed the control loops of the system. + Timestamp (micros since boot or Unix epoch) + X acceleration in body frame + Y acceleration in body frame + Z acceleration in body frame + X velocity in body frame + Y velocity in body frame + Z velocity in body frame + X position in local frame + Y position in local frame + Z position in local frame + Airspeed, set to -1 if unknown + Variance of body velocity estimate + Variance in local position + The attitude, represented as Quaternion + Angular rate in roll axis + Angular rate in pitch axis + Angular rate in yaw axis + + + Battery information + Battery ID + Function of the battery + Type (chemistry) of the battery + Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. + Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. + Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate + Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate + Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery + + + Version and capability of autopilot software + bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum) + Firmware version number + Middleware version number + Operating system version number + HW / board version (last 8 bytes should be silicon ID, if any) + Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. + ID of the board vendor + ID of the product + UID if provided by hardware + + + The location of a landing area captured from a downward facing camera + Timestamp (micros since boot or Unix epoch) + The ID of the target if multiple targets are present + MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc. + X-axis angular offset (in radians) of the target from the center of the image + Y-axis angular offset (in radians) of the target from the center of the image + Distance to the target from the vehicle in meters + Size in radians of target along x-axis + Size in radians of target along y-axis + + + + Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovaton test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovaton test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user. + Timestamp (micros since boot or Unix epoch) + Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS. + Velocity innovation test ratio + Horizontal position innovation test ratio + Vertical position innovation test ratio + Magnetometer innovation test ratio + Height above terrain innovation test ratio + True airspeed innovation test ratio + Horizontal position 1-STD accuracy relative to the EKF local origin (m) + Vertical position 1-STD accuracy relative to the EKF local origin (m) + + + Timestamp (micros since boot or Unix epoch) + Wind in X (NED) direction in m/s + Wind in Y (NED) direction in m/s + Wind in Z (NED) direction in m/s + Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate. + Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate. + AMSL altitude (m) this measurement was taken at + Horizontal speed 1-STD accuracy + Vertical speed 1-STD accuracy + + + Vibration levels and accelerometer clipping + Timestamp (micros since boot or Unix epoch) + Vibration levels on X-axis + Vibration levels on Y-axis + Vibration levels on Z-axis + first accelerometer clipping count + second accelerometer clipping count + third accelerometer clipping count + + + This message can be requested by sending the MAV_CMD_GET_HOME_POSITION command. The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The position the system will return to and land on. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84, in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + Local X position of this position in the local coordinate frame + Local Y position of this position in the local coordinate frame + Local Z position of this position in the local coordinate frame + World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + + + The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. + System ID. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84, in degrees * 1E7 + Altitude (AMSL), in meters * 1000 (positive for up) + Local X position of this position in the local coordinate frame + Local Y position of this position in the local coordinate frame + Local Z position of this position in the local coordinate frame + World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground + Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + + + This interface replaces DATA_STREAM + The ID of the requested MAVLink message. v1.0 is limited to 254 messages. + The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. + + + Provides state for additional features + The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. + The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. + + + The location and information of an ADSB vehicle + ICAO address + Latitude, expressed as degrees * 1E7 + Longitude, expressed as degrees * 1E7 + Type from ADSB_ALTITUDE_TYPE enum + Altitude(ASL) in millimeters + Course over ground in centidegrees + The horizontal velocity in centimeters/second + The vertical velocity in centimeters/second, positive is up + The callsign, 8+null + Type from ADSB_EMITTER_TYPE enum + Time since last communication in seconds + Flags to indicate various statuses including valid data fields + Squawk code + + + Message implementing parts of the V2 payload specs in V1 frames for transitional support. + Network ID (0 for broadcast) + System ID (0 for broadcast) + Component ID (0 for broadcast) + A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. + Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. + + + Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Starting address of the debug variables + Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + Memory contents at specified address + + + Name + Timestamp + x + y + z + + + Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Timestamp (milliseconds since system boot) + Name of the debug variable + Floating point value + + + Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Timestamp (milliseconds since system boot) + Name of the debug variable + Signed integer value + + + Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). + Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. + Status text message, without null termination character + + + Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N. + Timestamp (milliseconds since system boot) + index of debug variable + DEBUG value + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/matrixpilot.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/matrixpilot.xml new file mode 100644 index 0000000..29d368d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/matrixpilot.xml @@ -0,0 +1,284 @@ + + + common.xml + + + + + + + + Action required when performing CMD_PREFLIGHT_STORAGE + + Read all parameters from storage + + + Write all parameters to storage + + + Clear all parameters in storage + + + Read specific parameters from storage + + + Write specific parameters to storage + + + Clear specific parameters in storage + + + do nothing + + + + + + Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. + Storage action: Action defined by MAV_PREFLIGHT_STORAGE_ACTION_ADVANCED + Storage area as defined by parameter database + Storage flags as defined by parameter database + Empty + Empty + Empty + Empty + + + + + + + + + Depreciated but used as a compiler flag. Do not remove + System ID + Component ID + + + Reqest reading of flexifunction data + System ID + Component ID + Type of flexifunction data requested + index into data where needed + + + Flexifunction type and parameters for component at function index from buffer + System ID + Component ID + Function index + Total count of functions + Address in the flexifunction data, Set to 0xFFFF to use address in target memory + Size of the + Settings data + + + Flexifunction type and parameters for component at function index from buffer + System ID + Component ID + Function index + result of acknowledge, 0=fail, 1=good + + + Acknowldge sucess or failure of a flexifunction command + System ID + Component ID + 0=inputs, 1=outputs + index of first directory entry to write + count of directory entries to write + Settings data + + + Acknowldge sucess or failure of a flexifunction command + System ID + Component ID + 0=inputs, 1=outputs + index of first directory entry to write + count of directory entries to write + result of acknowledge, 0=fail, 1=good + + + Acknowldge sucess or failure of a flexifunction command + System ID + Component ID + Flexifunction command type + + + Acknowldge sucess or failure of a flexifunction command + Command acknowledged + result of acknowledge + + + Backwards compatible MAVLink version of SERIAL_UDB_EXTRA - F2: Format Part A + Serial UDB Extra Time + Serial UDB Extra Status + Serial UDB Extra Latitude + Serial UDB Extra Longitude + Serial UDB Extra Altitude + Serial UDB Extra Waypoint Index + Serial UDB Extra Rmat 0 + Serial UDB Extra Rmat 1 + Serial UDB Extra Rmat 2 + Serial UDB Extra Rmat 3 + Serial UDB Extra Rmat 4 + Serial UDB Extra Rmat 5 + Serial UDB Extra Rmat 6 + Serial UDB Extra Rmat 7 + Serial UDB Extra Rmat 8 + Serial UDB Extra GPS Course Over Ground + Serial UDB Extra Speed Over Ground + Serial UDB Extra CPU Load + Serial UDB Extra Voltage in MilliVolts + Serial UDB Extra 3D IMU Air Speed + Serial UDB Extra Estimated Wind 0 + Serial UDB Extra Estimated Wind 1 + Serial UDB Extra Estimated Wind 2 + Serial UDB Extra Magnetic Field Earth 0 + Serial UDB Extra Magnetic Field Earth 1 + Serial UDB Extra Magnetic Field Earth 2 + Serial UDB Extra Number of Sattelites in View + Serial UDB Extra GPS Horizontal Dilution of Precision + + + Backwards compatible version of SERIAL_UDB_EXTRA - F2: Part B + Serial UDB Extra Time + Serial UDB Extra PWM Input Channel 1 + Serial UDB Extra PWM Input Channel 2 + Serial UDB Extra PWM Input Channel 3 + Serial UDB Extra PWM Input Channel 4 + Serial UDB Extra PWM Input Channel 5 + Serial UDB Extra PWM Input Channel 6 + Serial UDB Extra PWM Input Channel 7 + Serial UDB Extra PWM Input Channel 8 + Serial UDB Extra PWM Input Channel 9 + Serial UDB Extra PWM Input Channel 10 + Serial UDB Extra PWM Output Channel 1 + Serial UDB Extra PWM Output Channel 2 + Serial UDB Extra PWM Output Channel 3 + Serial UDB Extra PWM Output Channel 4 + Serial UDB Extra PWM Output Channel 5 + Serial UDB Extra PWM Output Channel 6 + Serial UDB Extra PWM Output Channel 7 + Serial UDB Extra PWM Output Channel 8 + Serial UDB Extra PWM Output Channel 9 + Serial UDB Extra PWM Output Channel 10 + Serial UDB Extra IMU Location X + Serial UDB Extra IMU Location Y + Serial UDB Extra IMU Location Z + Serial UDB Extra Status Flags + Serial UDB Extra Oscillator Failure Count + Serial UDB Extra IMU Velocity X + Serial UDB Extra IMU Velocity Y + Serial UDB Extra IMU Velocity Z + Serial UDB Extra Current Waypoint Goal X + Serial UDB Extra Current Waypoint Goal Y + Serial UDB Extra Current Waypoint Goal Z + Serial UDB Extra Stack Memory Free + + + Backwards compatible version of SERIAL_UDB_EXTRA F4: format + Serial UDB Extra Roll Stabilization with Ailerons Enabled + Serial UDB Extra Roll Stabilization with Rudder Enabled + Serial UDB Extra Pitch Stabilization Enabled + Serial UDB Extra Yaw Stabilization using Rudder Enabled + Serial UDB Extra Yaw Stabilization using Ailerons Enabled + Serial UDB Extra Navigation with Ailerons Enabled + Serial UDB Extra Navigation with Rudder Enabled + Serial UDB Extra Type of Alitude Hold when in Stabilized Mode + Serial UDB Extra Type of Alitude Hold when in Waypoint Mode + Serial UDB Extra Firmware racing mode enabled + + + Backwards compatible version of SERIAL_UDB_EXTRA F5: format + Serial UDB YAWKP_AILERON Gain for Proporional control of navigation + Serial UDB YAWKD_AILERON Gain for Rate control of navigation + Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization + Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization + YAW_STABILIZATION_AILERON Proportional control + Gain For Boosting Manual Aileron control When Plane Stabilized + + + Backwards compatible version of SERIAL_UDB_EXTRA F6: format + Serial UDB Extra PITCHGAIN Proportional Control + Serial UDB Extra Pitch Rate Control + Serial UDB Extra Rudder to Elevator Mix + Serial UDB Extra Roll to Elevator Mix + Gain For Boosting Manual Elevator control When Plane Stabilized + + + Backwards compatible version of SERIAL_UDB_EXTRA F7: format + Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation + Serial UDB YAWKD_RUDDER Gain for Rate control of navigation + Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization + Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization + SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized + Serial UDB Extra Return To Landing - Angle to Pitch Plane Down + + + Backwards compatible version of SERIAL_UDB_EXTRA F8: format + Serial UDB Extra HEIGHT_TARGET_MAX + Serial UDB Extra HEIGHT_TARGET_MIN + Serial UDB Extra ALT_HOLD_THROTTLE_MIN + Serial UDB Extra ALT_HOLD_THROTTLE_MAX + Serial UDB Extra ALT_HOLD_PITCH_MIN + Serial UDB Extra ALT_HOLD_PITCH_MAX + Serial UDB Extra ALT_HOLD_PITCH_HIGH + + + Backwards compatible version of SERIAL_UDB_EXTRA F13: format + Serial UDB Extra GPS Week Number + Serial UDB Extra MP Origin Latitude + Serial UDB Extra MP Origin Longitude + Serial UDB Extra MP Origin Altitude Above Sea Level + + + Backwards compatible version of SERIAL_UDB_EXTRA F14: format + Serial UDB Extra Wind Estimation Enabled + Serial UDB Extra Type of GPS Unit + Serial UDB Extra Dead Reckoning Enabled + Serial UDB Extra Type of UDB Hardware + Serial UDB Extra Type of Airframe + Serial UDB Extra Reboot Regitster of DSPIC + Serial UDB Extra Last dspic Trap Flags + Serial UDB Extra Type Program Address of Last Trap + Serial UDB Extra Number of Ocillator Failures + Serial UDB Extra UDB Internal Clock Configuration + Serial UDB Extra Type of Flight Plan + + + Backwards compatible version of SERIAL_UDB_EXTRA F15 and F16: format + Serial UDB Extra Model Name Of Vehicle + Serial UDB Extra Registraton Number of Vehicle + + + Serial UDB Extra Name of Expected Lead Pilot + Serial UDB Extra URL of Lead Pilot or Team + + + The altitude measured by sensors and IMU + Timestamp (milliseconds since system boot) + GPS altitude in meters, expressed as * 1000 (millimeters), above MSL + IMU altitude above ground in meters, expressed as * 1000 (millimeters) + barometeric altitude above ground in meters, expressed as * 1000 (millimeters) + Optical flow altitude above ground in meters, expressed as * 1000 (millimeters) + Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters) + Extra altitude above ground in meters, expressed as * 1000 (millimeters) + + + The airspeed measured by sensors and IMU + Timestamp (milliseconds since system boot) + Airspeed estimate from IMU, cm/s + Pitot measured forward airpseed, cm/s + Hot wire anenometer measured airspeed, cm/s + Ultrasonic measured airspeed, cm/s + Angle of attack sensor, degrees * 10 + Yaw angle sensor, degrees * 10 + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/minimal.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/minimal.xml new file mode 100644 index 0000000..88985a5 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/minimal.xml @@ -0,0 +1,189 @@ + + + 2 + + + Micro air vehicle / autopilot classes. This identifies the individual model. + + Generic autopilot, full support for everything + + + PIXHAWK autopilot, http://pixhawk.ethz.ch + + + SLUGS autopilot, http://slugsuav.soe.ucsc.edu + + + ArduPilotMega / ArduCopter, http://diydrones.com + + + OpenPilot, http://openpilot.org + + + Generic autopilot only supporting simple waypoints + + + Generic autopilot supporting waypoints and other simple navigation commands + + + Generic autopilot supporting the full mission command set + + + No valid autopilot, e.g. a GCS or other MAVLink component + + + PPZ UAV - http://nongnu.org/paparazzi + + + UAV Dev Board + + + FlexiPilot + + + + + Generic micro air vehicle. + + + Fixed wing aircraft. + + + Quadrotor + + + Coaxial helicopter + + + Normal helicopter with tail rotor. + + + Ground installation + + + Operator control unit / ground control station + + + Airship, controlled + + + Free balloon, uncontrolled + + + Rocket + + + Ground rover + + + Surface vessel, boat, ship + + + Submarine + + + Hexarotor + + + Octorotor + + + Octorotor + + + Flapping wing + + + + These flags encode the MAV mode. + + 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. + + + 0b01000000 remote control input is enabled. + + + 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. + + + 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. + + + 0b00001000 guided mode enabled, system flies MISSIONs / mission items. + + + 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. + + + 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. + + + 0b00000001 Reserved for future use. + + + + These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. + + First bit: 10000000 + + + Second bit: 01000000 + + + Third bit: 00100000 + + + Fourth bit: 00010000 + + + Fifth bit: 00001000 + + + Sixt bit: 00000100 + + + Seventh bit: 00000010 + + + Eighth bit: 00000001 + + + + + Uninitialized system, state is unknown. + + + System is booting up. + + + System is calibrating and not flight-ready. + + + System is grounded and on standby. It can be launched any time. + + + System is active and might be already airborne. Motors are engaged. + + + System is in a non-normal flight mode. It can however still navigate. + + + System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. + + + System just initialized its power-down sequence, will shut down now. + + + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Autopilot type / class. defined in MAV_AUTOPILOT ENUM + System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + A bitfield for use for autopilot-specific flags. + System status flag, see MAV_STATE ENUM + MAVLink version + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/paparazzi.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/paparazzi.xml new file mode 100644 index 0000000..2200075 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/paparazzi.xml @@ -0,0 +1,38 @@ + + + common.xml + 3 + + + + + + Message encoding a mission script item. This message is emitted upon a request for the next script item. + System ID + Component ID + Sequence + The name of the mission script, NULL terminated. + + + Request script item with the sequence number seq. The response of the system to this message should be a SCRIPT_ITEM message. + System ID + Component ID + Sequence + + + Request the overall list of mission items from the system/component. + System ID + Component ID + + + This message is emitted as response to SCRIPT_REQUEST_LIST by the MAV to get the number of mission scripts. + System ID + Component ID + Number of script items in the sequence + + + This message informs about the currently active SCRIPT. + Active Sequence + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/python_array_test.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/python_array_test.xml new file mode 100644 index 0000000..c015085 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/python_array_test.xml @@ -0,0 +1,67 @@ + + + +common.xml + + + Array test #0. + Stub field + Value array + Value array + Value array + Value array + + + Array test #1. + Value array + + + Array test #3. + Stub field + Value array + + + Array test #4. + Value array + Stub field + + + Array test #5. + Value array + Value array + + + Array test #6. + Stub field + Stub field + Stub field + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + + + Array test #7. + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + Value array + + + Array test #8. + Stub field + Value array + Value array + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/rosflight.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/rosflight.xml new file mode 100644 index 0000000..4cbee6f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/rosflight.xml @@ -0,0 +1,153 @@ + + + common.xml + + + + + + + + + + + + + + + + + + + + + + Pass commanded values directly to actuators + + + Command roll rate, pitch rate, yaw rate, and throttle + + + Command roll angle, pitch angle, yaw rate, and throttle + + + Command roll angle, pitch angle, yaw rate, and altitude above ground + + + + + Convenience value for specifying no fields should be ignored + + + Field value1 should be ignored + + + Field value2 should be ignored + + + Field value3 should be ignored + + + Field value4 should be ignored + + + + + + + + + + + + + + + + + + + Offboard control mode, see OFFBOARD_CONTROL_MODE + Bitfield specifying which fields should be ignored, see OFFBOARD_CONTROL_IGNORE + x control channel interpreted according to mode + y control channel, interpreted according to mode + z control channel, interpreted according to mode + F control channel, interpreted according to mode + + + Measurement timestamp as microseconds since boot + Acceleration along X axis + Acceleration along Y axis + Acceleration along Z axis + Angular speed around X axis + Angular speed around Y axis + Angular speed around Z axis + Internal temperature measurement + + + Magnetic field along X axis + Magnetic field along Y axis + Magnetic field along Z axis + + + Calculated Altitude (m) + Measured Differential Pressure (Pa) + Measured Temperature (K) + + + Measured Velocity + Measured Differential Pressure (Pa) + Measured Temperature (K) + + + Measurement timestamp as microseconds since boot + Acceleration along X axis + Acceleration along Y axis + Acceleration along Z axis + Angular speed around X axis + Angular speed around Y axis + Angular speed around Z axis + Internal temperature measurement + True if there is an image associated with this measurement + + + Name of the command struct + Type of command struct + Type of command struct + x value in the command struct + y value in the command struct + z value in the command struct + F value in the command struct + + + Sensor type + Range Measurement (m) + Max Range (m) + Min Range (m) + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/slugs.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/slugs.xml new file mode 100644 index 0000000..a985eab --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/slugs.xml @@ -0,0 +1,339 @@ + + + common.xml + + + + + + Does nothing. + 1 to arm, 0 to disarm + + + + + + Return vehicle to base. + 0: return to base, 1: track mobile base + + + Stops the vehicle from returning to base and resumes flight. + + + Turns the vehicle's visible or infrared lights on or off. + 0: visible lights, 1: infrared lights + 0: turn on, 1: turn off + + + Requests vehicle to send current mid-level commands to ground station. + + + Requests storage of mid-level commands. + Mid-level command storage: 0: read from flash/EEPROM, 1: write to flash/EEPROM + + + + + + Slugs-specific navigation modes. + + No change to SLUGS mode. + + + Vehicle is in liftoff mode. + + + Vehicle is in passthrough mode, being controlled by a pilot. + + + Vehicle is in waypoint mode, navigating to waypoints. + + + Vehicle is executing mid-level commands. + + + Vehicle is returning to the home location. + + + Vehicle is landing. + + + Lost connection with vehicle. + + + Vehicle is in selective passthrough mode, where selected surfaces are being manually controlled. + + + Vehicle is in ISR mode, performing reconaissance at a point specified by ISR_LOCATION message. + + + Vehicle is patrolling along lines between waypoints. + + + Vehicle is grounded or an error has occurred. + + + + + These flags encode the control surfaces for selective passthrough mode. If a bit is set then the pilot console + has control of the surface, and if not then the autopilot has control of the surface. + + 0b10000000 Throttle control passes through to pilot console. + + + 0b01000000 Left aileron control passes through to pilot console. + + + 0b00100000 Right aileron control passes through to pilot console. + + + 0b00010000 Rudder control passes through to pilot console. + + + 0b00001000 Left elevator control passes through to pilot console. + + + 0b00000100 Right elevator control passes through to pilot console. + + + 0b00000010 Left flap control passes through to pilot console. + + + 0b00000001 Right flap control passes through to pilot console. + + + + + + + + Sensor and DSC control loads. + Sensor DSC Load + Control DSC Load + Battery Voltage in millivolts + + + + Accelerometer and gyro biases. + Accelerometer X bias (m/s) + Accelerometer Y bias (m/s) + Accelerometer Z bias (m/s) + Gyro X bias (rad/s) + Gyro Y bias (rad/s) + Gyro Z bias (rad/s) + + + + Configurable diagnostic messages. + Diagnostic float 1 + Diagnostic float 2 + Diagnostic float 3 + Diagnostic short 1 + Diagnostic short 2 + Diagnostic short 3 + + + + Data used in the navigation algorithm. + Measured Airspeed prior to the nav filter in m/s + Commanded Roll + Commanded Pitch + Commanded Turn rate + Y component of the body acceleration + Total Distance to Run on this leg of Navigation + Remaining distance to Run on this leg of Navigation + Origin WP + Destination WP + Commanded altitude in 0.1 m + + + + Configurable data log probes to be used inside Simulink + Log value 1 + Log value 2 + Log value 3 + Log value 4 + Log value 5 + Log value 6 + + + + Pilot console PWM messges. + Year reported by Gps + Month reported by Gps + Day reported by Gps + Hour reported by Gps + Min reported by Gps + Sec reported by Gps + Clock Status. See table 47 page 211 OEMStar Manual + Visible satellites reported by Gps + Used satellites in Solution + GPS+GLONASS satellites in Solution + GPS and GLONASS usage mask (bit 0 GPS_used? bit_4 GLONASS_used?) + Percent used GPS + + + + Mid Level commands sent from the GS to the autopilot. These are only sent when being operated in mid-level commands mode from the ground. + The system setting the commands + Commanded Altitude in meters + Commanded Airspeed in m/s + Commanded Turnrate in rad/s + + + + This message sets the control surfaces for selective passthrough mode. + The system setting the commands + Bitfield containing the passthrough configuration, see CONTROL_SURFACE_FLAG ENUM. + + + + Orders generated to the SLUGS camera mount. + The system reporting the action + Order the mount to pan: -1 left, 0 No pan motion, +1 right + Order the mount to tilt: -1 down, 0 No tilt motion, +1 up + Order the zoom values 0 to 10 + Orders the camera mount to move home. The other fields are ignored when this field is set. 1: move home, 0 ignored + + + + Control for surface; pending and order to origin. + The system setting the commands + ID control surface send 0: throttle 1: aileron 2: elevator 3: rudder + Pending + Order to origin + + + + + + + Transmits the last known position of the mobile GS to the UAV. Very relevant when Track Mobile is enabled + The system reporting the action + Mobile Latitude + Mobile Longitude + + + + Control for camara. + The system setting the commands + ID 0: brightness 1: aperture 2: iris 3: ICR 4: backlight + 1: up/on 2: down/off 3: auto/reset/no action + + + + Transmits the position of watch + The system reporting the action + ISR Latitude + ISR Longitude + ISR Height + Option 1 + Option 2 + Option 3 + + + + + + + Transmits the readings from the voltage and current sensors + It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM + Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V + Depends on the value of r2Type (0) Current consumption in uS of PWM, 20 uS = 90Amp (1) Distance in cm (2) Distance in cm (3) Absolute value + + + + Transmits the actual Pan, Tilt and Zoom values of the camera unit + The actual Zoom Value + The Pan value in 10ths of degree + The Tilt value in 10ths of degree + + + + Transmits the actual status values UAV in flight + The ID system reporting the action + Latitude UAV + Longitude UAV + Altitude UAV + Speed UAV + Course UAV + + + + This contains the status of the GPS readings + Number of times checksum has failed + The quality indicator, 0=fix not available or invalid, 1=GPS fix, 2=C/A differential GPS, 6=Dead reckoning mode, 7=Manual input mode (fixed position), 8=Simulator mode, 9= WAAS a + Indicates if GN, GL or GP messages are being received + A = data valid, V = data invalid + Magnetic variation, degrees + Magnetic variation direction E/W. Easterly variation (E) subtracts from True course and Westerly variation (W) adds to True course + Positioning system mode indicator. A - Autonomous;D-Differential; E-Estimated (dead reckoning) mode;M-Manual input; N-Data not valid + + + + Transmits the diagnostics data from the Novatel OEMStar GPS + The Time Status. See Table 8 page 27 Novatel OEMStar Manual + Status Bitfield. See table 69 page 350 Novatel OEMstar Manual + solution Status. See table 44 page 197 + position type. See table 43 page 196 + velocity type. See table 43 page 196 + Age of the position solution in seconds + Times the CRC has failed since boot + + + + Diagnostic data Sensor MCU + Float field 1 + Float field 2 + Int 16 field 1 + Int 8 field 1 + + + + + The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions. This message allows the sensor and control MCUs to communicate version numbers on startup. + The onboard software version + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/test.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/test.xml new file mode 100644 index 0000000..02bc032 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/test.xml @@ -0,0 +1,31 @@ + + + 3 + + + Test all field types + char + string + uint8_t + uint16_t + uint32_t + uint64_t + int8_t + int16_t + int32_t + int64_t + float + double + uint8_t_array + uint16_t_array + uint32_t_array + uint64_t_array + int8_t_array + int16_t_array + int32_t_array + int64_t_array + float_array + double_array + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/ualberta.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/ualberta.xml new file mode 100644 index 0000000..bb57e84 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/message_definitions/ualberta.xml @@ -0,0 +1,76 @@ + + + common.xml + + + Available autopilot modes for ualberta uav + + Raw input pulse widts sent to output + + + Inputs are normalized using calibration, the converted back to raw pulse widths for output + + + dfsdfs + + + dfsfds + + + dfsdfsdfs + + + + Navigation filter mode + + + AHRS mode + + + INS/GPS initialization mode + + + INS/GPS mode + + + + Mode currently commanded by pilot + + sdf + + + dfs + + + Rotomotion mode + + + + + + Accelerometer and Gyro biases from the navigation filter + Timestamp (microseconds) + b_f[0] + b_f[1] + b_f[2] + b_f[0] + b_f[1] + b_f[2] + + + Complete set of calibration parameters for the radio + Aileron setpoints: left, center, right + Elevator setpoints: nose down, center, nose up + Rudder setpoints: nose left, center, nose right + Tail gyro mode/gain setpoints: heading hold, rate mode + Pitch curve setpoints (every 25%) + Throttle curve setpoints (every 25%) + + + System status specific to ualberta uav + System mode, see UALBERTA_AUTOPILOT_MODE ENUM + Navigation mode, see UALBERTA_NAV_MODE ENUM + Pilot mode, see UALBERTA_PILOT_MODE + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/protocol.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/protocol.h new file mode 100644 index 0000000..bf20708 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/protocol.h @@ -0,0 +1,339 @@ +#ifndef _MAVLINK_PROTOCOL_H_ +#define _MAVLINK_PROTOCOL_H_ + +#include "string.h" +#include "mavlink_types.h" + +/* + If you want MAVLink on a system that is native big-endian, + you need to define NATIVE_BIG_ENDIAN +*/ +#ifdef NATIVE_BIG_ENDIAN +# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN) +#else +# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN) +#endif + +#ifndef MAVLINK_STACK_BUFFER +#define MAVLINK_STACK_BUFFER 0 +#endif + +#ifndef MAVLINK_AVOID_GCC_STACK_BUG +# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__) +#endif + +#ifndef MAVLINK_ASSERT +#define MAVLINK_ASSERT(x) +#endif + +#ifndef MAVLINK_START_UART_SEND +#define MAVLINK_START_UART_SEND(chan, length) +#endif + +#ifndef MAVLINK_END_UART_SEND +#define MAVLINK_END_UART_SEND(chan, length) +#endif + +/* option to provide alternative implementation of mavlink_helpers.h */ +#ifdef MAVLINK_SEPARATE_HELPERS + + #define MAVLINK_HELPER + + /* decls in sync with those in mavlink_helpers.h */ + #ifndef MAVLINK_GET_CHANNEL_STATUS + MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan); + #endif + MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan); + #if MAVLINK_CRC_EXTRA + MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length, uint8_t crc_extra); + MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length, uint8_t crc_extra); + #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, + uint8_t length, uint8_t crc_extra); + #endif + #else + MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t chan, uint8_t length); + MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length); + #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length); + #endif + #endif // MAVLINK_CRC_EXTRA + MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg); + MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg); + MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c); + MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, + mavlink_status_t* status, + uint8_t c, + mavlink_message_t* r_message, + mavlink_status_t* r_mavlink_status); + MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); + MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); + MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, + uint8_t* r_bit_index, uint8_t* buffer); + #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); + MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg); + #endif + +#else + + #define MAVLINK_HELPER static inline + #include "mavlink_helpers.h" + +#endif // MAVLINK_SEPARATE_HELPERS + +/** + * @brief Get the required buffer size for this message + */ +static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg) +{ + return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; +} + +#if MAVLINK_NEED_BYTE_SWAP +static inline void byte_swap_2(char *dst, const char *src) +{ + dst[0] = src[1]; + dst[1] = src[0]; +} +static inline void byte_swap_4(char *dst, const char *src) +{ + dst[0] = src[3]; + dst[1] = src[2]; + dst[2] = src[1]; + dst[3] = src[0]; +} +static inline void byte_swap_8(char *dst, const char *src) +{ + dst[0] = src[7]; + dst[1] = src[6]; + dst[2] = src[5]; + dst[3] = src[4]; + dst[4] = src[3]; + dst[5] = src[2]; + dst[6] = src[1]; + dst[7] = src[0]; +} +#elif !MAVLINK_ALIGNED_FIELDS +static inline void byte_copy_2(char *dst, const char *src) +{ + dst[0] = src[0]; + dst[1] = src[1]; +} +static inline void byte_copy_4(char *dst, const char *src) +{ + dst[0] = src[0]; + dst[1] = src[1]; + dst[2] = src[2]; + dst[3] = src[3]; +} +static inline void byte_copy_8(char *dst, const char *src) +{ + memcpy(dst, src, 8); +} +#endif + +#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b +#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b +#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b + +#if MAVLINK_NEED_BYTE_SWAP +#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) +#elif !MAVLINK_ALIGNED_FIELDS +#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) +#else +#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b +#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b +#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b +#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b +#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b +#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b +#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b +#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b +#endif + +/* + like memcpy(), but if src is NULL, do a memset to zero +*/ +static inline void mav_array_memcpy(void *dest, const void *src, size_t n) +{ + if (src == NULL) { + memset(dest, 0, n); + } else { + memcpy(dest, src, n); + } +} + +/* + * Place a char array into a buffer + */ +static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) +{ + mav_array_memcpy(&buf[wire_offset], b, array_length); + +} + +/* + * Place a uint8_t array into a buffer + */ +static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) +{ + mav_array_memcpy(&buf[wire_offset], b, array_length); + +} + +/* + * Place a int8_t array into a buffer + */ +static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) +{ + mav_array_memcpy(&buf[wire_offset], b, array_length); + +} + +#if MAVLINK_NEED_BYTE_SWAP +#define _MAV_PUT_ARRAY(TYPE, V) \ +static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ +{ \ + if (b == NULL) { \ + memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \ + } else { \ + uint16_t i; \ + for (i=0; imsgid = MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif +} + +/** + * @brief Pack a camera_stamped_small_imu message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_us Measurement timestamp as microseconds since boot + * @param xacc Acceleration along X axis + * @param yacc Acceleration along Y axis + * @param zacc Acceleration along Z axis + * @param xgyro Angular speed around X axis + * @param ygyro Angular speed around Y axis + * @param zgyro Angular speed around Z axis + * @param temperature Internal temperature measurement + * @param image True if there is an image associated with this measurement + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_camera_stamped_small_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_boot_us,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float temperature,uint8_t image) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_boot_us); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, temperature); + _mav_put_uint8_t(buf, 36, image); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#else + mavlink_camera_stamped_small_imu_t packet; + packet.time_boot_us = time_boot_us; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.temperature = temperature; + packet.image = image; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif +} + +/** + * @brief Encode a camera_stamped_small_imu struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param camera_stamped_small_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_camera_stamped_small_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_stamped_small_imu_t* camera_stamped_small_imu) +{ + return mavlink_msg_camera_stamped_small_imu_pack(system_id, component_id, msg, camera_stamped_small_imu->time_boot_us, camera_stamped_small_imu->xacc, camera_stamped_small_imu->yacc, camera_stamped_small_imu->zacc, camera_stamped_small_imu->xgyro, camera_stamped_small_imu->ygyro, camera_stamped_small_imu->zgyro, camera_stamped_small_imu->temperature, camera_stamped_small_imu->image); +} + +/** + * @brief Encode a camera_stamped_small_imu struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param camera_stamped_small_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_camera_stamped_small_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_stamped_small_imu_t* camera_stamped_small_imu) +{ + return mavlink_msg_camera_stamped_small_imu_pack_chan(system_id, component_id, chan, msg, camera_stamped_small_imu->time_boot_us, camera_stamped_small_imu->xacc, camera_stamped_small_imu->yacc, camera_stamped_small_imu->zacc, camera_stamped_small_imu->xgyro, camera_stamped_small_imu->ygyro, camera_stamped_small_imu->zgyro, camera_stamped_small_imu->temperature, camera_stamped_small_imu->image); +} + +/** + * @brief Send a camera_stamped_small_imu message + * @param chan MAVLink channel to send the message + * + * @param time_boot_us Measurement timestamp as microseconds since boot + * @param xacc Acceleration along X axis + * @param yacc Acceleration along Y axis + * @param zacc Acceleration along Z axis + * @param xgyro Angular speed around X axis + * @param ygyro Angular speed around Y axis + * @param zgyro Angular speed around Z axis + * @param temperature Internal temperature measurement + * @param image True if there is an image associated with this measurement + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_camera_stamped_small_imu_send(mavlink_channel_t chan, uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature, uint8_t image) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_boot_us); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, temperature); + _mav_put_uint8_t(buf, 36, image); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, buf, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, buf, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif +#else + mavlink_camera_stamped_small_imu_t packet; + packet.time_boot_us = time_boot_us; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.temperature = temperature; + packet.image = image; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_camera_stamped_small_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature, uint8_t image) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_boot_us); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, temperature); + _mav_put_uint8_t(buf, 36, image); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, buf, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, buf, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif +#else + mavlink_camera_stamped_small_imu_t *packet = (mavlink_camera_stamped_small_imu_t *)msgbuf; + packet->time_boot_us = time_boot_us; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->temperature = temperature; + packet->image = image; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, (const char *)packet, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU, (const char *)packet, MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE CAMERA_STAMPED_SMALL_IMU UNPACKING + + +/** + * @brief Get field time_boot_us from camera_stamped_small_imu message + * + * @return Measurement timestamp as microseconds since boot + */ +static inline uint64_t mavlink_msg_camera_stamped_small_imu_get_time_boot_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field xacc from camera_stamped_small_imu message + * + * @return Acceleration along X axis + */ +static inline float mavlink_msg_camera_stamped_small_imu_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yacc from camera_stamped_small_imu message + * + * @return Acceleration along Y axis + */ +static inline float mavlink_msg_camera_stamped_small_imu_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field zacc from camera_stamped_small_imu message + * + * @return Acceleration along Z axis + */ +static inline float mavlink_msg_camera_stamped_small_imu_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field xgyro from camera_stamped_small_imu message + * + * @return Angular speed around X axis + */ +static inline float mavlink_msg_camera_stamped_small_imu_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field ygyro from camera_stamped_small_imu message + * + * @return Angular speed around Y axis + */ +static inline float mavlink_msg_camera_stamped_small_imu_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field zgyro from camera_stamped_small_imu message + * + * @return Angular speed around Z axis + */ +static inline float mavlink_msg_camera_stamped_small_imu_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field temperature from camera_stamped_small_imu message + * + * @return Internal temperature measurement + */ +static inline float mavlink_msg_camera_stamped_small_imu_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field image from camera_stamped_small_imu message + * + * @return True if there is an image associated with this measurement + */ +static inline uint8_t mavlink_msg_camera_stamped_small_imu_get_image(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Decode a camera_stamped_small_imu message into a struct + * + * @param msg The message to decode + * @param camera_stamped_small_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_camera_stamped_small_imu_decode(const mavlink_message_t* msg, mavlink_camera_stamped_small_imu_t* camera_stamped_small_imu) +{ +#if MAVLINK_NEED_BYTE_SWAP + camera_stamped_small_imu->time_boot_us = mavlink_msg_camera_stamped_small_imu_get_time_boot_us(msg); + camera_stamped_small_imu->xacc = mavlink_msg_camera_stamped_small_imu_get_xacc(msg); + camera_stamped_small_imu->yacc = mavlink_msg_camera_stamped_small_imu_get_yacc(msg); + camera_stamped_small_imu->zacc = mavlink_msg_camera_stamped_small_imu_get_zacc(msg); + camera_stamped_small_imu->xgyro = mavlink_msg_camera_stamped_small_imu_get_xgyro(msg); + camera_stamped_small_imu->ygyro = mavlink_msg_camera_stamped_small_imu_get_ygyro(msg); + camera_stamped_small_imu->zgyro = mavlink_msg_camera_stamped_small_imu_get_zgyro(msg); + camera_stamped_small_imu->temperature = mavlink_msg_camera_stamped_small_imu_get_temperature(msg); + camera_stamped_small_imu->image = mavlink_msg_camera_stamped_small_imu_get_image(msg); +#else + memcpy(camera_stamped_small_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CAMERA_STAMPED_SMALL_IMU_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_diff_pressure.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_diff_pressure.h new file mode 100644 index 0000000..f7277c0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_diff_pressure.h @@ -0,0 +1,257 @@ +// MESSAGE DIFF_PRESSURE PACKING + +#define MAVLINK_MSG_ID_DIFF_PRESSURE 184 + +typedef struct __mavlink_diff_pressure_t +{ + float velocity; /*< Measured Velocity*/ + float diff_pressure; /*< Measured Differential Pressure (Pa)*/ + float temperature; /*< Measured Temperature (K)*/ +} mavlink_diff_pressure_t; + +#define MAVLINK_MSG_ID_DIFF_PRESSURE_LEN 12 +#define MAVLINK_MSG_ID_184_LEN 12 + +#define MAVLINK_MSG_ID_DIFF_PRESSURE_CRC 169 +#define MAVLINK_MSG_ID_184_CRC 169 + + + +#define MAVLINK_MESSAGE_INFO_DIFF_PRESSURE { \ + "DIFF_PRESSURE", \ + 3, \ + { { "velocity", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_diff_pressure_t, velocity) }, \ + { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_diff_pressure_t, diff_pressure) }, \ + { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_diff_pressure_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a diff_pressure message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param velocity Measured Velocity + * @param diff_pressure Measured Differential Pressure (Pa) + * @param temperature Measured Temperature (K) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_diff_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float velocity, float diff_pressure, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DIFF_PRESSURE_LEN]; + _mav_put_float(buf, 0, velocity); + _mav_put_float(buf, 4, diff_pressure); + _mav_put_float(buf, 8, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#else + mavlink_diff_pressure_t packet; + packet.velocity = velocity; + packet.diff_pressure = diff_pressure; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DIFF_PRESSURE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN, MAVLINK_MSG_ID_DIFF_PRESSURE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif +} + +/** + * @brief Pack a diff_pressure message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param velocity Measured Velocity + * @param diff_pressure Measured Differential Pressure (Pa) + * @param temperature Measured Temperature (K) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_diff_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float velocity,float diff_pressure,float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DIFF_PRESSURE_LEN]; + _mav_put_float(buf, 0, velocity); + _mav_put_float(buf, 4, diff_pressure); + _mav_put_float(buf, 8, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#else + mavlink_diff_pressure_t packet; + packet.velocity = velocity; + packet.diff_pressure = diff_pressure; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_DIFF_PRESSURE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN, MAVLINK_MSG_ID_DIFF_PRESSURE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif +} + +/** + * @brief Encode a diff_pressure struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param diff_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_diff_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_diff_pressure_t* diff_pressure) +{ + return mavlink_msg_diff_pressure_pack(system_id, component_id, msg, diff_pressure->velocity, diff_pressure->diff_pressure, diff_pressure->temperature); +} + +/** + * @brief Encode a diff_pressure struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param diff_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_diff_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_diff_pressure_t* diff_pressure) +{ + return mavlink_msg_diff_pressure_pack_chan(system_id, component_id, chan, msg, diff_pressure->velocity, diff_pressure->diff_pressure, diff_pressure->temperature); +} + +/** + * @brief Send a diff_pressure message + * @param chan MAVLink channel to send the message + * + * @param velocity Measured Velocity + * @param diff_pressure Measured Differential Pressure (Pa) + * @param temperature Measured Temperature (K) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_diff_pressure_send(mavlink_channel_t chan, float velocity, float diff_pressure, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_DIFF_PRESSURE_LEN]; + _mav_put_float(buf, 0, velocity); + _mav_put_float(buf, 4, diff_pressure); + _mav_put_float(buf, 8, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, buf, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN, MAVLINK_MSG_ID_DIFF_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, buf, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif +#else + mavlink_diff_pressure_t packet; + packet.velocity = velocity; + packet.diff_pressure = diff_pressure; + packet.temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN, MAVLINK_MSG_ID_DIFF_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_DIFF_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_diff_pressure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float velocity, float diff_pressure, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, velocity); + _mav_put_float(buf, 4, diff_pressure); + _mav_put_float(buf, 8, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, buf, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN, MAVLINK_MSG_ID_DIFF_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, buf, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif +#else + mavlink_diff_pressure_t *packet = (mavlink_diff_pressure_t *)msgbuf; + packet->velocity = velocity; + packet->diff_pressure = diff_pressure; + packet->temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN, MAVLINK_MSG_ID_DIFF_PRESSURE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIFF_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE DIFF_PRESSURE UNPACKING + + +/** + * @brief Get field velocity from diff_pressure message + * + * @return Measured Velocity + */ +static inline float mavlink_msg_diff_pressure_get_velocity(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field diff_pressure from diff_pressure message + * + * @return Measured Differential Pressure (Pa) + */ +static inline float mavlink_msg_diff_pressure_get_diff_pressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field temperature from diff_pressure message + * + * @return Measured Temperature (K) + */ +static inline float mavlink_msg_diff_pressure_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Decode a diff_pressure message into a struct + * + * @param msg The message to decode + * @param diff_pressure C-struct to decode the message contents into + */ +static inline void mavlink_msg_diff_pressure_decode(const mavlink_message_t* msg, mavlink_diff_pressure_t* diff_pressure) +{ +#if MAVLINK_NEED_BYTE_SWAP + diff_pressure->velocity = mavlink_msg_diff_pressure_get_velocity(msg); + diff_pressure->diff_pressure = mavlink_msg_diff_pressure_get_diff_pressure(msg); + diff_pressure->temperature = mavlink_msg_diff_pressure_get_temperature(msg); +#else + memcpy(diff_pressure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DIFF_PRESSURE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_named_command_struct.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_named_command_struct.h new file mode 100644 index 0000000..2aa1064 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_named_command_struct.h @@ -0,0 +1,345 @@ +// MESSAGE NAMED_COMMAND_STRUCT PACKING + +#define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT 186 + +typedef struct __mavlink_named_command_struct_t +{ + float x; /*< x value in the command struct*/ + float y; /*< y value in the command struct*/ + float z; /*< z value in the command struct*/ + float F; /*< F value in the command struct*/ + char name[10]; /*< Name of the command struct*/ + uint8_t type; /*< Type of command struct*/ + uint8_t ignore; /*< Type of command struct*/ +} mavlink_named_command_struct_t; + +#define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN 28 +#define MAVLINK_MSG_ID_186_LEN 28 + +#define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC 169 +#define MAVLINK_MSG_ID_186_CRC 169 + +#define MAVLINK_MSG_NAMED_COMMAND_STRUCT_FIELD_NAME_LEN 10 + +#define MAVLINK_MESSAGE_INFO_NAMED_COMMAND_STRUCT { \ + "NAMED_COMMAND_STRUCT", \ + 7, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_named_command_struct_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_command_struct_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_named_command_struct_t, z) }, \ + { "F", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_named_command_struct_t, F) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 10, 16, offsetof(mavlink_named_command_struct_t, name) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_named_command_struct_t, type) }, \ + { "ignore", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_named_command_struct_t, ignore) }, \ + } \ +} + + +/** + * @brief Pack a named_command_struct message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param name Name of the command struct + * @param type Type of command struct + * @param ignore Type of command struct + * @param x x value in the command struct + * @param y y value in the command struct + * @param z z value in the command struct + * @param F F value in the command struct + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_command_struct_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *name, uint8_t type, uint8_t ignore, float x, float y, float z, float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 26, type); + _mav_put_uint8_t(buf, 27, ignore); + _mav_put_char_array(buf, 16, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#else + mavlink_named_command_struct_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.F = F; + packet.type = type; + packet.ignore = ignore; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif +} + +/** + * @brief Pack a named_command_struct message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param name Name of the command struct + * @param type Type of command struct + * @param ignore Type of command struct + * @param x x value in the command struct + * @param y y value in the command struct + * @param z z value in the command struct + * @param F F value in the command struct + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_command_struct_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *name,uint8_t type,uint8_t ignore,float x,float y,float z,float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 26, type); + _mav_put_uint8_t(buf, 27, ignore); + _mav_put_char_array(buf, 16, name, 10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#else + mavlink_named_command_struct_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.F = F; + packet.type = type; + packet.ignore = ignore; + mav_array_memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif +} + +/** + * @brief Encode a named_command_struct struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param named_command_struct C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_command_struct_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_command_struct_t* named_command_struct) +{ + return mavlink_msg_named_command_struct_pack(system_id, component_id, msg, named_command_struct->name, named_command_struct->type, named_command_struct->ignore, named_command_struct->x, named_command_struct->y, named_command_struct->z, named_command_struct->F); +} + +/** + * @brief Encode a named_command_struct struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param named_command_struct C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_command_struct_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_command_struct_t* named_command_struct) +{ + return mavlink_msg_named_command_struct_pack_chan(system_id, component_id, chan, msg, named_command_struct->name, named_command_struct->type, named_command_struct->ignore, named_command_struct->x, named_command_struct->y, named_command_struct->z, named_command_struct->F); +} + +/** + * @brief Send a named_command_struct message + * @param chan MAVLink channel to send the message + * + * @param name Name of the command struct + * @param type Type of command struct + * @param ignore Type of command struct + * @param x x value in the command struct + * @param y y value in the command struct + * @param z z value in the command struct + * @param F F value in the command struct + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_named_command_struct_send(mavlink_channel_t chan, const char *name, uint8_t type, uint8_t ignore, float x, float y, float z, float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 26, type); + _mav_put_uint8_t(buf, 27, ignore); + _mav_put_char_array(buf, 16, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, buf, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, buf, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif +#else + mavlink_named_command_struct_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.F = F; + packet.type = type; + packet.ignore = ignore; + mav_array_memcpy(packet.name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_named_command_struct_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *name, uint8_t type, uint8_t ignore, float x, float y, float z, float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 26, type); + _mav_put_uint8_t(buf, 27, ignore); + _mav_put_char_array(buf, 16, name, 10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, buf, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, buf, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif +#else + mavlink_named_command_struct_t *packet = (mavlink_named_command_struct_t *)msgbuf; + packet->x = x; + packet->y = y; + packet->z = z; + packet->F = F; + packet->type = type; + packet->ignore = ignore; + mav_array_memcpy(packet->name, name, sizeof(char)*10); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, (const char *)packet, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, (const char *)packet, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE NAMED_COMMAND_STRUCT UNPACKING + + +/** + * @brief Get field name from named_command_struct message + * + * @return Name of the command struct + */ +static inline uint16_t mavlink_msg_named_command_struct_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 10, 16); +} + +/** + * @brief Get field type from named_command_struct message + * + * @return Type of command struct + */ +static inline uint8_t mavlink_msg_named_command_struct_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 26); +} + +/** + * @brief Get field ignore from named_command_struct message + * + * @return Type of command struct + */ +static inline uint8_t mavlink_msg_named_command_struct_get_ignore(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 27); +} + +/** + * @brief Get field x from named_command_struct message + * + * @return x value in the command struct + */ +static inline float mavlink_msg_named_command_struct_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from named_command_struct message + * + * @return y value in the command struct + */ +static inline float mavlink_msg_named_command_struct_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from named_command_struct message + * + * @return z value in the command struct + */ +static inline float mavlink_msg_named_command_struct_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field F from named_command_struct message + * + * @return F value in the command struct + */ +static inline float mavlink_msg_named_command_struct_get_F(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a named_command_struct message into a struct + * + * @param msg The message to decode + * @param named_command_struct C-struct to decode the message contents into + */ +static inline void mavlink_msg_named_command_struct_decode(const mavlink_message_t* msg, mavlink_named_command_struct_t* named_command_struct) +{ +#if MAVLINK_NEED_BYTE_SWAP + named_command_struct->x = mavlink_msg_named_command_struct_get_x(msg); + named_command_struct->y = mavlink_msg_named_command_struct_get_y(msg); + named_command_struct->z = mavlink_msg_named_command_struct_get_z(msg); + named_command_struct->F = mavlink_msg_named_command_struct_get_F(msg); + mavlink_msg_named_command_struct_get_name(msg, named_command_struct->name); + named_command_struct->type = mavlink_msg_named_command_struct_get_type(msg); + named_command_struct->ignore = mavlink_msg_named_command_struct_get_ignore(msg); +#else + memcpy(named_command_struct, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_offboard_control.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_offboard_control.h new file mode 100644 index 0000000..39ca729 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_offboard_control.h @@ -0,0 +1,329 @@ +// MESSAGE OFFBOARD_CONTROL PACKING + +#define MAVLINK_MSG_ID_OFFBOARD_CONTROL 180 + +typedef struct __mavlink_offboard_control_t +{ + float x; /*< x control channel interpreted according to mode*/ + float y; /*< y control channel, interpreted according to mode*/ + float z; /*< z control channel, interpreted according to mode*/ + float F; /*< F control channel, interpreted according to mode*/ + uint8_t mode; /*< Offboard control mode, see OFFBOARD_CONTROL_MODE*/ + uint8_t ignore; /*< Bitfield specifying which fields should be ignored, see OFFBOARD_CONTROL_IGNORE*/ +} mavlink_offboard_control_t; + +#define MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN 18 +#define MAVLINK_MSG_ID_180_LEN 18 + +#define MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC 93 +#define MAVLINK_MSG_ID_180_CRC 93 + + + +#define MAVLINK_MESSAGE_INFO_OFFBOARD_CONTROL { \ + "OFFBOARD_CONTROL", \ + 6, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_offboard_control_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_offboard_control_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_offboard_control_t, z) }, \ + { "F", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_offboard_control_t, F) }, \ + { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_offboard_control_t, mode) }, \ + { "ignore", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_offboard_control_t, ignore) }, \ + } \ +} + + +/** + * @brief Pack a offboard_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param mode Offboard control mode, see OFFBOARD_CONTROL_MODE + * @param ignore Bitfield specifying which fields should be ignored, see OFFBOARD_CONTROL_IGNORE + * @param x x control channel interpreted according to mode + * @param y y control channel, interpreted according to mode + * @param z z control channel, interpreted according to mode + * @param F F control channel, interpreted according to mode + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_offboard_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t mode, uint8_t ignore, float x, float y, float z, float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 16, mode); + _mav_put_uint8_t(buf, 17, ignore); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#else + mavlink_offboard_control_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.F = F; + packet.mode = mode; + packet.ignore = ignore; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_OFFBOARD_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN, MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif +} + +/** + * @brief Pack a offboard_control message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param mode Offboard control mode, see OFFBOARD_CONTROL_MODE + * @param ignore Bitfield specifying which fields should be ignored, see OFFBOARD_CONTROL_IGNORE + * @param x x control channel interpreted according to mode + * @param y y control channel, interpreted according to mode + * @param z z control channel, interpreted according to mode + * @param F F control channel, interpreted according to mode + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_offboard_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t mode,uint8_t ignore,float x,float y,float z,float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 16, mode); + _mav_put_uint8_t(buf, 17, ignore); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#else + mavlink_offboard_control_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.F = F; + packet.mode = mode; + packet.ignore = ignore; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_OFFBOARD_CONTROL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN, MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif +} + +/** + * @brief Encode a offboard_control struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param offboard_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_offboard_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_offboard_control_t* offboard_control) +{ + return mavlink_msg_offboard_control_pack(system_id, component_id, msg, offboard_control->mode, offboard_control->ignore, offboard_control->x, offboard_control->y, offboard_control->z, offboard_control->F); +} + +/** + * @brief Encode a offboard_control struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param offboard_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_offboard_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_offboard_control_t* offboard_control) +{ + return mavlink_msg_offboard_control_pack_chan(system_id, component_id, chan, msg, offboard_control->mode, offboard_control->ignore, offboard_control->x, offboard_control->y, offboard_control->z, offboard_control->F); +} + +/** + * @brief Send a offboard_control message + * @param chan MAVLink channel to send the message + * + * @param mode Offboard control mode, see OFFBOARD_CONTROL_MODE + * @param ignore Bitfield specifying which fields should be ignored, see OFFBOARD_CONTROL_IGNORE + * @param x x control channel interpreted according to mode + * @param y y control channel, interpreted according to mode + * @param z z control channel, interpreted according to mode + * @param F F control channel, interpreted according to mode + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_offboard_control_send(mavlink_channel_t chan, uint8_t mode, uint8_t ignore, float x, float y, float z, float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 16, mode); + _mav_put_uint8_t(buf, 17, ignore); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, buf, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN, MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, buf, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif +#else + mavlink_offboard_control_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.F = F; + packet.mode = mode; + packet.ignore = ignore; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN, MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_offboard_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t mode, uint8_t ignore, float x, float y, float z, float F) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, F); + _mav_put_uint8_t(buf, 16, mode); + _mav_put_uint8_t(buf, 17, ignore); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, buf, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN, MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, buf, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif +#else + mavlink_offboard_control_t *packet = (mavlink_offboard_control_t *)msgbuf; + packet->x = x; + packet->y = y; + packet->z = z; + packet->F = F; + packet->mode = mode; + packet->ignore = ignore; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, (const char *)packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN, MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, (const char *)packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE OFFBOARD_CONTROL UNPACKING + + +/** + * @brief Get field mode from offboard_control message + * + * @return Offboard control mode, see OFFBOARD_CONTROL_MODE + */ +static inline uint8_t mavlink_msg_offboard_control_get_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field ignore from offboard_control message + * + * @return Bitfield specifying which fields should be ignored, see OFFBOARD_CONTROL_IGNORE + */ +static inline uint8_t mavlink_msg_offboard_control_get_ignore(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field x from offboard_control message + * + * @return x control channel interpreted according to mode + */ +static inline float mavlink_msg_offboard_control_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from offboard_control message + * + * @return y control channel, interpreted according to mode + */ +static inline float mavlink_msg_offboard_control_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from offboard_control message + * + * @return z control channel, interpreted according to mode + */ +static inline float mavlink_msg_offboard_control_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field F from offboard_control message + * + * @return F control channel, interpreted according to mode + */ +static inline float mavlink_msg_offboard_control_get_F(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a offboard_control message into a struct + * + * @param msg The message to decode + * @param offboard_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_offboard_control_decode(const mavlink_message_t* msg, mavlink_offboard_control_t* offboard_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + offboard_control->x = mavlink_msg_offboard_control_get_x(msg); + offboard_control->y = mavlink_msg_offboard_control_get_y(msg); + offboard_control->z = mavlink_msg_offboard_control_get_z(msg); + offboard_control->F = mavlink_msg_offboard_control_get_F(msg); + offboard_control->mode = mavlink_msg_offboard_control_get_mode(msg); + offboard_control->ignore = mavlink_msg_offboard_control_get_ignore(msg); +#else + memcpy(offboard_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_rosflight_cmd.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_rosflight_cmd.h new file mode 100644 index 0000000..281fd65 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_rosflight_cmd.h @@ -0,0 +1,209 @@ +// MESSAGE ROSFLIGHT_CMD PACKING + +#define MAVLINK_MSG_ID_ROSFLIGHT_CMD 188 + +typedef struct __mavlink_rosflight_cmd_t +{ + uint8_t command; /*< */ +} mavlink_rosflight_cmd_t; + +#define MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN 1 +#define MAVLINK_MSG_ID_188_LEN 1 + +#define MAVLINK_MSG_ID_ROSFLIGHT_CMD_CRC 249 +#define MAVLINK_MSG_ID_188_CRC 249 + + + +#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_CMD { \ + "ROSFLIGHT_CMD", \ + 1, \ + { { "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rosflight_cmd_t, command) }, \ + } \ +} + + +/** + * @brief Pack a rosflight_cmd message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param command + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_cmd_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t command) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN]; + _mav_put_uint8_t(buf, 0, command); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#else + mavlink_rosflight_cmd_t packet; + packet.command = command; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_CMD; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif +} + +/** + * @brief Pack a rosflight_cmd message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param command + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_cmd_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t command) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN]; + _mav_put_uint8_t(buf, 0, command); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#else + mavlink_rosflight_cmd_t packet; + packet.command = command; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_CMD; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif +} + +/** + * @brief Encode a rosflight_cmd struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rosflight_cmd C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_cmd_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rosflight_cmd_t* rosflight_cmd) +{ + return mavlink_msg_rosflight_cmd_pack(system_id, component_id, msg, rosflight_cmd->command); +} + +/** + * @brief Encode a rosflight_cmd struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rosflight_cmd C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_cmd_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rosflight_cmd_t* rosflight_cmd) +{ + return mavlink_msg_rosflight_cmd_pack_chan(system_id, component_id, chan, msg, rosflight_cmd->command); +} + +/** + * @brief Send a rosflight_cmd message + * @param chan MAVLink channel to send the message + * + * @param command + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rosflight_cmd_send(mavlink_channel_t chan, uint8_t command) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN]; + _mav_put_uint8_t(buf, 0, command); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif +#else + mavlink_rosflight_cmd_t packet; + packet.command = command; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rosflight_cmd_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t command) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, command); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif +#else + mavlink_rosflight_cmd_t *packet = (mavlink_rosflight_cmd_t *)msgbuf; + packet->command = command; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ROSFLIGHT_CMD UNPACKING + + +/** + * @brief Get field command from rosflight_cmd message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_cmd_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Decode a rosflight_cmd message into a struct + * + * @param msg The message to decode + * @param rosflight_cmd C-struct to decode the message contents into + */ +static inline void mavlink_msg_rosflight_cmd_decode(const mavlink_message_t* msg, mavlink_rosflight_cmd_t* rosflight_cmd) +{ +#if MAVLINK_NEED_BYTE_SWAP + rosflight_cmd->command = mavlink_msg_rosflight_cmd_get_command(msg); +#else + memcpy(rosflight_cmd, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROSFLIGHT_CMD_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_rosflight_cmd_ack.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_rosflight_cmd_ack.h new file mode 100644 index 0000000..4e8d931 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_rosflight_cmd_ack.h @@ -0,0 +1,233 @@ +// MESSAGE ROSFLIGHT_CMD_ACK PACKING + +#define MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK 189 + +typedef struct __mavlink_rosflight_cmd_ack_t +{ + uint8_t command; /*< */ + uint8_t success; /*< */ +} mavlink_rosflight_cmd_ack_t; + +#define MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN 2 +#define MAVLINK_MSG_ID_189_LEN 2 + +#define MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_CRC 113 +#define MAVLINK_MSG_ID_189_CRC 113 + + + +#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_CMD_ACK { \ + "ROSFLIGHT_CMD_ACK", \ + 2, \ + { { "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rosflight_cmd_ack_t, command) }, \ + { "success", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_rosflight_cmd_ack_t, success) }, \ + } \ +} + + +/** + * @brief Pack a rosflight_cmd_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param command + * @param success + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_cmd_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t command, uint8_t success) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN]; + _mav_put_uint8_t(buf, 0, command); + _mav_put_uint8_t(buf, 1, success); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#else + mavlink_rosflight_cmd_ack_t packet; + packet.command = command; + packet.success = success; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif +} + +/** + * @brief Pack a rosflight_cmd_ack message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param command + * @param success + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_cmd_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t command,uint8_t success) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN]; + _mav_put_uint8_t(buf, 0, command); + _mav_put_uint8_t(buf, 1, success); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#else + mavlink_rosflight_cmd_ack_t packet; + packet.command = command; + packet.success = success; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif +} + +/** + * @brief Encode a rosflight_cmd_ack struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rosflight_cmd_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_cmd_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rosflight_cmd_ack_t* rosflight_cmd_ack) +{ + return mavlink_msg_rosflight_cmd_ack_pack(system_id, component_id, msg, rosflight_cmd_ack->command, rosflight_cmd_ack->success); +} + +/** + * @brief Encode a rosflight_cmd_ack struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rosflight_cmd_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_cmd_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rosflight_cmd_ack_t* rosflight_cmd_ack) +{ + return mavlink_msg_rosflight_cmd_ack_pack_chan(system_id, component_id, chan, msg, rosflight_cmd_ack->command, rosflight_cmd_ack->success); +} + +/** + * @brief Send a rosflight_cmd_ack message + * @param chan MAVLink channel to send the message + * + * @param command + * @param success + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rosflight_cmd_ack_send(mavlink_channel_t chan, uint8_t command, uint8_t success) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN]; + _mav_put_uint8_t(buf, 0, command); + _mav_put_uint8_t(buf, 1, success); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif +#else + mavlink_rosflight_cmd_ack_t packet; + packet.command = command; + packet.success = success; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rosflight_cmd_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t command, uint8_t success) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint8_t(buf, 0, command); + _mav_put_uint8_t(buf, 1, success); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, buf, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif +#else + mavlink_rosflight_cmd_ack_t *packet = (mavlink_rosflight_cmd_ack_t *)msgbuf; + packet->command = command; + packet->success = success; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ROSFLIGHT_CMD_ACK UNPACKING + + +/** + * @brief Get field command from rosflight_cmd_ack message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_cmd_ack_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field success from rosflight_cmd_ack message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_cmd_ack_get_success(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a rosflight_cmd_ack message into a struct + * + * @param msg The message to decode + * @param rosflight_cmd_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_rosflight_cmd_ack_decode(const mavlink_message_t* msg, mavlink_rosflight_cmd_ack_t* rosflight_cmd_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + rosflight_cmd_ack->command = mavlink_msg_rosflight_cmd_ack_get_command(msg); + rosflight_cmd_ack->success = mavlink_msg_rosflight_cmd_ack_get_success(msg); +#else + memcpy(rosflight_cmd_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_rosflight_output_raw.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_rosflight_output_raw.h new file mode 100644 index 0000000..03e14f7 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_rosflight_output_raw.h @@ -0,0 +1,225 @@ +// MESSAGE ROSFLIGHT_OUTPUT_RAW PACKING + +#define MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW 190 + +typedef struct __mavlink_rosflight_output_raw_t +{ + uint64_t stamp; /*< */ + float values[8]; /*< */ +} mavlink_rosflight_output_raw_t; + +#define MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN 40 +#define MAVLINK_MSG_ID_190_LEN 40 + +#define MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC 230 +#define MAVLINK_MSG_ID_190_CRC 230 + +#define MAVLINK_MSG_ROSFLIGHT_OUTPUT_RAW_FIELD_VALUES_LEN 8 + +#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_OUTPUT_RAW { \ + "ROSFLIGHT_OUTPUT_RAW", \ + 2, \ + { { "stamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rosflight_output_raw_t, stamp) }, \ + { "values", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_rosflight_output_raw_t, values) }, \ + } \ +} + + +/** + * @brief Pack a rosflight_output_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param stamp + * @param values + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t stamp, const float *values) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN]; + _mav_put_uint64_t(buf, 0, stamp); + _mav_put_float_array(buf, 8, values, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#else + mavlink_rosflight_output_raw_t packet; + packet.stamp = stamp; + mav_array_memcpy(packet.values, values, sizeof(float)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif +} + +/** + * @brief Pack a rosflight_output_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param stamp + * @param values + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t stamp,const float *values) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN]; + _mav_put_uint64_t(buf, 0, stamp); + _mav_put_float_array(buf, 8, values, 8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#else + mavlink_rosflight_output_raw_t packet; + packet.stamp = stamp; + mav_array_memcpy(packet.values, values, sizeof(float)*8); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif +} + +/** + * @brief Encode a rosflight_output_raw struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rosflight_output_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rosflight_output_raw_t* rosflight_output_raw) +{ + return mavlink_msg_rosflight_output_raw_pack(system_id, component_id, msg, rosflight_output_raw->stamp, rosflight_output_raw->values); +} + +/** + * @brief Encode a rosflight_output_raw struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rosflight_output_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_output_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rosflight_output_raw_t* rosflight_output_raw) +{ + return mavlink_msg_rosflight_output_raw_pack_chan(system_id, component_id, chan, msg, rosflight_output_raw->stamp, rosflight_output_raw->values); +} + +/** + * @brief Send a rosflight_output_raw message + * @param chan MAVLink channel to send the message + * + * @param stamp + * @param values + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rosflight_output_raw_send(mavlink_channel_t chan, uint64_t stamp, const float *values) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN]; + _mav_put_uint64_t(buf, 0, stamp); + _mav_put_float_array(buf, 8, values, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, buf, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, buf, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif +#else + mavlink_rosflight_output_raw_t packet; + packet.stamp = stamp; + mav_array_memcpy(packet.values, values, sizeof(float)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rosflight_output_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t stamp, const float *values) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, stamp); + _mav_put_float_array(buf, 8, values, 8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, buf, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, buf, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif +#else + mavlink_rosflight_output_raw_t *packet = (mavlink_rosflight_output_raw_t *)msgbuf; + packet->stamp = stamp; + mav_array_memcpy(packet->values, values, sizeof(float)*8); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ROSFLIGHT_OUTPUT_RAW UNPACKING + + +/** + * @brief Get field stamp from rosflight_output_raw message + * + * @return + */ +static inline uint64_t mavlink_msg_rosflight_output_raw_get_stamp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field values from rosflight_output_raw message + * + * @return + */ +static inline uint16_t mavlink_msg_rosflight_output_raw_get_values(const mavlink_message_t* msg, float *values) +{ + return _MAV_RETURN_float_array(msg, values, 8, 8); +} + +/** + * @brief Decode a rosflight_output_raw message into a struct + * + * @param msg The message to decode + * @param rosflight_output_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_rosflight_output_raw_decode(const mavlink_message_t* msg, mavlink_rosflight_output_raw_t* rosflight_output_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + rosflight_output_raw->stamp = mavlink_msg_rosflight_output_raw_get_stamp(msg); + mavlink_msg_rosflight_output_raw_get_values(msg, rosflight_output_raw->values); +#else + memcpy(rosflight_output_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_rosflight_status.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_rosflight_status.h new file mode 100644 index 0000000..0e53c95 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_rosflight_status.h @@ -0,0 +1,377 @@ +// MESSAGE ROSFLIGHT_STATUS PACKING + +#define MAVLINK_MSG_ID_ROSFLIGHT_STATUS 191 + +typedef struct __mavlink_rosflight_status_t +{ + int16_t num_errors; /*< */ + int16_t loop_time_us; /*< */ + uint8_t armed; /*< */ + uint8_t failsafe; /*< */ + uint8_t rc_override; /*< */ + uint8_t offboard; /*< */ + uint8_t error_code; /*< */ + uint8_t control_mode; /*< */ +} mavlink_rosflight_status_t; + +#define MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN 10 +#define MAVLINK_MSG_ID_191_LEN 10 + +#define MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC 183 +#define MAVLINK_MSG_ID_191_CRC 183 + + + +#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_STATUS { \ + "ROSFLIGHT_STATUS", \ + 8, \ + { { "num_errors", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_rosflight_status_t, num_errors) }, \ + { "loop_time_us", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_rosflight_status_t, loop_time_us) }, \ + { "armed", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_rosflight_status_t, armed) }, \ + { "failsafe", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_rosflight_status_t, failsafe) }, \ + { "rc_override", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_rosflight_status_t, rc_override) }, \ + { "offboard", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_rosflight_status_t, offboard) }, \ + { "error_code", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_rosflight_status_t, error_code) }, \ + { "control_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_rosflight_status_t, control_mode) }, \ + } \ +} + + +/** + * @brief Pack a rosflight_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param armed + * @param failsafe + * @param rc_override + * @param offboard + * @param error_code + * @param control_mode + * @param num_errors + * @param loop_time_us + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t armed, uint8_t failsafe, uint8_t rc_override, uint8_t offboard, uint8_t error_code, uint8_t control_mode, int16_t num_errors, int16_t loop_time_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN]; + _mav_put_int16_t(buf, 0, num_errors); + _mav_put_int16_t(buf, 2, loop_time_us); + _mav_put_uint8_t(buf, 4, armed); + _mav_put_uint8_t(buf, 5, failsafe); + _mav_put_uint8_t(buf, 6, rc_override); + _mav_put_uint8_t(buf, 7, offboard); + _mav_put_uint8_t(buf, 8, error_code); + _mav_put_uint8_t(buf, 9, control_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#else + mavlink_rosflight_status_t packet; + packet.num_errors = num_errors; + packet.loop_time_us = loop_time_us; + packet.armed = armed; + packet.failsafe = failsafe; + packet.rc_override = rc_override; + packet.offboard = offboard; + packet.error_code = error_code; + packet.control_mode = control_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif +} + +/** + * @brief Pack a rosflight_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param armed + * @param failsafe + * @param rc_override + * @param offboard + * @param error_code + * @param control_mode + * @param num_errors + * @param loop_time_us + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t armed,uint8_t failsafe,uint8_t rc_override,uint8_t offboard,uint8_t error_code,uint8_t control_mode,int16_t num_errors,int16_t loop_time_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN]; + _mav_put_int16_t(buf, 0, num_errors); + _mav_put_int16_t(buf, 2, loop_time_us); + _mav_put_uint8_t(buf, 4, armed); + _mav_put_uint8_t(buf, 5, failsafe); + _mav_put_uint8_t(buf, 6, rc_override); + _mav_put_uint8_t(buf, 7, offboard); + _mav_put_uint8_t(buf, 8, error_code); + _mav_put_uint8_t(buf, 9, control_mode); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#else + mavlink_rosflight_status_t packet; + packet.num_errors = num_errors; + packet.loop_time_us = loop_time_us; + packet.armed = armed; + packet.failsafe = failsafe; + packet.rc_override = rc_override; + packet.offboard = offboard; + packet.error_code = error_code; + packet.control_mode = control_mode; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_STATUS; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif +} + +/** + * @brief Encode a rosflight_status struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rosflight_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rosflight_status_t* rosflight_status) +{ + return mavlink_msg_rosflight_status_pack(system_id, component_id, msg, rosflight_status->armed, rosflight_status->failsafe, rosflight_status->rc_override, rosflight_status->offboard, rosflight_status->error_code, rosflight_status->control_mode, rosflight_status->num_errors, rosflight_status->loop_time_us); +} + +/** + * @brief Encode a rosflight_status struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rosflight_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rosflight_status_t* rosflight_status) +{ + return mavlink_msg_rosflight_status_pack_chan(system_id, component_id, chan, msg, rosflight_status->armed, rosflight_status->failsafe, rosflight_status->rc_override, rosflight_status->offboard, rosflight_status->error_code, rosflight_status->control_mode, rosflight_status->num_errors, rosflight_status->loop_time_us); +} + +/** + * @brief Send a rosflight_status message + * @param chan MAVLink channel to send the message + * + * @param armed + * @param failsafe + * @param rc_override + * @param offboard + * @param error_code + * @param control_mode + * @param num_errors + * @param loop_time_us + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rosflight_status_send(mavlink_channel_t chan, uint8_t armed, uint8_t failsafe, uint8_t rc_override, uint8_t offboard, uint8_t error_code, uint8_t control_mode, int16_t num_errors, int16_t loop_time_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN]; + _mav_put_int16_t(buf, 0, num_errors); + _mav_put_int16_t(buf, 2, loop_time_us); + _mav_put_uint8_t(buf, 4, armed); + _mav_put_uint8_t(buf, 5, failsafe); + _mav_put_uint8_t(buf, 6, rc_override); + _mav_put_uint8_t(buf, 7, offboard); + _mav_put_uint8_t(buf, 8, error_code); + _mav_put_uint8_t(buf, 9, control_mode); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, buf, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, buf, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif +#else + mavlink_rosflight_status_t packet; + packet.num_errors = num_errors; + packet.loop_time_us = loop_time_us; + packet.armed = armed; + packet.failsafe = failsafe; + packet.rc_override = rc_override; + packet.offboard = offboard; + packet.error_code = error_code; + packet.control_mode = control_mode; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rosflight_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t armed, uint8_t failsafe, uint8_t rc_override, uint8_t offboard, uint8_t error_code, uint8_t control_mode, int16_t num_errors, int16_t loop_time_us) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_int16_t(buf, 0, num_errors); + _mav_put_int16_t(buf, 2, loop_time_us); + _mav_put_uint8_t(buf, 4, armed); + _mav_put_uint8_t(buf, 5, failsafe); + _mav_put_uint8_t(buf, 6, rc_override); + _mav_put_uint8_t(buf, 7, offboard); + _mav_put_uint8_t(buf, 8, error_code); + _mav_put_uint8_t(buf, 9, control_mode); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, buf, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, buf, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif +#else + mavlink_rosflight_status_t *packet = (mavlink_rosflight_status_t *)msgbuf; + packet->num_errors = num_errors; + packet->loop_time_us = loop_time_us; + packet->armed = armed; + packet->failsafe = failsafe; + packet->rc_override = rc_override; + packet->offboard = offboard; + packet->error_code = error_code; + packet->control_mode = control_mode; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ROSFLIGHT_STATUS UNPACKING + + +/** + * @brief Get field armed from rosflight_status message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_status_get_armed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field failsafe from rosflight_status message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_status_get_failsafe(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field rc_override from rosflight_status message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_status_get_rc_override(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field offboard from rosflight_status message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_status_get_offboard(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field error_code from rosflight_status message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_status_get_error_code(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field control_mode from rosflight_status message + * + * @return + */ +static inline uint8_t mavlink_msg_rosflight_status_get_control_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 9); +} + +/** + * @brief Get field num_errors from rosflight_status message + * + * @return + */ +static inline int16_t mavlink_msg_rosflight_status_get_num_errors(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Get field loop_time_us from rosflight_status message + * + * @return + */ +static inline int16_t mavlink_msg_rosflight_status_get_loop_time_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 2); +} + +/** + * @brief Decode a rosflight_status message into a struct + * + * @param msg The message to decode + * @param rosflight_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_rosflight_status_decode(const mavlink_message_t* msg, mavlink_rosflight_status_t* rosflight_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + rosflight_status->num_errors = mavlink_msg_rosflight_status_get_num_errors(msg); + rosflight_status->loop_time_us = mavlink_msg_rosflight_status_get_loop_time_us(msg); + rosflight_status->armed = mavlink_msg_rosflight_status_get_armed(msg); + rosflight_status->failsafe = mavlink_msg_rosflight_status_get_failsafe(msg); + rosflight_status->rc_override = mavlink_msg_rosflight_status_get_rc_override(msg); + rosflight_status->offboard = mavlink_msg_rosflight_status_get_offboard(msg); + rosflight_status->error_code = mavlink_msg_rosflight_status_get_error_code(msg); + rosflight_status->control_mode = mavlink_msg_rosflight_status_get_control_mode(msg); +#else + memcpy(rosflight_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_rosflight_version.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_rosflight_version.h new file mode 100644 index 0000000..3d9fcb9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_rosflight_version.h @@ -0,0 +1,209 @@ +// MESSAGE ROSFLIGHT_VERSION PACKING + +#define MAVLINK_MSG_ID_ROSFLIGHT_VERSION 192 + +typedef struct __mavlink_rosflight_version_t +{ + char version[50]; /*< */ +} mavlink_rosflight_version_t; + +#define MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN 50 +#define MAVLINK_MSG_ID_192_LEN 50 + +#define MAVLINK_MSG_ID_ROSFLIGHT_VERSION_CRC 134 +#define MAVLINK_MSG_ID_192_CRC 134 + +#define MAVLINK_MSG_ROSFLIGHT_VERSION_FIELD_VERSION_LEN 50 + +#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_VERSION { \ + "ROSFLIGHT_VERSION", \ + 1, \ + { { "version", NULL, MAVLINK_TYPE_CHAR, 50, 0, offsetof(mavlink_rosflight_version_t, version) }, \ + } \ +} + + +/** + * @brief Pack a rosflight_version message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param version + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *version) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN]; + + _mav_put_char_array(buf, 0, version, 50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#else + mavlink_rosflight_version_t packet; + + mav_array_memcpy(packet.version, version, sizeof(char)*50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_VERSION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif +} + +/** + * @brief Pack a rosflight_version message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param version + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rosflight_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *version) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN]; + + _mav_put_char_array(buf, 0, version, 50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#else + mavlink_rosflight_version_t packet; + + mav_array_memcpy(packet.version, version, sizeof(char)*50); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_VERSION; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif +} + +/** + * @brief Encode a rosflight_version struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rosflight_version C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rosflight_version_t* rosflight_version) +{ + return mavlink_msg_rosflight_version_pack(system_id, component_id, msg, rosflight_version->version); +} + +/** + * @brief Encode a rosflight_version struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param rosflight_version C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rosflight_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rosflight_version_t* rosflight_version) +{ + return mavlink_msg_rosflight_version_pack_chan(system_id, component_id, chan, msg, rosflight_version->version); +} + +/** + * @brief Send a rosflight_version message + * @param chan MAVLink channel to send the message + * + * @param version + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rosflight_version_send(mavlink_channel_t chan, const char *version) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN]; + + _mav_put_char_array(buf, 0, version, 50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, buf, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, buf, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif +#else + mavlink_rosflight_version_t packet; + + mav_array_memcpy(packet.version, version, sizeof(char)*50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_rosflight_version_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *version) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + + _mav_put_char_array(buf, 0, version, 50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, buf, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, buf, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif +#else + mavlink_rosflight_version_t *packet = (mavlink_rosflight_version_t *)msgbuf; + + mav_array_memcpy(packet->version, version, sizeof(char)*50); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_VERSION, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ROSFLIGHT_VERSION UNPACKING + + +/** + * @brief Get field version from rosflight_version message + * + * @return + */ +static inline uint16_t mavlink_msg_rosflight_version_get_version(const mavlink_message_t* msg, char *version) +{ + return _MAV_RETURN_char_array(msg, version, 50, 0); +} + +/** + * @brief Decode a rosflight_version message into a struct + * + * @param msg The message to decode + * @param rosflight_version C-struct to decode the message contents into + */ +static inline void mavlink_msg_rosflight_version_decode(const mavlink_message_t* msg, mavlink_rosflight_version_t* rosflight_version) +{ +#if MAVLINK_NEED_BYTE_SWAP + mavlink_msg_rosflight_version_get_version(msg, rosflight_version->version); +#else + memcpy(rosflight_version, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROSFLIGHT_VERSION_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_small_baro.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_small_baro.h new file mode 100644 index 0000000..19ecc32 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_small_baro.h @@ -0,0 +1,257 @@ +// MESSAGE SMALL_BARO PACKING + +#define MAVLINK_MSG_ID_SMALL_BARO 183 + +typedef struct __mavlink_small_baro_t +{ + float altitude; /*< Calculated Altitude (m)*/ + float pressure; /*< Measured Differential Pressure (Pa)*/ + float temperature; /*< Measured Temperature (K)*/ +} mavlink_small_baro_t; + +#define MAVLINK_MSG_ID_SMALL_BARO_LEN 12 +#define MAVLINK_MSG_ID_183_LEN 12 + +#define MAVLINK_MSG_ID_SMALL_BARO_CRC 206 +#define MAVLINK_MSG_ID_183_CRC 206 + + + +#define MAVLINK_MESSAGE_INFO_SMALL_BARO { \ + "SMALL_BARO", \ + 3, \ + { { "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_small_baro_t, altitude) }, \ + { "pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_small_baro_t, pressure) }, \ + { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_small_baro_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a small_baro message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param altitude Calculated Altitude (m) + * @param pressure Measured Differential Pressure (Pa) + * @param temperature Measured Temperature (K) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_baro_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float altitude, float pressure, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_BARO_LEN]; + _mav_put_float(buf, 0, altitude); + _mav_put_float(buf, 4, pressure); + _mav_put_float(buf, 8, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#else + mavlink_small_baro_t packet; + packet.altitude = altitude; + packet.pressure = pressure; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_BARO; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_BARO_LEN, MAVLINK_MSG_ID_SMALL_BARO_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif +} + +/** + * @brief Pack a small_baro message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param altitude Calculated Altitude (m) + * @param pressure Measured Differential Pressure (Pa) + * @param temperature Measured Temperature (K) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_baro_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float altitude,float pressure,float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_BARO_LEN]; + _mav_put_float(buf, 0, altitude); + _mav_put_float(buf, 4, pressure); + _mav_put_float(buf, 8, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#else + mavlink_small_baro_t packet; + packet.altitude = altitude; + packet.pressure = pressure; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_BARO; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_BARO_LEN, MAVLINK_MSG_ID_SMALL_BARO_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif +} + +/** + * @brief Encode a small_baro struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param small_baro C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_baro_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_small_baro_t* small_baro) +{ + return mavlink_msg_small_baro_pack(system_id, component_id, msg, small_baro->altitude, small_baro->pressure, small_baro->temperature); +} + +/** + * @brief Encode a small_baro struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param small_baro C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_baro_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_small_baro_t* small_baro) +{ + return mavlink_msg_small_baro_pack_chan(system_id, component_id, chan, msg, small_baro->altitude, small_baro->pressure, small_baro->temperature); +} + +/** + * @brief Send a small_baro message + * @param chan MAVLink channel to send the message + * + * @param altitude Calculated Altitude (m) + * @param pressure Measured Differential Pressure (Pa) + * @param temperature Measured Temperature (K) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_small_baro_send(mavlink_channel_t chan, float altitude, float pressure, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_BARO_LEN]; + _mav_put_float(buf, 0, altitude); + _mav_put_float(buf, 4, pressure); + _mav_put_float(buf, 8, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, buf, MAVLINK_MSG_ID_SMALL_BARO_LEN, MAVLINK_MSG_ID_SMALL_BARO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, buf, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif +#else + mavlink_small_baro_t packet; + packet.altitude = altitude; + packet.pressure = pressure; + packet.temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, (const char *)&packet, MAVLINK_MSG_ID_SMALL_BARO_LEN, MAVLINK_MSG_ID_SMALL_BARO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, (const char *)&packet, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SMALL_BARO_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_small_baro_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float altitude, float pressure, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, altitude); + _mav_put_float(buf, 4, pressure); + _mav_put_float(buf, 8, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, buf, MAVLINK_MSG_ID_SMALL_BARO_LEN, MAVLINK_MSG_ID_SMALL_BARO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, buf, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif +#else + mavlink_small_baro_t *packet = (mavlink_small_baro_t *)msgbuf; + packet->altitude = altitude; + packet->pressure = pressure; + packet->temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, (const char *)packet, MAVLINK_MSG_ID_SMALL_BARO_LEN, MAVLINK_MSG_ID_SMALL_BARO_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_BARO, (const char *)packet, MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SMALL_BARO UNPACKING + + +/** + * @brief Get field altitude from small_baro message + * + * @return Calculated Altitude (m) + */ +static inline float mavlink_msg_small_baro_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field pressure from small_baro message + * + * @return Measured Differential Pressure (Pa) + */ +static inline float mavlink_msg_small_baro_get_pressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field temperature from small_baro message + * + * @return Measured Temperature (K) + */ +static inline float mavlink_msg_small_baro_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Decode a small_baro message into a struct + * + * @param msg The message to decode + * @param small_baro C-struct to decode the message contents into + */ +static inline void mavlink_msg_small_baro_decode(const mavlink_message_t* msg, mavlink_small_baro_t* small_baro) +{ +#if MAVLINK_NEED_BYTE_SWAP + small_baro->altitude = mavlink_msg_small_baro_get_altitude(msg); + small_baro->pressure = mavlink_msg_small_baro_get_pressure(msg); + small_baro->temperature = mavlink_msg_small_baro_get_temperature(msg); +#else + memcpy(small_baro, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SMALL_BARO_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_small_imu.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_small_imu.h new file mode 100644 index 0000000..c60cfde --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_small_imu.h @@ -0,0 +1,377 @@ +// MESSAGE SMALL_IMU PACKING + +#define MAVLINK_MSG_ID_SMALL_IMU 181 + +typedef struct __mavlink_small_imu_t +{ + uint64_t time_boot_us; /*< Measurement timestamp as microseconds since boot*/ + float xacc; /*< Acceleration along X axis*/ + float yacc; /*< Acceleration along Y axis*/ + float zacc; /*< Acceleration along Z axis*/ + float xgyro; /*< Angular speed around X axis*/ + float ygyro; /*< Angular speed around Y axis*/ + float zgyro; /*< Angular speed around Z axis*/ + float temperature; /*< Internal temperature measurement*/ +} mavlink_small_imu_t; + +#define MAVLINK_MSG_ID_SMALL_IMU_LEN 36 +#define MAVLINK_MSG_ID_181_LEN 36 + +#define MAVLINK_MSG_ID_SMALL_IMU_CRC 67 +#define MAVLINK_MSG_ID_181_CRC 67 + + + +#define MAVLINK_MESSAGE_INFO_SMALL_IMU { \ + "SMALL_IMU", \ + 8, \ + { { "time_boot_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_small_imu_t, time_boot_us) }, \ + { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_small_imu_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_small_imu_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_small_imu_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_small_imu_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_small_imu_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_small_imu_t, zgyro) }, \ + { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_small_imu_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a small_imu message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_us Measurement timestamp as microseconds since boot + * @param xacc Acceleration along X axis + * @param yacc Acceleration along Y axis + * @param zacc Acceleration along Z axis + * @param xgyro Angular speed around X axis + * @param ygyro Angular speed around Y axis + * @param zgyro Angular speed around Z axis + * @param temperature Internal temperature measurement + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_boot_us); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#else + mavlink_small_imu_t packet; + packet.time_boot_us = time_boot_us; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif +} + +/** + * @brief Pack a small_imu message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_us Measurement timestamp as microseconds since boot + * @param xacc Acceleration along X axis + * @param yacc Acceleration along Y axis + * @param zacc Acceleration along Z axis + * @param xgyro Angular speed around X axis + * @param ygyro Angular speed around Y axis + * @param zgyro Angular speed around Z axis + * @param temperature Internal temperature measurement + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_boot_us,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_boot_us); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, temperature); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#else + mavlink_small_imu_t packet; + packet.time_boot_us = time_boot_us; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_IMU; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif +} + +/** + * @brief Encode a small_imu struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param small_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_small_imu_t* small_imu) +{ + return mavlink_msg_small_imu_pack(system_id, component_id, msg, small_imu->time_boot_us, small_imu->xacc, small_imu->yacc, small_imu->zacc, small_imu->xgyro, small_imu->ygyro, small_imu->zgyro, small_imu->temperature); +} + +/** + * @brief Encode a small_imu struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param small_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_small_imu_t* small_imu) +{ + return mavlink_msg_small_imu_pack_chan(system_id, component_id, chan, msg, small_imu->time_boot_us, small_imu->xacc, small_imu->yacc, small_imu->zacc, small_imu->xgyro, small_imu->ygyro, small_imu->zgyro, small_imu->temperature); +} + +/** + * @brief Send a small_imu message + * @param chan MAVLink channel to send the message + * + * @param time_boot_us Measurement timestamp as microseconds since boot + * @param xacc Acceleration along X axis + * @param yacc Acceleration along Y axis + * @param zacc Acceleration along Z axis + * @param xgyro Angular speed around X axis + * @param ygyro Angular speed around Y axis + * @param zgyro Angular speed around Z axis + * @param temperature Internal temperature measurement + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_small_imu_send(mavlink_channel_t chan, uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_IMU_LEN]; + _mav_put_uint64_t(buf, 0, time_boot_us); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, buf, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, buf, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif +#else + mavlink_small_imu_t packet; + packet.time_boot_us = time_boot_us; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, (const char *)&packet, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, (const char *)&packet, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SMALL_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_small_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_boot_us); + _mav_put_float(buf, 8, xacc); + _mav_put_float(buf, 12, yacc); + _mav_put_float(buf, 16, zacc); + _mav_put_float(buf, 20, xgyro); + _mav_put_float(buf, 24, ygyro); + _mav_put_float(buf, 28, zgyro); + _mav_put_float(buf, 32, temperature); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, buf, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, buf, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif +#else + mavlink_small_imu_t *packet = (mavlink_small_imu_t *)msgbuf; + packet->time_boot_us = time_boot_us; + packet->xacc = xacc; + packet->yacc = yacc; + packet->zacc = zacc; + packet->xgyro = xgyro; + packet->ygyro = ygyro; + packet->zgyro = zgyro; + packet->temperature = temperature; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, (const char *)packet, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, (const char *)packet, MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SMALL_IMU UNPACKING + + +/** + * @brief Get field time_boot_us from small_imu message + * + * @return Measurement timestamp as microseconds since boot + */ +static inline uint64_t mavlink_msg_small_imu_get_time_boot_us(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field xacc from small_imu message + * + * @return Acceleration along X axis + */ +static inline float mavlink_msg_small_imu_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yacc from small_imu message + * + * @return Acceleration along Y axis + */ +static inline float mavlink_msg_small_imu_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field zacc from small_imu message + * + * @return Acceleration along Z axis + */ +static inline float mavlink_msg_small_imu_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field xgyro from small_imu message + * + * @return Angular speed around X axis + */ +static inline float mavlink_msg_small_imu_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field ygyro from small_imu message + * + * @return Angular speed around Y axis + */ +static inline float mavlink_msg_small_imu_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field zgyro from small_imu message + * + * @return Angular speed around Z axis + */ +static inline float mavlink_msg_small_imu_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field temperature from small_imu message + * + * @return Internal temperature measurement + */ +static inline float mavlink_msg_small_imu_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Decode a small_imu message into a struct + * + * @param msg The message to decode + * @param small_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_small_imu_decode(const mavlink_message_t* msg, mavlink_small_imu_t* small_imu) +{ +#if MAVLINK_NEED_BYTE_SWAP + small_imu->time_boot_us = mavlink_msg_small_imu_get_time_boot_us(msg); + small_imu->xacc = mavlink_msg_small_imu_get_xacc(msg); + small_imu->yacc = mavlink_msg_small_imu_get_yacc(msg); + small_imu->zacc = mavlink_msg_small_imu_get_zacc(msg); + small_imu->xgyro = mavlink_msg_small_imu_get_xgyro(msg); + small_imu->ygyro = mavlink_msg_small_imu_get_ygyro(msg); + small_imu->zgyro = mavlink_msg_small_imu_get_zgyro(msg); + small_imu->temperature = mavlink_msg_small_imu_get_temperature(msg); +#else + memcpy(small_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SMALL_IMU_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_small_mag.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_small_mag.h new file mode 100644 index 0000000..acd1f98 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_small_mag.h @@ -0,0 +1,257 @@ +// MESSAGE SMALL_MAG PACKING + +#define MAVLINK_MSG_ID_SMALL_MAG 182 + +typedef struct __mavlink_small_mag_t +{ + float xmag; /*< Magnetic field along X axis*/ + float ymag; /*< Magnetic field along Y axis*/ + float zmag; /*< Magnetic field along Z axis*/ +} mavlink_small_mag_t; + +#define MAVLINK_MSG_ID_SMALL_MAG_LEN 12 +#define MAVLINK_MSG_ID_182_LEN 12 + +#define MAVLINK_MSG_ID_SMALL_MAG_CRC 218 +#define MAVLINK_MSG_ID_182_CRC 218 + + + +#define MAVLINK_MESSAGE_INFO_SMALL_MAG { \ + "SMALL_MAG", \ + 3, \ + { { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_small_mag_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_small_mag_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_small_mag_t, zmag) }, \ + } \ +} + + +/** + * @brief Pack a small_mag message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param xmag Magnetic field along X axis + * @param ymag Magnetic field along Y axis + * @param zmag Magnetic field along Z axis + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_mag_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float xmag, float ymag, float zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_MAG_LEN]; + _mav_put_float(buf, 0, xmag); + _mav_put_float(buf, 4, ymag); + _mav_put_float(buf, 8, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#else + mavlink_small_mag_t packet; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_MAG; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_MAG_LEN, MAVLINK_MSG_ID_SMALL_MAG_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif +} + +/** + * @brief Pack a small_mag message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param xmag Magnetic field along X axis + * @param ymag Magnetic field along Y axis + * @param zmag Magnetic field along Z axis + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_mag_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float xmag,float ymag,float zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_MAG_LEN]; + _mav_put_float(buf, 0, xmag); + _mav_put_float(buf, 4, ymag); + _mav_put_float(buf, 8, zmag); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#else + mavlink_small_mag_t packet; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_MAG; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_MAG_LEN, MAVLINK_MSG_ID_SMALL_MAG_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif +} + +/** + * @brief Encode a small_mag struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param small_mag C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_mag_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_small_mag_t* small_mag) +{ + return mavlink_msg_small_mag_pack(system_id, component_id, msg, small_mag->xmag, small_mag->ymag, small_mag->zmag); +} + +/** + * @brief Encode a small_mag struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param small_mag C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_mag_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_small_mag_t* small_mag) +{ + return mavlink_msg_small_mag_pack_chan(system_id, component_id, chan, msg, small_mag->xmag, small_mag->ymag, small_mag->zmag); +} + +/** + * @brief Send a small_mag message + * @param chan MAVLink channel to send the message + * + * @param xmag Magnetic field along X axis + * @param ymag Magnetic field along Y axis + * @param zmag Magnetic field along Z axis + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_small_mag_send(mavlink_channel_t chan, float xmag, float ymag, float zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_MAG_LEN]; + _mav_put_float(buf, 0, xmag); + _mav_put_float(buf, 4, ymag); + _mav_put_float(buf, 8, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, buf, MAVLINK_MSG_ID_SMALL_MAG_LEN, MAVLINK_MSG_ID_SMALL_MAG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, buf, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif +#else + mavlink_small_mag_t packet; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, (const char *)&packet, MAVLINK_MSG_ID_SMALL_MAG_LEN, MAVLINK_MSG_ID_SMALL_MAG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, (const char *)&packet, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SMALL_MAG_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_small_mag_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float xmag, float ymag, float zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, xmag); + _mav_put_float(buf, 4, ymag); + _mav_put_float(buf, 8, zmag); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, buf, MAVLINK_MSG_ID_SMALL_MAG_LEN, MAVLINK_MSG_ID_SMALL_MAG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, buf, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif +#else + mavlink_small_mag_t *packet = (mavlink_small_mag_t *)msgbuf; + packet->xmag = xmag; + packet->ymag = ymag; + packet->zmag = zmag; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, (const char *)packet, MAVLINK_MSG_ID_SMALL_MAG_LEN, MAVLINK_MSG_ID_SMALL_MAG_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_MAG, (const char *)packet, MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SMALL_MAG UNPACKING + + +/** + * @brief Get field xmag from small_mag message + * + * @return Magnetic field along X axis + */ +static inline float mavlink_msg_small_mag_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field ymag from small_mag message + * + * @return Magnetic field along Y axis + */ +static inline float mavlink_msg_small_mag_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field zmag from small_mag message + * + * @return Magnetic field along Z axis + */ +static inline float mavlink_msg_small_mag_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Decode a small_mag message into a struct + * + * @param msg The message to decode + * @param small_mag C-struct to decode the message contents into + */ +static inline void mavlink_msg_small_mag_decode(const mavlink_message_t* msg, mavlink_small_mag_t* small_mag) +{ +#if MAVLINK_NEED_BYTE_SWAP + small_mag->xmag = mavlink_msg_small_mag_get_xmag(msg); + small_mag->ymag = mavlink_msg_small_mag_get_ymag(msg); + small_mag->zmag = mavlink_msg_small_mag_get_zmag(msg); +#else + memcpy(small_mag, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SMALL_MAG_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_small_range.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_small_range.h new file mode 100644 index 0000000..6693473 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/mavlink_msg_small_range.h @@ -0,0 +1,281 @@ +// MESSAGE SMALL_RANGE PACKING + +#define MAVLINK_MSG_ID_SMALL_RANGE 187 + +typedef struct __mavlink_small_range_t +{ + float range; /*< Range Measurement (m)*/ + float max_range; /*< Max Range (m)*/ + float min_range; /*< Min Range (m)*/ + uint8_t type; /*< Sensor type*/ +} mavlink_small_range_t; + +#define MAVLINK_MSG_ID_SMALL_RANGE_LEN 13 +#define MAVLINK_MSG_ID_187_LEN 13 + +#define MAVLINK_MSG_ID_SMALL_RANGE_CRC 60 +#define MAVLINK_MSG_ID_187_CRC 60 + + + +#define MAVLINK_MESSAGE_INFO_SMALL_RANGE { \ + "SMALL_RANGE", \ + 4, \ + { { "range", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_small_range_t, range) }, \ + { "max_range", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_small_range_t, max_range) }, \ + { "min_range", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_small_range_t, min_range) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_small_range_t, type) }, \ + } \ +} + + +/** + * @brief Pack a small_range message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type Sensor type + * @param range Range Measurement (m) + * @param max_range Max Range (m) + * @param min_range Min Range (m) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_range_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t type, float range, float max_range, float min_range) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_RANGE_LEN]; + _mav_put_float(buf, 0, range); + _mav_put_float(buf, 4, max_range); + _mav_put_float(buf, 8, min_range); + _mav_put_uint8_t(buf, 12, type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#else + mavlink_small_range_t packet; + packet.range = range; + packet.max_range = max_range; + packet.min_range = min_range; + packet.type = type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_RANGE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_RANGE_LEN, MAVLINK_MSG_ID_SMALL_RANGE_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif +} + +/** + * @brief Pack a small_range message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param type Sensor type + * @param range Range Measurement (m) + * @param max_range Max Range (m) + * @param min_range Min Range (m) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_small_range_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t type,float range,float max_range,float min_range) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_RANGE_LEN]; + _mav_put_float(buf, 0, range); + _mav_put_float(buf, 4, max_range); + _mav_put_float(buf, 8, min_range); + _mav_put_uint8_t(buf, 12, type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#else + mavlink_small_range_t packet; + packet.range = range; + packet.max_range = max_range; + packet.min_range = min_range; + packet.type = type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_SMALL_RANGE; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_RANGE_LEN, MAVLINK_MSG_ID_SMALL_RANGE_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif +} + +/** + * @brief Encode a small_range struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param small_range C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_range_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_small_range_t* small_range) +{ + return mavlink_msg_small_range_pack(system_id, component_id, msg, small_range->type, small_range->range, small_range->max_range, small_range->min_range); +} + +/** + * @brief Encode a small_range struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param small_range C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_small_range_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_small_range_t* small_range) +{ + return mavlink_msg_small_range_pack_chan(system_id, component_id, chan, msg, small_range->type, small_range->range, small_range->max_range, small_range->min_range); +} + +/** + * @brief Send a small_range message + * @param chan MAVLink channel to send the message + * + * @param type Sensor type + * @param range Range Measurement (m) + * @param max_range Max Range (m) + * @param min_range Min Range (m) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_small_range_send(mavlink_channel_t chan, uint8_t type, float range, float max_range, float min_range) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_SMALL_RANGE_LEN]; + _mav_put_float(buf, 0, range); + _mav_put_float(buf, 4, max_range); + _mav_put_float(buf, 8, min_range); + _mav_put_uint8_t(buf, 12, type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, buf, MAVLINK_MSG_ID_SMALL_RANGE_LEN, MAVLINK_MSG_ID_SMALL_RANGE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, buf, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif +#else + mavlink_small_range_t packet; + packet.range = range; + packet.max_range = max_range; + packet.min_range = min_range; + packet.type = type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, (const char *)&packet, MAVLINK_MSG_ID_SMALL_RANGE_LEN, MAVLINK_MSG_ID_SMALL_RANGE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, (const char *)&packet, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_SMALL_RANGE_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_small_range_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, float range, float max_range, float min_range) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_float(buf, 0, range); + _mav_put_float(buf, 4, max_range); + _mav_put_float(buf, 8, min_range); + _mav_put_uint8_t(buf, 12, type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, buf, MAVLINK_MSG_ID_SMALL_RANGE_LEN, MAVLINK_MSG_ID_SMALL_RANGE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, buf, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif +#else + mavlink_small_range_t *packet = (mavlink_small_range_t *)msgbuf; + packet->range = range; + packet->max_range = max_range; + packet->min_range = min_range; + packet->type = type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, (const char *)packet, MAVLINK_MSG_ID_SMALL_RANGE_LEN, MAVLINK_MSG_ID_SMALL_RANGE_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_RANGE, (const char *)packet, MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE SMALL_RANGE UNPACKING + + +/** + * @brief Get field type from small_range message + * + * @return Sensor type + */ +static inline uint8_t mavlink_msg_small_range_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field range from small_range message + * + * @return Range Measurement (m) + */ +static inline float mavlink_msg_small_range_get_range(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field max_range from small_range message + * + * @return Max Range (m) + */ +static inline float mavlink_msg_small_range_get_max_range(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field min_range from small_range message + * + * @return Min Range (m) + */ +static inline float mavlink_msg_small_range_get_min_range(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Decode a small_range message into a struct + * + * @param msg The message to decode + * @param small_range C-struct to decode the message contents into + */ +static inline void mavlink_msg_small_range_decode(const mavlink_message_t* msg, mavlink_small_range_t* small_range) +{ +#if MAVLINK_NEED_BYTE_SWAP + small_range->range = mavlink_msg_small_range_get_range(msg); + small_range->max_range = mavlink_msg_small_range_get_max_range(msg); + small_range->min_range = mavlink_msg_small_range_get_min_range(msg); + small_range->type = mavlink_msg_small_range_get_type(msg); +#else + memcpy(small_range, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SMALL_RANGE_LEN); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/rosflight.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/rosflight.h new file mode 100644 index 0000000..90e59c6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/rosflight.h @@ -0,0 +1,153 @@ +/** @file + * @brief MAVLink comm protocol generated from rosflight.xml + * @see http://mavlink.org + */ +#ifndef MAVLINK_ROSFLIGHT_H +#define MAVLINK_ROSFLIGHT_H + +#ifndef MAVLINK_H + #error Wrong include order: MAVLINK_ROSFLIGHT.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call. +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 37, 4, 0, 0, 27, 25, 0, 0, 0, 0, 0, 68, 26, 185, 229, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 53, 51, 53, 51, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 44, 64, 84, 9, 254, 16, 12, 36, 44, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 22, 13, 255, 14, 18, 43, 8, 22, 14, 36, 43, 41, 32, 243, 14, 93, 0, 100, 36, 60, 30, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 36, 12, 12, 12, 37, 28, 13, 1, 2, 40, 10, 50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 40, 0, 0, 0, 0, 0, 0, 0, 0, 0, 32, 52, 53, 6, 2, 38, 0, 254, 36, 30, 18, 18, 51, 9, 0} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 78, 196, 0, 0, 15, 3, 0, 0, 0, 0, 0, 153, 183, 51, 59, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 138, 108, 32, 185, 84, 34, 174, 124, 237, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 46, 29, 223, 85, 6, 229, 203, 1, 195, 109, 168, 181, 47, 72, 131, 127, 0, 103, 154, 178, 200, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 93, 67, 218, 206, 169, 209, 169, 60, 249, 113, 230, 183, 134, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 163, 105, 0, 0, 0, 0, 0, 0, 0, 0, 0, 90, 104, 85, 95, 130, 184, 0, 8, 204, 49, 170, 44, 83, 46, 0} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ALTITUDE, MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3, MAVLINK_MESSAGE_INFO_FOLLOW_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_LANDING_TARGET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OFFBOARD_CONTROL, MAVLINK_MESSAGE_INFO_SMALL_IMU, MAVLINK_MESSAGE_INFO_SMALL_MAG, MAVLINK_MESSAGE_INFO_SMALL_BARO, MAVLINK_MESSAGE_INFO_DIFF_PRESSURE, MAVLINK_MESSAGE_INFO_CAMERA_STAMPED_SMALL_IMU, MAVLINK_MESSAGE_INFO_NAMED_COMMAND_STRUCT, MAVLINK_MESSAGE_INFO_SMALL_RANGE, MAVLINK_MESSAGE_INFO_ROSFLIGHT_CMD, MAVLINK_MESSAGE_INFO_ROSFLIGHT_CMD_ACK, MAVLINK_MESSAGE_INFO_ROSFLIGHT_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_ROSFLIGHT_STATUS, MAVLINK_MESSAGE_INFO_ROSFLIGHT_VERSION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS, MAVLINK_MESSAGE_INFO_WIND_COV, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VIBRATION, MAVLINK_MESSAGE_INFO_HOME_POSITION, MAVLINK_MESSAGE_INFO_SET_HOME_POSITION, MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL, MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE, MAVLINK_MESSAGE_INFO_ADSB_VEHICLE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_ROSFLIGHT + +// ENUM DEFINITIONS + + +/** @brief */ +#ifndef HAVE_ENUM_ROSFLIGHT_CMD +#define HAVE_ENUM_ROSFLIGHT_CMD +typedef enum ROSFLIGHT_CMD +{ + ROSFLIGHT_CMD_RC_CALIBRATION=0, /* | */ + ROSFLIGHT_CMD_ACCEL_CALIBRATION=1, /* | */ + ROSFLIGHT_CMD_GYRO_CALIBRATION=2, /* | */ + ROSFLIGHT_CMD_BARO_CALIBRATION=3, /* | */ + ROSFLIGHT_CMD_AIRSPEED_CALIBRATION=4, /* | */ + ROSFLIGHT_CMD_READ_PARAMS=5, /* | */ + ROSFLIGHT_CMD_WRITE_PARAMS=6, /* | */ + ROSFLIGHT_CMD_SET_PARAM_DEFAULTS=7, /* | */ + ROSFLIGHT_CMD_REBOOT=8, /* | */ + ROSFLIGHT_CMD_REBOOT_TO_BOOTLOADER=9, /* | */ + ROSFLIGHT_CMD_SEND_VERSION=10, /* | */ + ROSFLIGHT_CMD_ENUM_END=11, /* | */ +} ROSFLIGHT_CMD; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_ROSFLIGHT_CMD_RESPONSE +#define HAVE_ENUM_ROSFLIGHT_CMD_RESPONSE +typedef enum ROSFLIGHT_CMD_RESPONSE +{ + ROSFLIGHT_CMD_FAILED=0, /* | */ + ROSFLIGHT_CMD_SUCCESS=1, /* | */ + ROSFLIGHT_CMD_RESPONSE_ENUM_END=2, /* | */ +} ROSFLIGHT_CMD_RESPONSE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_OFFBOARD_CONTROL_MODE +#define HAVE_ENUM_OFFBOARD_CONTROL_MODE +typedef enum OFFBOARD_CONTROL_MODE +{ + MODE_PASS_THROUGH=0, /* Pass commanded values directly to actuators | */ + MODE_ROLLRATE_PITCHRATE_YAWRATE_THROTTLE=1, /* Command roll rate, pitch rate, yaw rate, and throttle | */ + MODE_ROLL_PITCH_YAWRATE_THROTTLE=2, /* Command roll angle, pitch angle, yaw rate, and throttle | */ + MODE_ROLL_PITCH_YAWRATE_ALTITUDE=3, /* Command roll angle, pitch angle, yaw rate, and altitude above ground | */ + OFFBOARD_CONTROL_MODE_ENUM_END=4, /* | */ +} OFFBOARD_CONTROL_MODE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_OFFBOARD_CONTROL_IGNORE +#define HAVE_ENUM_OFFBOARD_CONTROL_IGNORE +typedef enum OFFBOARD_CONTROL_IGNORE +{ + IGNORE_NONE=0, /* Convenience value for specifying no fields should be ignored | */ + IGNORE_VALUE1=1, /* Field value1 should be ignored | */ + IGNORE_VALUE2=2, /* Field value2 should be ignored | */ + IGNORE_VALUE3=4, /* Field value3 should be ignored | */ + IGNORE_VALUE4=8, /* Field value4 should be ignored | */ + OFFBOARD_CONTROL_IGNORE_ENUM_END=9, /* | */ +} OFFBOARD_CONTROL_IGNORE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_ROSFLIGHT_ERROR_CODE +#define HAVE_ENUM_ROSFLIGHT_ERROR_CODE +typedef enum ROSFLIGHT_ERROR_CODE +{ + ROSFLIGHT_ERROR_NONE=0, /* | */ + ROSFLIGHT_ERROR_INVALID_MIXER=1, /* | */ + ROSFLIGHT_ERROR_IMU_NOT_RESPONDING=2, /* | */ + ROSFLIGHT_ERROR_RC_LOST=4, /* | */ + ROSFLIGHT_ERROR_UNHEALTHY_ESTIMATOR=8, /* | */ + ROSFLIGHT_ERROR_TIME_GOING_BACKWARDS=16, /* | */ + ROSFLIGHT_ERROR_UNCALIBRATED_IMU=32, /* | */ + ROSFLIGHT_ERROR_CODE_ENUM_END=33, /* | */ +} ROSFLIGHT_ERROR_CODE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_ROSFLIGHT_RANGE_TYPE +#define HAVE_ENUM_ROSFLIGHT_RANGE_TYPE +typedef enum ROSFLIGHT_RANGE_TYPE +{ + ROSFLIGHT_RANGE_SONAR=0, /* | */ + ROSFLIGHT_RANGE_LIDAR=1, /* | */ + ROSFLIGHT_RANGE_TYPE_ENUM_END=2, /* | */ +} ROSFLIGHT_RANGE_TYPE; +#endif + +#include "../common/common.h" + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_offboard_control.h" +#include "./mavlink_msg_small_imu.h" +#include "./mavlink_msg_small_mag.h" +#include "./mavlink_msg_small_baro.h" +#include "./mavlink_msg_diff_pressure.h" +#include "./mavlink_msg_camera_stamped_small_imu.h" +#include "./mavlink_msg_named_command_struct.h" +#include "./mavlink_msg_small_range.h" +#include "./mavlink_msg_rosflight_cmd.h" +#include "./mavlink_msg_rosflight_cmd_ack.h" +#include "./mavlink_msg_rosflight_output_raw.h" +#include "./mavlink_msg_rosflight_status.h" +#include "./mavlink_msg_rosflight_version.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // MAVLINK_ROSFLIGHT_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/testsuite.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/testsuite.h new file mode 100644 index 0000000..6ff769e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/mavlink/v1.0/rosflight/testsuite.h @@ -0,0 +1,650 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from rosflight.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef ROSFLIGHT_TESTSUITE_H +#define ROSFLIGHT_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL +static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); +static void mavlink_test_rosflight(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_test_common(system_id, component_id, last_msg); + mavlink_test_rosflight(system_id, component_id, last_msg); +} +#endif + +#include "../common/testsuite.h" + + +static void mavlink_test_offboard_control(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_offboard_control_t packet_in = { + 17.0,45.0,73.0,101.0,53,120 + }; + mavlink_offboard_control_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.x = packet_in.x; + packet1.y = packet_in.y; + packet1.z = packet_in.z; + packet1.F = packet_in.F; + packet1.mode = packet_in.mode; + packet1.ignore = packet_in.ignore; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_offboard_control_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_offboard_control_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_offboard_control_pack(system_id, component_id, &msg , packet1.mode , packet1.ignore , packet1.x , packet1.y , packet1.z , packet1.F ); + mavlink_msg_offboard_control_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_offboard_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.mode , packet1.ignore , packet1.x , packet1.y , packet1.z , packet1.F ); + mavlink_msg_offboard_control_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; i + +#ifndef M_PI +#define M_PI 3.14159265359 +#endif + +static const float atan_max_x = 1.000000; +static const float atan_min_x = 0.000000; +static const int16_t atan_num_entries = 500; +static const float atan_scale_factor = 10000.000000; +static const int16_t atan_lookup_table[500] = { +0, 20, 40, 60, 80, 100, 120, 140, 160, 180, +200, 220, 240, 260, 280, 300, 320, 340, 360, 380, +400, 420, 440, 460, 480, 500, 520, 539, 559, 579, +599, 619, 639, 659, 679, 699, 719, 739, 759, 778, +798, 818, 838, 858, 878, 898, 917, 937, 957, 977, +997, 1016, 1036, 1056, 1076, 1096, 1115, 1135, 1155, 1175, +1194, 1214, 1234, 1253, 1273, 1293, 1312, 1332, 1352, 1371, +1391, 1411, 1430, 1450, 1469, 1489, 1508, 1528, 1548, 1567, +1587, 1606, 1626, 1645, 1664, 1684, 1703, 1723, 1742, 1762, +1781, 1800, 1820, 1839, 1858, 1878, 1897, 1916, 1935, 1955, +1974, 1993, 2012, 2032, 2051, 2070, 2089, 2108, 2127, 2146, +2166, 2185, 2204, 2223, 2242, 2261, 2280, 2299, 2318, 2337, +2355, 2374, 2393, 2412, 2431, 2450, 2469, 2487, 2506, 2525, +2544, 2562, 2581, 2600, 2618, 2637, 2656, 2674, 2693, 2712, +2730, 2749, 2767, 2786, 2804, 2823, 2841, 2859, 2878, 2896, +2915, 2933, 2951, 2970, 2988, 3006, 3024, 3043, 3061, 3079, +3097, 3115, 3133, 3151, 3169, 3187, 3206, 3224, 3241, 3259, +3277, 3295, 3313, 3331, 3349, 3367, 3385, 3402, 3420, 3438, +3456, 3473, 3491, 3509, 3526, 3544, 3561, 3579, 3596, 3614, +3631, 3649, 3666, 3684, 3701, 3719, 3736, 3753, 3771, 3788, +3805, 3822, 3839, 3857, 3874, 3891, 3908, 3925, 3942, 3959, +3976, 3993, 4010, 4027, 4044, 4061, 4078, 4095, 4112, 4128, +4145, 4162, 4179, 4195, 4212, 4229, 4245, 4262, 4278, 4295, +4311, 4328, 4344, 4361, 4377, 4394, 4410, 4426, 4443, 4459, +4475, 4491, 4508, 4524, 4540, 4556, 4572, 4588, 4604, 4620, +4636, 4652, 4668, 4684, 4700, 4716, 4732, 4748, 4764, 4779, +4795, 4811, 4827, 4842, 4858, 4874, 4889, 4905, 4920, 4936, +4951, 4967, 4982, 4998, 5013, 5028, 5044, 5059, 5074, 5090, +5105, 5120, 5135, 5150, 5166, 5181, 5196, 5211, 5226, 5241, +5256, 5271, 5286, 5301, 5315, 5330, 5345, 5360, 5375, 5389, +5404, 5419, 5434, 5448, 5463, 5477, 5492, 5507, 5521, 5535, +5550, 5564, 5579, 5593, 5608, 5622, 5636, 5650, 5665, 5679, +5693, 5707, 5721, 5736, 5750, 5764, 5778, 5792, 5806, 5820, +5834, 5848, 5862, 5875, 5889, 5903, 5917, 5931, 5944, 5958, +5972, 5985, 5999, 6013, 6026, 6040, 6053, 6067, 6080, 6094, +6107, 6121, 6134, 6147, 6161, 6174, 6187, 6201, 6214, 6227, +6240, 6253, 6267, 6280, 6293, 6306, 6319, 6332, 6345, 6358, +6371, 6384, 6397, 6409, 6422, 6435, 6448, 6461, 6473, 6486, +6499, 6511, 6524, 6537, 6549, 6562, 6574, 6587, 6599, 6612, +6624, 6637, 6649, 6661, 6674, 6686, 6698, 6711, 6723, 6735, +6747, 6760, 6772, 6784, 6796, 6808, 6820, 6832, 6844, 6856, +6868, 6880, 6892, 6904, 6916, 6928, 6940, 6951, 6963, 6975, +6987, 6998, 7010, 7022, 7033, 7045, 7057, 7068, 7080, 7091, +7103, 7114, 7126, 7137, 7149, 7160, 7171, 7183, 7194, 7205, +7217, 7228, 7239, 7250, 7261, 7273, 7284, 7295, 7306, 7317, +7328, 7339, 7350, 7361, 7372, 7383, 7394, 7405, 7416, 7427, +7438, 7448, 7459, 7470, 7481, 7491, 7502, 7513, 7524, 7534, +7545, 7555, 7566, 7577, 7587, 7598, 7608, 7619, 7629, 7640, +7650, 7660, 7671, 7681, 7691, 7702, 7712, 7722, 7733, 7743, +7753, 7763, 7773, 7783, 7794, 7804, 7814, 7824, 7834, 7844, +}; + +static const float asin_max_x = 1.000000; +static const float asin_min_x = 0.000000; +static const int16_t asin_num_entries = 500; +static const float asin_scale_factor = 10000.000000; +static const int16_t asin_lookup_table[501] = { +0, 20, 40, 60, 80, 100, 120, 140, 160, 180, +200, 220, 240, 260, 280, 300, 320, 340, 360, 380, +400, 420, 440, 460, 480, 500, 520, 540, 560, 580, +600, 620, 640, 660, 681, 701, 721, 741, 761, 781, +801, 821, 841, 861, 881, 901, 921, 941, 961, 982, +1002, 1022, 1042, 1062, 1082, 1102, 1122, 1142, 1163, 1183, +1203, 1223, 1243, 1263, 1284, 1304, 1324, 1344, 1364, 1384, +1405, 1425, 1445, 1465, 1485, 1506, 1526, 1546, 1566, 1587, +1607, 1627, 1647, 1668, 1688, 1708, 1729, 1749, 1769, 1790, +1810, 1830, 1851, 1871, 1891, 1912, 1932, 1952, 1973, 1993, +2014, 2034, 2054, 2075, 2095, 2116, 2136, 2157, 2177, 2198, +2218, 2239, 2259, 2280, 2300, 2321, 2341, 2362, 2382, 2403, +2424, 2444, 2465, 2486, 2506, 2527, 2547, 2568, 2589, 2610, +2630, 2651, 2672, 2692, 2713, 2734, 2755, 2775, 2796, 2817, +2838, 2859, 2880, 2900, 2921, 2942, 2963, 2984, 3005, 3026, +3047, 3068, 3089, 3110, 3131, 3152, 3173, 3194, 3215, 3236, +3257, 3278, 3300, 3321, 3342, 3363, 3384, 3405, 3427, 3448, +3469, 3490, 3512, 3533, 3554, 3576, 3597, 3618, 3640, 3661, +3683, 3704, 3726, 3747, 3769, 3790, 3812, 3833, 3855, 3876, +3898, 3920, 3941, 3963, 3985, 4006, 4028, 4050, 4072, 4093, +4115, 4137, 4159, 4181, 4203, 4225, 4246, 4268, 4290, 4312, +4334, 4357, 4379, 4401, 4423, 4445, 4467, 4489, 4511, 4534, +4556, 4578, 4601, 4623, 4645, 4668, 4690, 4712, 4735, 4757, +4780, 4802, 4825, 4848, 4870, 4893, 4916, 4938, 4961, 4984, +5007, 5029, 5052, 5075, 5098, 5121, 5144, 5167, 5190, 5213, +5236, 5259, 5282, 5305, 5329, 5352, 5375, 5398, 5422, 5445, +5469, 5492, 5515, 5539, 5562, 5586, 5610, 5633, 5657, 5681, +5704, 5728, 5752, 5776, 5800, 5824, 5848, 5872, 5896, 5920, +5944, 5968, 5992, 6016, 6041, 6065, 6089, 6114, 6138, 6163, +6187, 6212, 6236, 6261, 6286, 6311, 6335, 6360, 6385, 6410, +6435, 6460, 6485, 6510, 6535, 6561, 6586, 6611, 6637, 6662, +6687, 6713, 6739, 6764, 6790, 6816, 6841, 6867, 6893, 6919, +6945, 6971, 6997, 7023, 7050, 7076, 7102, 7129, 7155, 7182, +7208, 7235, 7262, 7288, 7315, 7342, 7369, 7396, 7423, 7450, +7478, 7505, 7532, 7560, 7587, 7615, 7643, 7670, 7698, 7726, +7754, 7782, 7810, 7838, 7867, 7895, 7923, 7952, 7981, 8009, +8038, 8067, 8096, 8125, 8154, 8183, 8213, 8242, 8271, 8301, +8331, 8360, 8390, 8420, 8450, 8481, 8511, 8541, 8572, 8602, +8633, 8664, 8695, 8726, 8757, 8788, 8820, 8851, 8883, 8915, +8947, 8979, 9011, 9043, 9076, 9108, 9141, 9174, 9207, 9240, +9273, 9306, 9340, 9374, 9407, 9442, 9476, 9510, 9545, 9579, +9614, 9649, 9684, 9720, 9755, 9791, 9827, 9863, 9900, 9936, +9973, 10010, 10047, 10084, 10122, 10160, 10198, 10236, 10275, 10314, +10353, 10392, 10432, 10471, 10512, 10552, 10593, 10634, 10675, 10717, +10759, 10801, 10844, 10886, 10930, 10973, 11018, 11062, 11107, 11152, +11198, 11244, 11290, 11337, 11385, 11433, 11481, 11530, 11580, 11630, +11681, 11732, 11784, 11837, 11890, 11944, 11999, 12054, 12111, 12168, +12226, 12285, 12346, 12407, 12469, 12532, 12597, 12663, 12730, 12799, +12870, 12942, 13017, 13093, 13171, 13252, 13336, 13423, 13513, 13606, +13705, 13808, 13917, 14033, 14157, 14293, 14442, 14612, 14813, 15075, +15708 +}; + +static const int32_t max_pressure = 106598; +static const int32_t min_pressure = 69681; +static const int16_t num_entries = 500; +static const int16_t dx = 73; +static const int16_t alt_lookup_table[500] = { +30467, 30384, 30301, 30218, 30135, 30052, 29970, 29887, 29804, 29722, +29639, 29557, 29474, 29392, 29310, 29227, 29145, 29063, 28981, 28899, +28818, 28736, 28654, 28573, 28491, 28410, 28328, 28247, 28166, 28084, +28003, 27922, 27841, 27760, 27679, 27598, 27518, 27437, 27356, 27276, +27195, 27115, 27035, 26954, 26874, 26794, 26714, 26634, 26554, 26474, +26394, 26315, 26235, 26155, 26076, 25996, 25917, 25837, 25758, 25679, +25600, 25521, 25442, 25363, 25284, 25205, 25126, 25047, 24969, 24890, +24811, 24733, 24655, 24576, 24498, 24420, 24341, 24263, 24185, 24107, +24029, 23952, 23874, 23796, 23718, 23641, 23563, 23486, 23408, 23331, +23254, 23176, 23099, 23022, 22945, 22868, 22791, 22714, 22637, 22561, +22484, 22407, 22331, 22254, 22178, 22101, 22025, 21949, 21872, 21796, +21720, 21644, 21568, 21492, 21416, 21340, 21265, 21189, 21113, 21038, +20962, 20887, 20811, 20736, 20661, 20585, 20510, 20435, 20360, 20285, +20210, 20135, 20060, 19985, 19911, 19836, 19761, 19687, 19612, 19538, +19463, 19389, 19315, 19240, 19166, 19092, 19018, 18944, 18870, 18796, +18722, 18649, 18575, 18501, 18427, 18354, 18280, 18207, 18133, 18060, +17987, 17914, 17840, 17767, 17694, 17621, 17548, 17475, 17402, 17329, +17257, 17184, 17111, 17039, 16966, 16894, 16821, 16749, 16676, 16604, +16532, 16460, 16387, 16315, 16243, 16171, 16099, 16027, 15956, 15884, +15812, 15740, 15669, 15597, 15526, 15454, 15383, 15311, 15240, 15169, +15098, 15026, 14955, 14884, 14813, 14742, 14671, 14600, 14530, 14459, +14388, 14317, 14247, 14176, 14106, 14035, 13965, 13894, 13824, 13754, +13684, 13613, 13543, 13473, 13403, 13333, 13263, 13193, 13123, 13054, +12984, 12914, 12845, 12775, 12705, 12636, 12566, 12497, 12428, 12358, +12289, 12220, 12151, 12081, 12012, 11943, 11874, 11805, 11737, 11668, +11599, 11530, 11461, 11393, 11324, 11256, 11187, 11119, 11050, 10982, +10913, 10845, 10777, 10709, 10641, 10572, 10504, 10436, 10368, 10300, +10233, 10165, 10097, 10029, 9962, 9894, 9826, 9759, 9691, 9624, +9556, 9489, 9422, 9354, 9287, 9220, 9153, 9086, 9018, 8951, +8884, 8817, 8751, 8684, 8617, 8550, 8483, 8417, 8350, 8283, +8217, 8150, 8084, 8018, 7951, 7885, 7819, 7752, 7686, 7620, +7554, 7488, 7422, 7356, 7290, 7224, 7158, 7092, 7026, 6961, +6895, 6829, 6764, 6698, 6633, 6567, 6502, 6436, 6371, 6306, +6240, 6175, 6110, 6045, 5980, 5915, 5849, 5784, 5720, 5655, +5590, 5525, 5460, 5395, 5331, 5266, 5201, 5137, 5072, 5008, +4943, 4879, 4815, 4750, 4686, 4622, 4557, 4493, 4429, 4365, +4301, 4237, 4173, 4109, 4045, 3981, 3917, 3854, 3790, 3726, +3663, 3599, 3535, 3472, 3408, 3345, 3281, 3218, 3155, 3091, +3028, 2965, 2902, 2838, 2775, 2712, 2649, 2586, 2523, 2460, +2397, 2335, 2272, 2209, 2146, 2084, 2021, 1958, 1896, 1833, +1771, 1708, 1646, 1583, 1521, 1459, 1396, 1334, 1272, 1210, +1148, 1085, 1023, 961, 899, 837, 776, 714, 652, 590, +528, 467, 405, 343, 282, 220, 158, 97, 35, -26, +-87, -149, -210, -271, -333, -394, -455, -516, -577, -638, +-699, -760, -821, -882, -943, -1004, -1065, -1126, -1186, -1247, +-1308, -1369, -1429, -1490, -1550, -1611, -1671, -1732, -1792, -1852, +-1913, -1973, -2033, -2094, -2154, -2214, -2274, -2334, -2394, -2454, +-2514, -2574, -2634, -2694, -2754, -2814, -2874, -2933, -2993, -3053, +-3112, -3172, -3232, -3291, -3351, -3410, -3469, -3529, -3588, -3648, +-3707, -3766, -3825, -3885, -3944, -4003, -4062, -4121, -4180, -4239 +}; + +float fsign(float y) +{ + return (0.0f < y) - (y < 0.0f); +} + +float asin_approx(float x) +{ + return turboasin(x); +} + + +float turboatan(float x) +{ + // atan is symmetric + if (x < 0) + { + return -1.0*turboatan(-1.0*x); + } + // This uses a sweet identity to wrap the domain of atan onto (0,1) + if (x > 1.0) + { + return M_PI/2.0 - turboatan(1.0/x); + } + + float t = (x - atan_min_x)/(float)(atan_max_x - atan_min_x) * (float)atan_num_entries; + int16_t index = (int)t; + float dx = t - index; + + if (index >= atan_num_entries) + return atan_lookup_table[atan_num_entries-1]/atan_scale_factor; + else if (index < atan_num_entries - 1) + return atan_lookup_table[index]/atan_scale_factor + dx * (atan_lookup_table[index + 1] - atan_lookup_table[index])/atan_scale_factor; + else + return atan_lookup_table[index]/atan_scale_factor + dx * (atan_lookup_table[index] - atan_lookup_table[index - 1])/atan_scale_factor; +} + + +float atan2_approx(float y, float x) +{ + // algorithm from wikipedia: https://en.wikipedia.org/wiki/Atan2 + if (x == 0.0) + { + if (y < 0.0) + { + return - M_PI/2.0; + } + else if ( y > 0.0) + { + return M_PI/2.0; + } + else + { + return 0.0; + } + } + + float arctan = turboatan(y/x); + + if (x < 0.0) + { + if ( y < 0) + { + return arctan - M_PI; + } + else + { + return arctan + M_PI; + } + } + + else + { + return arctan; + } +} + + +float turboasin(float x) +{ + if (x < 0.0) + { + return -1.0*turboasin(-1.0*x); + } + + float t = (x - asin_min_x)/(float)(asin_max_x - asin_min_x) * (float)asin_num_entries; + int16_t index = (int)t; + float dx = t - index; + + if (index >= asin_num_entries) + return asin_lookup_table[500]/asin_scale_factor; + else if (index < asin_num_entries - 1) + return asin_lookup_table[index]/asin_scale_factor + dx * (asin_lookup_table[index + 1] - asin_lookup_table[index])/asin_scale_factor; + else + return asin_lookup_table[index]/asin_scale_factor + dx * (asin_lookup_table[index] - asin_lookup_table[index - 1])/asin_scale_factor; +} + +float fast_alt(float press) +{ + + if(press < max_pressure && press > min_pressure) + { + float t = (float)num_entries*(press - (float)min_pressure) / (float)(max_pressure - min_pressure); + int16_t index = (uint16_t)t; + float dp = t - (float)index; + + float out = 0.0; + + if (index < num_entries - 1) + { + out = alt_lookup_table[index]/10.0 + dp * (alt_lookup_table[index + 1] - alt_lookup_table[index])/10.0; + } + else + { + out = alt_lookup_table[index]/10.0 + dp * (alt_lookup_table[index] - alt_lookup_table[index - 1])/10.0; + } + + return out; + } + else + return 0.0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/turbotrig/turbotrig.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/turbotrig/turbotrig.h new file mode 100644 index 0000000..4c2beb9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/turbotrig/turbotrig.h @@ -0,0 +1,48 @@ +/* + * + * BSD 3-Clause License + * + * Copyright (c) 2017, James Jackson BYU MAGICC Lab, Provo UT + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#pragma once + +#include + +// float-based wrappers +float atan2_approx(float y, float x); +float asin_approx(float x); + +// turbo-speed trig approximation +float turboatan(float x); +float turboasin(float x); +float fsign(float y); + +// turbo-speed approximation of (1.0 - pow(pressure/101325.0, 0.1902631)) * 39097.63 +float fast_alt(float x); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/turbotrig/turbovec.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/turbotrig/turbovec.cpp new file mode 100644 index 0000000..4db13f3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/turbotrig/turbovec.cpp @@ -0,0 +1,199 @@ +/* + * + * BSD 3-Clause License + * + * Copyright (c) 2017, James Jackson BYU MAGICC Lab, Provo UT + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#pragma GCC diagnostic ignored "-Wstrict-aliasing" + + +#include +#include + + +void pfquat() __attribute__((unused)); + + +/**************************************/ +/*** FLOATING POINT IMPLEMENTATIONS ***/ +/**************************************/ +float dot(vector_t v1, vector_t v2) +{ + return v1.x*v2.x + v1.y*v2.y + v1.z*v2.z; +} + +vector_t cross(vector_t u, vector_t v) +{ + vector_t out = {u.y * v.z - u.z * v.y, + u.z * v.x - u.x * v.z, + u.x * v.y - u.y * v.x + }; + return out; +} + +vector_t scalar_multiply(float s, vector_t v) +{ + vector_t out = {s * v.x, + s * v.y, + s * v.z + }; + return out; +} + +vector_t vector_add(vector_t u, vector_t v) +{ + vector_t out = {u.x + v.x, + u.y + v.y, + u.z + v.z + }; + return out; + +} + +vector_t vector_sub(vector_t u, vector_t v) +{ + vector_t out = {u.x - v.x, + u.y - v.y, + u.z - v.z + }; + return out; +} + +float sqrd_norm(vector_t v) +{ + return v.x*v.x + v.y*v.y + v.z*v.z; +} + +float norm(vector_t v) +{ + float out = 1.0/turboInvSqrt(v.x*v.x + v.y*v.y + v.z*v.z); + return out; +} + +vector_t vector_normalize(vector_t v) +{ + float recipNorm = turboInvSqrt(v.x*v.x + v.y*v.y + v.z*v.z); + vector_t out = {recipNorm*v.x, + recipNorm*v.y, + recipNorm*v.z + }; + return out; +} + +quaternion_t quaternion_normalize(quaternion_t q) +{ + float recipNorm = turboInvSqrt(q.w*q.w + q.x*q.x + q.y*q.y + q.z*q.z); + quaternion_t out = {recipNorm*q.w, + recipNorm*q.x, + recipNorm*q.y, + recipNorm*q.z}; + return out; +} + +quaternion_t quaternion_multiply(quaternion_t q1, quaternion_t q2) +{ + quaternion_t q = {q1.w *q2.w - q1.x *q2.x - q1.y *q2.y - q1.z*q2.z, + q1.w *q2.x + q1.x *q2.w - q1.y *q2.z + q1.z*q2.y, + q1.w *q2.y + q1.x *q2.z + q1.y *q2.w - q1.z*q2.x, + q1.w *q2.z - q1.x *q2.y + q1.y *q2.x + q1.z *q2.w + }; + return q; +} + +quaternion_t quaternion_inverse(quaternion_t q) +{ + q.x *= -1.0f; + q.y *= -1.0f; + q.z *= -1.0f; + return q; +} + +vector_t rotate_vector(quaternion_t q, vector_t v) +{ + vector_t out = { (1.0f - 2.0f*q.y*q.y - 2.0f*q.z*q.z) * v.x + (2.0f*(q.x*q.y + q.w*q.z))*v.y + 2.0f*(q.x*q.z - q.w*q.y)*v.z, + (2.0f*(q.x*q.y - q.w*q.z)) * v.x + (1.0f - 2.0f*q.x*q.x - 2.0f*q.z*q.z) * v.y + 2.0f*(q.y*q.z + q.w*q.x)*v.z, + (2.0f*(q.x*q.z + q.w*q.y)) * v.x + 2.0f*(q.y*q.z - q.w*q.x)*v.y + (1.0f - 2.0f*q.x*q.x - 2.0f*q.y*q.y)*v.z}; + return out; +} + +quaternion_t quat_from_two_unit_vectors(vector_t u, vector_t v) +{ + // Adapted From the Ogre3d source code + // https://bitbucket.org/sinbad/ogre/src/9db75e3ba05c/OgreMain/include/OgreVector3.h?fileviewer=file-view-default#cl-651 + quaternion_t out; + float d = dot(u, v); + if ( d >= 1.0f) + { + out = {1, 0, 0, 0}; + } + else + { + float invs = turboInvSqrt(2*(1+d)); + vector_t xyz = scalar_multiply(invs, cross(u, v)); + out = {0.5f/invs, xyz.x, xyz.y, xyz.z}; + } + return quaternion_normalize(out); +} + +void euler_from_quat(quaternion_t q, float *phi, float *theta, float *psi) +{ + *phi = atan2_approx(2.0f * (q.w*q.x + q.y*q.z), + 1.0f - 2.0f * (q.x*q.x + q.y*q.y)); + *theta = asin_approx(2.0f*(q.w*q.y - q.z*q.x)); + *psi = atan2_approx(2.0f * (q.w*q.z + q.x*q.y), + 1.0f - 2.0f * (q.y*q.y + q.z*q.z)); +} + + +float turboInvSqrt(float x) +{ + volatile long i; + volatile float x2, y; + const float threehalfs = 1.5F; + + x2 = x * 0.5F; + y = x; + i = * (long *) &y; // evil floating point bit level hacking + i = 0x5f3759df - (i >> 1); + y = * (float *) &i; + y = y * (threehalfs - (x2 * y * y)); // 1st iteration + y = y * (threehalfs - (x2 * y * y)); // 2nd iteration, this can be removed + + return y; +} + +float fsat(float value, float max) +{ + if (fabs(value) > fabs(max)) + { + value = max*fsign(value); + } + return value; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/turbotrig/turbovec.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/turbotrig/turbovec.h new file mode 100644 index 0000000..1c1dd98 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/lib/turbotrig/turbovec.h @@ -0,0 +1,72 @@ +/* + * + * BSD 3-Clause License + * + * Copyright (c) 2017, James Jackson BYU MAGICC Lab, Provo UT + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#pragma once + +#include +#include +#include + +typedef struct +{ + float x; + float y; + float z; +} vector_t; + +typedef struct +{ + float w; + float x; + float y; + float z; +} quaternion_t; + +float dot(vector_t v1, vector_t v2); +vector_t cross(vector_t u, vector_t v); +vector_t scalar_multiply(float s, vector_t v); +vector_t vector_add(vector_t u, vector_t v); +vector_t vector_sub(vector_t u, vector_t v); +float sqrd_norm(vector_t v); +float norm(vector_t v); +vector_t vector_normalize(vector_t v); +vector_t rotate_vector(quaternion_t q, vector_t v); +quaternion_t quaternion_normalize(quaternion_t q); +quaternion_t quaternion_multiply(quaternion_t q1, quaternion_t q2); +quaternion_t quaternion_inverse(quaternion_t q); +quaternion_t quat_from_two_unit_vectors(vector_t u, vector_t v); + +void euler_from_quat(quaternion_t q, float *phi, float *theta, float *psi); +float turboInvSqrt(float x); +float fsat(float value, float max); +int32_t sat(int32_t value, int32_t max); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/mkdocs.yml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/mkdocs.yml new file mode 100644 index 0000000..77bf8ca --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/mkdocs.yml @@ -0,0 +1,24 @@ +site_name: ROSflight +site_url: http://rosflight.org +repo_url: https://github.com/rosflight/firmware +edit_uri: blob/master/docs/ +google_analytics: ['UA-96018590-2', 'docs.rosflight.org'] +theme: readthedocs +theme_dir: docs/custom_theme +extra_css: [custom_theme/extra.css] +extra_javascript: + - https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.0/MathJax.js?config=TeX-AMS-MML_HTMLorMML +markdown_extensions: + - mdx_math +pages: + - Home: index.md + - User Guide: + - Getting started: user-guide/getting-started.md + - Hardware setup: user-guide/hardware-setup.md + - Autopilot setup: user-guide/autopilot-setup.md + - ROS setup: user-guide/ros-setup.md + - Parameter Configuration: user-guide/parameter-configuration.md + - RC Configuration: user-guide/rc-configuration.md + - Preflight checks: user-guide/preflight-checks.md + - Improving performance: user-guide/performance.md + - Autonomous flight: user-guide/autonomous-flight.md diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/param_parser.py b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/param_parser.py new file mode 100644 index 0000000..3e21a8e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/param_parser.py @@ -0,0 +1,64 @@ +#!/usr/bin/env python +# +__author__ = "James Jackson" +__copyright__ = "Copyright 2017, ROSflight" +__license__ = "BSD-3" +__version__ = "0.1" +__maintainer__ = "James Jackson" +__email__ = "superjax08@gmail.com" + +import re + +f = open('src/param.cpp') +text = f.read() + + +lines = re.split("\n+", text) + +params = [] +i = 0 +for line in lines: + # search for init_param lines + match = re.search("^\s*init_param", line) + if match != None: + name_with_quotes = re.search("\".*\"", line).group(0) + name = re.search("\w{1,16}", name_with_quotes).group(0) + if name != 'DEFAULT': + params.append(dict()) + params[i]['type'] = re.split("\(", re.split("_", line)[2])[0] + params[i]['name'] = name + # Find default value + params[i]['default'] = re.split("\)", re.split(",", line)[2])[0] + # isolate the comment portion of the line and split it on the "|" characters + comment = re.split("\|", re.split("//", line)[1]) + # Isolate the Description + params[i]["description"] = comment[0].strip() + params[i]["min"] = comment[1].strip() + params[i]["max"] = comment[2].strip() + i += 1 + +# Now, generate the markdown table of the parameters +out = open('parameter-descriptions.md', 'w') +# Print the title +out.write("# Parameter descriptions\n\n") +# Start the table +out.write("| Parameter | Description | Type | Default Value | Min | Max |\n") +out.write("|-----------|-------------|------|---------------|-----|-----|\n") +for param in params: + out.write("| ") + out.write(param['name']) + out.write(" | ") + out.write(param['description']) + out.write(" | ") + out.write(param['type']) + out.write(" | ") + out.write(param['default']) + out.write(" | ") + out.write(param['min']) + out.write(" | ") + out.write(param['max']) + out.write(" |\n") + +out.close() + +debug = 1 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/altitude.tex b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/altitude.tex new file mode 100644 index 0000000..1f1855c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/altitude.tex @@ -0,0 +1,175 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% Short Sectioned Assignment +% LaTeX Template +% Version 1.0 (5/5/12) +% +% This template has been downloaded from: +% http://www.LaTeXTemplates.com +% +% Original author: +% Frits Wenneker (http://www.howtotex.com) +% +% License: +% CC BY-NC-SA 3.0 (http://creativecommons.org/licenses/by-nc-sa/3.0/) +% +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +%---------------------------------------------------------------------------------------- +% PACKAGES AND OTHER DOCUMENT CONFIGURATIONS +%---------------------------------------------------------------------------------------- + +\documentclass[paper=a4, fontsize=11pt]{scrartcl} % A4 paper and 11pt font size + +\usepackage[T1]{fontenc} % Use 8-bit encoding that has 256 glyphs +\usepackage{fourier} % Use the Adobe Utopia font for the document - comment this line to return to the LaTeX default +\usepackage[english]{babel} % English language/hyphenation +\usepackage{amsmath,amsfonts,amsthm} % Math packages + +\usepackage{lipsum} % Used for inserting dummy 'Lorem ipsum' text into the template + +\usepackage{sectsty} % Allows customizing section commands +\allsectionsfont{\centering \normalfont\scshape} % Make all sections centered, the default font and small caps + +\usepackage{fancyhdr} % Custom headers and footers +\usepackage{bm} +\usepackage{upgreek} +\pagestyle{fancyplain} % Makes all pages in the document conform to the custom headers and footers +\fancyhead{} % No page header - if you want one, create it in the same way as the footers below +\fancyfoot[L]{} % Empty left footer +\fancyfoot[C]{} % Empty center footer +\fancyfoot[R]{\thepage} % Page numbering for right footer +\renewcommand{\headrulewidth}{0pt} % Remove header underlines +\renewcommand{\footrulewidth}{0pt} % Remove footer underlines +\setlength{\headheight}{13.6pt} % Customize the height of the header + +\numberwithin{equation}{section} % Number equations within sections (i.e. 1.1, 1.2, 2.1, 2.2 instead of 1, 2, 3, 4) +\numberwithin{figure}{section} % Number figures within sections (i.e. 1.1, 1.2, 2.1, 2.2 instead of 1, 2, 3, 4) +\numberwithin{table}{section} % Number tables within sections (i.e. 1.1, 1.2, 2.1, 2.2 instead of 1, 2, 3, 4) + +%---------------------------------------------------------------------------------------- +% TITLE SECTION +%---------------------------------------------------------------------------------------- + +\newcommand{\horrule}[1]{\rule{\linewidth}{#1}} % Create horizontal rule command with 1 argument of height + +\title{ +\normalfont \normalsize +\textsc{MAGICC Lab - Brigham Young University} \\ [25pt] % Your university, school and/or department name(s) +\horrule{0.5pt} \\[0.4cm] % Thin top horizontal rule +\huge Altitude Complementary Filter \\ % The assignment title +\horrule{2pt} \\[0.5cm] % Thick bottom horizontal rule +} + +\author{James Jackson} % Your name + +\date{\normalsize\today} % Today's date or a custom date + +\begin{document} + +\maketitle % Print the title + +\section{Introduction} + +A common operational requirement for autonomous multirotor MAVs is to hover at a given altitude. +This is typically performed by fusing inertial and other measurements with an Extended Kalman Filter (EKF) to provide an estimate of current altitude. +The altitude estimate is then used to calculate control input to reach and maintain desired altitude. +While this method has been demonstrated successfully in practice, the calculation of state with a full EKF requires a great deal of computation. +This calculation is impossible to perform on most embedded MAV flight control units and is instead generally performed on an onboard computer. +Given a separation between an onboard computer performing full-state estimation and a smaller, less capable, but real-time embedded flight control processor +This document outlines the derivation of a nonlinear altitude observer that fuses measurements from an onboard barometer, accelerometer and sonar. +It will also be shown through a Lyuapunov stability analysis that this observer guarantees estimates of both altitude and accelerometer bias to converge exponentially to their true values. + + +\section{Definitions} + +\newcommand{\zhat}{\hat{z}} +\newcommand{\z}{z} +\newcommand{\zdot}{\dot{z}} +\newcommand{\acc}{\bm{a}} +\newcommand{\ameas}{\bm{a}_{meas}} +\newcommand{\khat}{\hat{\bm{k}}} +\newcommand{\RbI}{R_b^I} +\newcommand{\RIb}{R_I^b} +\newcomand{\norm{x}}{\vert x \vert} + +Altitude $\z$ is defined as the inertial z component of distance between the current position of the MAV and it's initial starting position, and is measured positive upwards. It is known to evolve according to the following dynamics: + +\begin{equation} + \begin{aligned} + \zdot = \left( \RbI \acc \right) \cdot \khat + \end{aligned} +\end{equation} + +where $\RbI$ is the rotation from the body-fixed to the inertial frame, $\khat$ is the unit vector in the positive z inertial direction, and $\acc$ is the body fixed acceleration + +We will assume we have measurement from 3 sources: a 3-axis accelerometer, sonar and barometer. +We will assume that the accelerometer measurement $\ameas$ includes all accelerations due to forces except gravity with the addition of some small random, quasi-static bias $\bm{\alpha}$ and noise $\bm{\eta}$. +We will also assume that $\vert\bm{\alpha}\vert$ is bounded by some $\alpha_{max}$ and that $\vert\bm{\eta}\vert$ is also bounded by some $\eta_{max}$. +Therefore, we model true body-fixed acceleration as follows: + +\begin{equation} +\begin{aligned} + \acc &= \ameas + \bm{\alpha} + \RIb\bm{g} + \bm{\eta} \\ + \vert\vert \bm{\alpha} \vert\vert &\leq \alpha_{max} \\ + \vert\vert \bm{\eta} \vert\vert &\leq \eta_{max} \\ +\end{aligned} +\label{eq:accel_model} +\end{equation} + +\newcommand{\zbaro}{\z_{baro}} + +Barometer measurements, $\zbaro$ are assumed to include an absolute altitude measurement with respect to sea level with the addition of a significant wandering bias $\beta$ and noise $\xi$. We can assume, however, that both $\beta$ and $\xi$ are bounded by $\beta_{max}$ and $\xi_{max}$, respectively. Because altitude is measured with respect to the initial position, and not sea level, the intial altitude with repect to sea level, $b_0$ can be subtracted off the measurement to provide measurements with repect to the intial position rather than sea level. It is important to note that $b_0$ can also be thought of as part of $\beta$, rather than it's own term, because it is simply a constant bias. + +\begin{equation} +\begin{aligned} + \zbaro &= z + b_0 + \beta + \xi \\ + \vert \beta \vert &\leq \beta_{max} \\ + \vert \xi \vert &\leq \xi_{max} +\end{aligned} +\end{equation} + +\newcommand{\zsonar}{z_{sonar}} + +Sonar measurements $\zsonar$ are assumed to be absolute altitude above ground with the addition of some noise $\zeta$. +For this filter, we will assume that the ground remains level, so that this measurement can be a measurement of altitude directly, ignoring any additions of terrain changes. +Instead of a bias, many sonars have a cone of sensitivity which responds with a measurement of the closest point within this cone and a maximum and minimum range. +If the measurement is valid (i.e. the measurement is within the maximum and minimum range and the attitude of the MAV is sufficiently close to zero so as to have the measurement returned be of the perpendicular distance from the ground to the MAV) we use the following measurement model: +\begin{equation} +\begin{aligned} + \zsonar &= z + \zeta \\ + \vert \zeta \vert &\leq \zeta_{max} +\end{aligned} +\end{equation} + + +\section{Derivation} + +\newcommand{\alphahat}{\bm{\hat{\alpha}}} + +The derivation of the filter follows a predict-update sequence much like common nonlinear attitude observers. +Simple kinematics dictate that altitude will evolve according to the double integral of acceleration. + +\begin{equation} + \zhat(t) = \int_0^t\int_0^t (\RbI\acc) \cdot \khat \; dtdt + \label{eq:simple_dynamics} +\end{equation} + +Substituting the expected value of equation~\ref{eq:accel_model} into~\ref{eq:simple_dynamics} yields the following equation for the main predict step of the filter + +\begin{equation} + \zhat(t) = \int_0^t\int_0^t \left(\RbI \left(\ameas + \alphahat\right) \right) \cdot \khat \; dtdt +\end{equation} + +As sonar and barometer are available, update steps are performed to correct drift and converge on accurate estimates for $\alphahat$. + + + + + + +\bibliographystyle{plain} +\bibliography{./library} + + +\end{document} + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/estimator.tex b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/estimator.tex new file mode 100644 index 0000000..0931196 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/estimator.tex @@ -0,0 +1,446 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% Short Sectioned Assignment +% LaTeX Template +% Version 1.0 (5/5/12) +% +% This template has been downloaded from: +% http://www.LaTeXTemplates.com +% +% Original author: +% Frits Wenneker (http://www.howtotex.com) +% +% License: +% CC BY-NC-SA 3.0 (http://creativecommons.org/licenses/by-nc-sa/3.0/) +% +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +%---------------------------------------------------------------------------------------- +% PACKAGES AND OTHER DOCUMENT CONFIGURATIONS +%---------------------------------------------------------------------------------------- + +\documentclass[paper=a4, fontsize=11pt]{scrartcl} % A4 paper and 11pt font size + +\usepackage[T1]{fontenc} % Use 8-bit encoding that has 256 glyphs +\usepackage{fourier} % Use the Adobe Utopia font for the document - comment this line to return to the LaTeX default +\usepackage[english]{babel} % English language/hyphenation +\usepackage{amsmath,amsfonts,amsthm} % Math packages + +\usepackage{lipsum} % Used for inserting dummy 'Lorem ipsum' text into the template + +\usepackage{sectsty} % Allows customizing section commands +\allsectionsfont{\centering \normalfont\scshape} % Make all sections centered, the default font and small caps + +\usepackage{fancyhdr} % Custom headers and footers +\usepackage{bm} +\usepackage{graphicx} +\usepackage{upgreek} +\pagestyle{fancyplain} % Makes all pages in the document conform to the custom headers and footers +\fancyhead{} % No page header - if you want one, create it in the same way as the footers below +\fancyfoot[L]{} % Empty left footer +\fancyfoot[C]{} % Empty center footer +\fancyfoot[R]{\thepage} % Page numbering for right footer +\renewcommand{\headrulewidth}{0pt} % Remove header underlines +\renewcommand{\footrulewidth}{0pt} % Remove footer underlines +\setlength{\headheight}{13.6pt} % Customize the height of the header + +\numberwithin{equation}{section} % Number equations within sections (i.e. 1.1, 1.2, 2.1, 2.2 instead of 1, 2, 3, 4) +\numberwithin{figure}{section} % Number figures within sections (i.e. 1.1, 1.2, 2.1, 2.2 instead of 1, 2, 3, 4) +\numberwithin{table}{section} % Number tables within sections (i.e. 1.1, 1.2, 2.1, 2.2 instead of 1, 2, 3, 4) + +%---------------------------------------------------------------------------------------- +% TITLE SECTION +%---------------------------------------------------------------------------------------- + +\newcommand{\horrule}[1]{\rule{\linewidth}{#1}} % Create horizontal rule command with 1 argument of height + +\title{ +\normalfont \normalsize +\textsc{MAGICC Lab - Brigham Young University} \\ [25pt] % Your university, school and/or department name(s) +\horrule{0.5pt} \\[0.4cm] % Thin top horizontal rule +\huge Estimator \\ % The assignment title +\horrule{2pt} \\[0.5cm] % Thick bottom horizontal rule +} + +\author{James Jackson} % Your name + +\date{\normalsize\today} % Today's date or a custom date + +\begin{document} + +\maketitle % Print the title + +%---------------------------------------------------------------------------------------- +% PROBLEM 1 +%---------------------------------------------------------------------------------------- + +\section{Introduction} + +The estimator is used to calculate an estimate of the attitude and angular velocity of the multirotor. It is assumed that the flight controller is mounted rigidly to the body of the aircraft (perhaps with dampening material to remove vibrations from the motors), such that measurements of the onboard IMU are consistent with the motion of the aircraft. + +Due to the limited computational power on the embedded processor, and to calculate attitude estimates at speeds up to 1000Hz, a simple complementary filter is used, rather than an extended Kalman filter. In practice, this method works extremely well, and it used widely throughout commercially available autopilots. There are a variety of complementary filters, but the general theory is the same. A complementary filter is a method to fuse the measurements from a gyroscope, accelerometer and sometimes magnetometer to produce an estimate of the attitude of the MAV. + +\section{Sensors} +There are a variety of sensors available on most flight control units, but we will limit our discussion to accelerometers, rate gyroscopes and magnetometers. Each of these is important in estimating the attitude of an MAV. + +\subsection{Accelerometers} + +Accelerometers measure all the forces acting on the aircraft. We can assume that these forces consist primarily of forces from the propellers, but it often also consists of vibrations from unbalanced motors and propellers, wind, ground effect, and a variety of other sources. One thing accelerometers do \textit{not} measure is acceleration due to gravity. As a result, if you hold an accelerometer still and look at it's measurements, you'll notice it measures the forces required to hold it in place. For example, if you set an accelerometer on a table, it will measure the normal force the table exerts on the accelerometer. If we assume that the accelerometer is at rest (albeit a rather significant assumption for a MAV), then we can assume that the forces acting on the accelerometer must be directly opposite gravity. Knowing then the direction of gravity with respect to the body-fixed axes of the MAV allows us to back out the MAV's roll and pitch angles. (see Figure~\ref{fig:accelerometer_measure}.) + +\begin{figure}[h] +\centering +\includegraphics[width=0.5\textwidth]{fig/accelerometer_measurement.png} +\caption{Illustration of acceleromemeter measurement if MAV is at steady state. Because the accelerometer does not measure gravity, if we assume that the MAV is not accelerating, then the only accelerations measured are those which counteract gravity. The angle $\phi$ can be therefore calculated using the vector $y_{acc}$} +\label{fig:accelerometer_measure} + +\end{figure} + +As you might expect, a MAV is not always at rest, so accelerometer measurements tend to bounce around as the MAV accelerates to move around. In addition, there are often also a lot of high-frequency external forces (such as vibrations induced by imbalanced propellers and motors) on a MAV in flight which adds noise to the accelerometer measurement. We can assume, however, that these accelerations are short-lived, and the accelerometer measurement remains stable over time. + +Modern MEMS accelerometers suffer from a significant degree of temperature-dependent bias. This can be compensated for by recording the value of the stationary bias for all axes of the accelerometer vs temperature, and performing a least-squares approximation. In ROSflight, this approximation is first-order, and takes place on the onboard computer to take advantage of the superior computing power and ability to handle large amounts of data. Biases and compensation coefficients are then sent and applied on the flight controller. + +\subsection{Rate Gyrocopes} + +Rate Gyroscopes, or gyros, on the other hand, directly measure the angular velocity of the IMU. Gyros are not susceptible to external forces like accelerometers, and instead measure angular velocity directly, but integrating gyroscopes over time to calculate attitude would lead to large amounts of drift. Common MEMS rate gyros also often have some non-zero bias which must be corrected in order for their use on MAVs. This bias wanders in a stochastic manner, and cannot be corrected through temperature compensation. It can, however, be estimated using certain filters. + +\subsection{Magnetometers} + +Magnetometers are often included on many flight control units, and in theory, act like a compass by measuring earth's magnetic field. Using both the magnetometer and the accelerometer allows you to solve for both the attitude and heading of the vehicle. Without a magnetometer, the MAV's attitude roll and pitch angles can be estimated, but the heading angle is unobservable. + +However, because most MAVs now use electric motors, the magnetic field created by these motors, and high-current electricity flowing throughout the MAV, the magnetic field is subject to a very large amount of noise during flight. As a result, magnetometers are not very reliable in practice, and should be supplanted instead with GPS. In this derivation, we will assume that we are not using a magnetometer. + +The magnetometer however, is used very similarly to the accelerometer. In the abscence of other magnetic noise, the vector returned by the magnetometer measurement can be compared directly with the known inertial magnetic field. If you desire to incorporate the magnetometer into your estimator, you can simply copy the accelerometer update equations and instead of using the gravity vector as a reference, use the vector describing earth's magnetic field at your location. + +\section{Complementary Filtering} +The idea behind complementary filtering is to try to get the ``best of both worlds'' of gyros and accelerometers. Gyros are very accurate in short spaces of time, but they are subject to drift. Accelerometers don't drift in the long scheme of things, but they are noisy as the MAV moves about. So, to solve these problems, the complementary filter primarily propagates states using gyroscope measurements, but then corrects drift with the accelerometer. In a general sense, it is like taking a high-pass filtered version of gyroscope measurements, and a low-pass filtered version of accelerometers, and fusing the two together in a manner that results in an estimate that is stable over time, but also able to handle quick transient motions. + +\section{Attitude Representation} +There are a number of ways to represent the attitude of a MAV. Most commonly, attitude is represented in terms of the euler angles yaw, pitch and roll, but it can also be represented in other ways, such as rotation matrices, and quaternions. + +\subsection{Euler Angles} +Euler angles represent rotations about three different axes, usually, the z, y, and x axes in that order. This method is often the most easy for users to understand and interpret, but it is by far the least computationally efficient. To propagate euler angles, the following kinematics are employed: +\begin{equation} + \begin{bmatrix} + \dot{\phi} \\ + \dot{\theta} \\ + \dot{\psi} \\ + \end{bmatrix} + = + \begin{bmatrix} + 1 & \sin(\phi) \tan(\theta) & \cos(\phi)\tan(\theta) \\ + 0 & \cos(\phi) & -\sin(\phi) \\ + 0 & \frac{\sin(\phi)}{\cos(\theta)} & \frac{\cos(\phi)}{\cos(\theta)} \\ + \end{bmatrix} + \begin{bmatrix} + p \\ + q \\ + r \\ + \end{bmatrix} +\end{equation} + +Note the large number of trigonometric functions associated with this propagation. In a complementary filter, this will be evaluated at every measurement, and the non-linear coupling between $\bm{\omega}$ and the attitude becomes very expensive, particularly on embedded processors. + +Another shortcoming of euler angles is known as ``gimbal lock''. Gimbal lock occurs at the ``singularity'' of the euler angle representation, or pointing directly up or down. The problem occurs because there is more than one way to represent this particular rotation. There are some steps one can take to handle these issues, but it is a fundamental problem associated with using euler angles, and motivates the other attitude representations. + +\subsection{Rotation Matrix} + +Rotation matrices, are often used in attitude estimation, because they do not suffer from gimbal lock, are quickly converted to and from euler angles, and because of their simple kinematics. + +\begin{equation} + \dot{R} = \lfloor\bm{\omega}\rfloor R +\end{equation} + +where $\lfloor \bm{\omega} \rfloor$ is the skew-symmetric matrix of $\bm{\omega}$, and is related to calculating the cross product. + +\begin{equation} + \lfloor\bm{\omega}\rfloor = + \begin{bmatrix} + 0 & -r & q \\ + r & 0 & -p \\ + -q & p & 0 + \end{bmatrix} +\end{equation} + This propagation step is linear with respect to the angular rates, which simplifies calculation significantly. + +A rotation matrix from the inertial frame to body frame can be constructed from euler angles via the following formula: +\newcommand{\ct}{c\theta} +\newcommand{\cp}{c\phi} +\newcommand{\cs}{c\psi} +\newcommand{\st}{s\theta} +\newcommand{\sphi}{s\phi} +\newcommand{\spsi}{s\psi} +\begin{equation} + R = \begin{bmatrix} + \ct\cs & \ct\spsi & -\st \\ + \sphi\st\cs-\cp\spsi & \sphi\st\spsi+\cp\cs & \sphi\ct \\ + \cp\st\cs+\sphi\spsi & \cp\st\spsi-\sphi\cs & \sphi\st \\ + \end{bmatrix} +\end{equation} + +and converting back to euler angles is done via the following; +\begin{equation} + \begin{bmatrix} + \phi \\ + \theta \\ + \psi \\ + \end{bmatrix} = + \begin{bmatrix} + \textrm{atan2}\left(R_{32}, R_{33}\right) \\ + \textrm{atan2}\left(-R_{31}, \sqrt{R_{21}^2 + R_{33}^2}\right) \\ + \textrm{atan2}\left(R_{21}, R_{11}\right) \\ + \end{bmatrix} +\end{equation} + +\subsection{Quaternions} + +Quaternions are a number system which extends complex numbers. They have four elements, commonly known as $w$, $x$, $y$, and $z$. The last three elements can be though of as describing an axis, $\beta$ about which a rotation occurred, while the first element, $w$ can be though of as describing the amount of rotation $\alpha$ about that axis. (see eq~\ref{eq:euler_to_axis_angle}). While this may seem straight-forward, quaternions are normalized so that they can form a group. (That is, a quaternion multiplied by a quaternion is a quaternion), so they end up being really difficult for a human being to interpret just by looking at the values. However, they provide some amazing computational efficiencies, most of which comes from the following special mathematics associated with quaternions. + +First, just the definition of a quaternion: + +\begin{equation} + \bm{q} = \begin{bmatrix} + q_w \\ + q_x \\ + q_y \\ + q_z + \end{bmatrix} + = \begin{bmatrix} + \cos(\alpha/2) \\ + \sin(\alpha/2)\cos(\beta_x) \\ + \sin(\alpha/2)\cos(\beta_y) \\ + \sin(\alpha/2)\cos(\beta_y) + \end{bmatrix} + = \begin{bmatrix} + s \\ + \bm{v}_x \\ + \bm{v}_y \\ + \bm{v}_z + \end{bmatrix} + \label{eq:euler_to_axis_angle} +\end{equation} + +and second, some formulas to convert to and from euler angles. + + +\begin{equation} + \bm{q} = + \begin{bmatrix} + \cos(\theta/2)\cos(\theta/2)\cos(\psi/2) + \sin(\phi/2)\sin(\theta/2)\sin(\psi/2) \\ + \sin(\theta/2)\cos(\theta/2)\cos(\psi/2) - \cos(\phi/2)\sin(\theta/2)\sin(\psi/2) \\ + \cos(\theta/2)\sin(\theta/2)\cos(\psi/2) + \sin(\phi/2)\cos(\theta/2)\sin(\psi/2) \\ + \cos(\theta/2)\cos(\theta/2)\sin(\psi/2) - \sin(\phi/2)\sin(\theta/2)\cos(\psi/2) \\ + \end{bmatrix} +\end{equation} + +\begin{equation} + \begin{bmatrix} + \phi \\ + \theta \\ + \psi \\ + \end{bmatrix} + = + \begin{bmatrix} + \textrm{atan2}\left( 2\left(q_wq_x + q_yq_z\right),1-2\left(q_x^2+q_y^2\right) \right) \\ + \textrm{sin}^{-1}\left( 2 \left( q_wq_y - q_zq_x \right) \right) \\ + \textrm{atan2}\left( 2 \left( q_wq_z + q_xq_y \right), 1 - 2 \left( q_y^2 q_z^2 \right) \right) + \end{bmatrix} + \label{eq:euler_from_quat} +\end{equation} + +Quaternions are ``closed'' under the following operation, termed quaternion multiplication. + +\begin{equation} + \bm{q_1} \otimes \bm{q_2} = \begin{bmatrix} + s_1s_2 - \bm{v_1}^\top\bm{v_2} \\ + s_1\bm{v_2} + s_2\bm{v_1} + \bm{v_1} \times \bm{v_2} + \end{bmatrix} +\end{equation} + +To take the ``inverse'' of a quaternion is simply to multiply $s$ or $\bm{v}$ by $-1$ + +\begin{equation} + \bm{q}^{-1} = \begin{bmatrix} + -q_w \\ + q_x \\ + q_y \\ + q_z + \end{bmatrix} + = \begin{bmatrix} + q_w \\ + -q_x \\ + -q_y \\ + -q_z + \end{bmatrix} +\end{equation} + +and to find the difference between two quaternions, just quaternion multiply the inverse of one quaternion with the other. + +\begin{equation} + \tilde{\bm{q}} = \hat{\bm{q}}^{-1} \otimes \bm{q} +\end{equation} + +However, the most important aspect of quaternions is the way we propagate dynamics. + +\begin{equation} + \dot{\bm{q}} = \frac{1}{2} \bm{q} \otimes \bm{q_{\omega}} +\end{equation} + +where $\bm{q_{\omega}}$ is the pure quaternion created from angular rates. + +\begin{equation} + \bm{q_{\omega}} = \textrm{p}(\bm{\omega}) = + \begin{bmatrix} + 0 \\ + p \\ + q \\ + r + \end{bmatrix} +\end{equation} + +What this means is that, like rotation matrices, quaternion dynamics are \textit{linear} with respect to angular rates, as opposed to euler angles, which are non-linear, and they take less computation than rotation matrices because they have fewer terms. Casey et al.~\cite{Casey2013} performed a study comparing all three of the above representations, and found that complementary filters using an euler angle representation took \textbf{12 times} longer to compute on average than a quaternion-based filter. Quaternions were also about 20\% more efficient when compared with rotation matrices. For these reasons, ROSflight uses quaternions in its filter. + +\section{Derivation} + +ROSflight implements the quaternion-based passive ``Mahony'' filter as described in~\cite{Mahony2007}. In particular, we implement equation 47 from that paper, which also estimates gyroscope biases. A Lyuapanov stability analysis is performed in that paper, in which it is shown that all states and biases, except heading, are globally asymptotically stable given an accelerometer measurement and gyroscope. The above reference also describes how a magnetometer can be integrated in a similar method to the accelerometer. That portion of the filter is ommitted here due to the unreliable nature of magnetometers onboard modern small UAS. + +\subsection{Passive Complementary Filter} +The original filter propagates per the following dynamics: + +\newcommand{\wacc}{\bm{\omega}_{acc}} +\begin{equation} + \begin{aligned} + \bm{\dot{\hat{q}}} &= \frac{1}{2} \bm{\hat{q}} \otimes \bm{q}_{\omega}\\ + \bm{\dot{\hat{b}}} &= -2k_I\wacc + \end{aligned} + \label{eq:traditional_prop} +\end{equation} + + +where $\bm{q}_{\omega}$ is the pure quaternion formed from a composite $\bm{\omega}_{comp}$ which consists of the estimated angular rates, $\bar{\bm{\omega}}$, the estimated gyroscope biases, $\hat{\bm{b}}$, and an adjustment term, calculated from accelerometer measurements, $\bm{\omega}_{acc}$. $k_p$ and $k_I$ are constant gains used in determining the dynamics of the filter. +\begin{equation} +\begin{aligned} + \bm{q}_{\omega} &= \textrm{p}\left(\bar{\bm{\omega}} - \hat{\bm{b}} + k_P\wacc\right) \\ + &= \textrm{p}\left( \bm{\omega}_{comp} \right) + \label{eq:q_omega} +\end{aligned} +\end{equation} + +\newcommand{\avec}{\bm{a}} +\newcommand{\gvec}{\bm{g}} +\newcommand{\qmeas}{\bm{q}_{acc}} +\newcommand{\gamvec}{\bm{\gamma}} +\newcommand{\norm}[1]{\left\lVert#1\right\rVert} +\newcommand{\wbar}{\bm{\bar{\omega}}} +\newcommand{\w}{\bm{\omega}} +\newcommand{\qhat}{\hat{\bm{q}}} + +$\wacc$ can be described as the error in the attitude as predicted by the accelerometer. To calculate $\wacc$ the quaternion describing the rotation between the accelerometer estimate and the inertial frame, $\qmeas$, is first calculated +\begin{equation} +\begin{aligned} + \avec &= + \begin{bmatrix} + a_x \\ + a_y \\ + a_z \\ + \end{bmatrix}, + \qquad + \gvec &= + \begin{bmatrix} + 0 \\ + 0 \\ + 1 \\ + \end{bmatrix}, \qquad + \gamvec &= \frac{\avec+\gvec}{\norm{\avec+\gvec}}, \qquad + \qmeas &= + \begin{bmatrix} + \avec^\top \gamvec \\ + \avec \times \gamvec + \end{bmatrix} +\end{aligned} +\end{equation} + +\newcommand{\qtilde}{\tilde{\bm{q}}} +\newcommand{\vtilde}{\tilde{\bm{v}}} +Next, the quaternion error between the estimate $\qhat$ and the accelerometer measure $\qmeas$ is calculated. +\begin{equation} + \qtilde = \qmeas^{-1} \otimes \qhat = + \begin{bmatrix} + \tilde{s}\\ + \vtilde + \end{bmatrix} +\end{equation} + +\newcommand{\wmeas}{\bm{\omega}_{acc}} +Finally, $\qmeas$ is converted back into a 3-vector per the method described in eq. 47a of~\cite{Mahony2007}. +\begin{equation} + \wmeas = 2\tilde{s}\vtilde +\end{equation} + +Although the formulation in Eq.~\ref{eq:traditional_prop} is more concise, in implementation, $\bm{q}_{\omega}$ is never actually formed, instead the composite $\bm{\omega}_{comp}$ vector of Eq.~\ref{eq:q_omega} is directly substituted into equation~\ref{eq:mat_exponential}. Gyroscope bias propagation is performed using standard euler integration, because they are assumed to be nearly constant. + +\subsection{Modifications to Original Passive Filter} +There have been a few modifications to the passive filter described in~\cite{Mahony2007}, consisting primarily of contributions from~\cite{Casey2013}. Firstly, rather than simply taking gyroscope measurements directly as an estimate of $\bm{\omega}$, a quadratic polynomial is used to approximate the true angular rate from gyroscope measurements to reduce error. In~\cite{Casey2013}, this process was shown to reduce RMS error by more than 1,000 times. There are additional steps associated with performing this calculation, but the benefit in accuracy more than compensates for the extra calculation time. The equation to perform this calculation is shown in Eq.~\ref{eq:quad_approx}. + +\begin{equation} + \bar{\bm{\omega}} = \frac{1}{12}\left(-\bm{\omega}\left(t_{n-2}\right) + 8\bm{\omega}\left(t_{n-1}\right) + 5\bm{\omega}\left(t_n\right) \right) + \label{eq:quad_approx} +\end{equation} + +where $\bm{\omega}(t_{n-x})$ is the gyroscope measurement of the angular rate $x$ measurements previous. + +The second modification is in the way that the attitude is propagated after finding $\bm{\dot{\hat{q}}}$. Instead of performing the standar euler integration + +\begin{equation} + \bm{\hat{q}}_n = \bm{\hat{q}}_{n-1}+\bm{\dot{\hat{q}}}_{n}dt +\end{equation} + +we use an approximation of the matrix exponential. The matrix exponential arises out of the solution to the differential equation $\dot{x} = Ax$, namely +\begin{equation} + x(t) = e^{At} x(0) +\end{equation} + +and the discrete-time equivalent +\begin{equation} + x(t_{n+1}) = e^{hA}(t_n) +\end{equation} + +This discrete-time matrix exponential can be approximated by first expanding the matrix exponential into the infinite series + +\begin{equation} + e^{A} = \sum_{k=0}^\infty \dfrac{1}{k!}A^k +\end{equation} + + +and then grouping odd and even terms from the infinite series into two sinusoids, and results in the following equation for the propagation of the quaternion dynamics~\ + + +\begin{equation} + \qhat(t_n) = \left[ \cos \left( \frac{\norm{\w}h}{2}\right)I_4 + \frac{1}{\norm{\w}} \sin \left( \frac{\norm{\w}h}{2} \right) \lfloor\w\rfloor_4 \right] \qhat(t_{n-1}) + \label{eq:mat_exponential} +\end{equation} + +where $\lfloor\w\rfloor_4$ is the 4x4 skew-symmetric matrix formed from $\w$ + +\begin{equation} + \lfloor\w\rfloor_4 = + \begin{bmatrix} + 0 & - p & - q & - r \\ + p & 0 & r & - q \\ + q & - r & 0 & p \\ + r & q & - p & 0 \\ + \end{bmatrix} +\end{equation} + + +\subsection{Tuning} +The filter can be tuned with the two gains $k_P$ and $k_I$. Upon initialization, $k_P$ and $k_i$ are set very high, so as to quickly cause the filter to converge upon approprate values. After a few seconds, they are both reduced by a factor of 10, to a value chosen through manual tuning. A high $k_P$ will cause sensitivity to transient accelerometer errors, while a small $k_P$ will cause sensitivity to gyroscope drift. A high $k_I$ will cause biases to wander unnecessarily, while a low $k_I$ will result in slow convergence upon accurate gyroscope bias estimates. These parameters generally do not need to be modified from the default values. + +\subsection{Implementation} +The entire filter is implemented in float-based quaternion calculations. Even though the STM32F10x microprocessor does not contain a floating-point unit, the entire filter has been timed to take about 370$\upmu$s. The extra steps of quadratic integration and matrix exponential propagation can be ommited for a 20$\upmu$s and 90$\upmu$s reduction in speed, respectively. Even with these functions, however, this is sufficiently short to run at well over 1000Hz, which is the update rate of the MPU6050 on the naze32. +Control is performed according to euler angle estimates, and to reduce the computational load of converting from quaternion to euler angles (See Equation \ref{eq:euler_from_quat}), a lookup table approximation of atan2 and asin are used. The Invensense MPU6050 has a 16-bit ADC and an accelerometer and gyro onboard. The accelerometer, when scaled to $\pm$4g, has a resolution of 0.002394 m/s$^2$. The lookup table method used to approximate atan2 and asin in the actual implementation is accurate to $\pm$ 0.001 rad. Given the accuracy of the accelerometer, use of this lookup table implementation is justfied. The C-code implementation of the estimator can be found in the file \begin{verbatim} src/estimator.c \end{verbatim} + +\bibliographystyle{plain} +\bibliography{./library} + + +\end{document} + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/fig/motor_layout.jpg b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/fig/motor_layout.jpg new file mode 100644 index 0000000..40351a8 Binary files /dev/null and b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/fig/motor_layout.jpg differ diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/library.bib b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/library.bib new file mode 100644 index 0000000..0e9463d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/library.bib @@ -0,0 +1,25 @@ +Automatically generated by Mendeley Desktop 1.16.1 +Any changes to this file will be lost if it is regenerated by Mendeley. + +BibTeX export options can be customized via Options -> BibTeX in Mendeley Desktop + +@article{Casey2013, +abstract = {Complementary filter-based algorithms for attitude estimation seek to minimize the short-comings associated with the low-cost MEMS sensors and low-power embedded processors that are frequently used in unmanned aerial vehicles. This paper explores the performance impact of three different ingredients for attitude estimation within the complementary filter framework: 1) kinematic propagation, 2) attitude representation, and 3) the assumptions on the behavior of the angular rate vector between samples. Forward Euler integration and matrix exponential propagation methods are compared within several attitude representations, namely the direction cosine matrix (DCM), quaternion, Euler angle, and the angle-axis schemes. Assumptions of constant, linear, and quadratic angular velocities between samples are also examined. The resulting algorithms are evaluated from the points of view of accuracy, computational load, and noise response. Tests using analytic inputs as well as real data within the framework of the SLUGS autopilot are performed to evaluate algorithm performance. The results of the experiments indicate that by combining matrix exponential propagation with a quaternion representation of attitude high accuracy can be obtained with a standard processor.}, +author = {Casey, Robert T. and Karpenko, Mark and Curry, Renwick and Elkaim, Gabriel}, +doi = {10.2514/6.2013-4615}, +file = {:home/capn/Downloads/Paper from Ren Curry - Read and comment - Casey2013GNC (1).pdf:pdf}, +isbn = {978-1-62410-224-0}, +journal = {AIAA Guidance, Navigation, and Control (GNC) Conference}, +pages = {1--25}, +title = {{Attitude Representation and Kinematic Propagation for Low-Cost UAVs}}, +url = {http://arc.aiaa.org/doi/abs/10.2514/6.2013-4615}, +year = {2013} +} +@article{Mahony2007, +abstract = {This paper considers the problem of obtaining good attitude estimates from measurements obtained from typical low cost inertial measurement units. The outputs of such systems are characterised by high noise levels and time varying additive biases. We formulate the filtering problem as deterministic observer kinematics posed directly on the special orthogonal group SO(3) driven by reconstructed attitude and angular velocity measurements. Lyapunov analysis results for the proposed observers are derived that ensure almost global stability of the observer error. The approach taken leads to an observer that we term the direct complementary filter. By exploiting the geometry of the special orthogonal group a related observer, termed the passive complementary filter, is derived that decouples the gyro measurements from the reconstructed attitude in the observer inputs. Both the direct and passive filters can be extended to estimate gyro bias on-line. The passive filter is further developed to provide a formulation in terms of the measurement error that avoids any algebraic reconstruction of the attitude. This leads to an observer on SO(3), termed the explicit complementary filter, that requires only accelerometer and gyro outputs; is suitable for implementation on embedded hardware; and provides good attitude estimates as well as estimating the gyro biases on-line. The performance of the observers are demonstrated with a set of experiments performed on a robotic test-bed and a radio controlled unmanned aerial vehicle}, +author = {Mahony, R and Hamel, Tarek and Pflimlin, Jean-michel and Mahony, Robert and Hamel, Tarek and Pflimlin, Jean-michel}, +file = {:home/capn/.local/share/data/Mendeley Ltd./Mendeley Desktop/Downloaded/Mahony et al. - 2007 - Non-linear complementary filters on the special orthogonal group.pdf:pdf}, +title = {{Non-linear complementary filters on the special orthogonal group}}, +url = {https://hal.archives-ouvertes.fr/hal-00488376}, +year = {2007} +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/mixer.tex b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/mixer.tex new file mode 100644 index 0000000..3af75ce --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/mixer.tex @@ -0,0 +1,135 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% Short Sectioned Assignment +% LaTeX Template +% Version 1.0 (5/5/12) +% +% This template has been downloaded from: +% http://www.LaTeXTemplates.com +% +% Original author: +% Frits Wenneker (http://www.howtotex.com) +% +% License: +% CC BY-NC-SA 3.0 (http://creativecommons.org/licenses/by-nc-sa/3.0/) +% +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +%---------------------------------------------------------------------------------------- +% PACKAGES AND OTHER DOCUMENT CONFIGURATIONS +%---------------------------------------------------------------------------------------- + +\documentclass[paper=a4, fontsize=11pt]{scrartcl} % A4 paper and 11pt font size + +\usepackage[T1]{fontenc} % Use 8-bit encoding that has 256 glyphs +\usepackage{fourier} % Use the Adobe Utopia font for the document - comment this line to return to the LaTeX default +\usepackage[english]{babel} % English language/hyphenation +\usepackage{amsmath,amsfonts,amsthm} % Math packages + +\usepackage{lipsum} % Used for inserting dummy 'Lorem ipsum' text into the template + +\usepackage{sectsty} % Allows customizing section commands +\allsectionsfont{\centering \normalfont\scshape} % Make all sections centered, the default font and small caps + +\usepackage{fancyhdr} % Custom headers and footers +\usepackage{bm} +\usepackage{upgreek} +\usepackage{tikz} +\usetikzlibrary{shapes, arrows} +\pagestyle{fancyplain} % Makes all pages in the document conform to the custom headers and footers +\fancyhead{} % No page header - if you want one, create it in the same way as the footers below +\fancyfoot[L]{} % Empty left footer +\fancyfoot[C]{} % Empty center footer +\fancyfoot[R]{\thepage} % Page numbering for right footer +\renewcommand{\headrulewidth}{0pt} % Remove header underlines +\renewcommand{\footrulewidth}{0pt} % Remove footer underlines +\setlength{\headheight}{13.6pt} % Customize the height of the header + +\setlength\parindent{0pt} % Removes all indentation from paragraphs - comment this line for an assignment with lots of text + +%---------------------------------------------------------------------------------------- +% TITLE SECTION +%---------------------------------------------------------------------------------------- + +\newcommand{\horrule}[1]{\rule{\linewidth}{#1}} % Create horizontal rule command with 1 argument of height + +\title{ +\normalfont \normalsize +\textsc{MAGICC Lab - Brigham Young University} \\ [25pt] % Your university, school and/or department name(s) +\horrule{0.5pt} \\[0.4cm] % Thin top horizontal rule +\huge Mixer \\ % The assignment title +\horrule{2pt} \\[0.5cm] % Thick bottom horizontal rule +} + +\author{James Jackson} % Your name + +\date{\normalsize\today} % Today's date or a custom date + +\begin{document} + +\maketitle % Print the title + +%---------------------------------------------------------------------------------------- +% PROBLEM 1 +%---------------------------------------------------------------------------------------- + +\section{Introduction} + +The mixer is a mechanism by which abstract roll rate, pitch rate, yaw rate and throttle commands are mapped to the actuators of the MAV. In it's simplest form, the mixer is simply a matrix multiplication which maps these inputs onto motor outputs. + +In addition to the mixer, there is some saturation functionality baked into ROSflight. This functionality is insipired by that implemented in cleanflight, and serves to ensure that the MAV is always capable of responding to inputs, even during the most aggressive maneuvers. + +The flow of information through the firmware can be visualized in Figure~\ref{fig:mixer_flow} + +\begin{figure} + \centering + \tikzstyle{int}=[draw, fill=white, minimum size=6em] + \tikzstyle{init} = [pin edge={to-,thin,black}] + +\begin{tikzpicture}[node distance=4cm,auto,>=latex'] + \node [int] (a) {mixer}; + \node (b) [left of=a,node distance=4cm, coordinate] {a}; + \node [int] (c) [right of=a] {sat}; + \node [coordinate] (end) [right of=c, node distance=4cm]{}; + \path[->] (b) edge node {$\bm{\omega_c}, F$} (a); + \path[->] (a) edge node {$\hat{\tau}_1, \hat{\tau}_2 \ldots \hat{\tau}_n$} (c); + \draw[->] (c) edge node {$\tau_1, \tau_2 \ldots \tau_n$} (end) ; +\end{tikzpicture} +\label{fig:mixer_flow} +\caption{The flow of information through the mixer and saturation function} +\end{figure} + +\section{Mixer} + +As mentioned before, the mixer is essentially a matrix multiplication. There are a number of mixers pre-programmed into ROSflight2, and they are published in [CITE]. They are designed to match the original mixers programmed into cleanflight, and they match the corresponding motor output diagrams, shown in Figure~\ref{fig:motor_layout}. First, an abstract command is calculated by the rate controller, or passed directly into the mixer (see controller paper), in the form of a four-tuple. $(F, x, y, z)$. In general, these are the actuatable degrees of freedom in the MAV, but specifically, in the case of a multirotor, this is interpreted as Force, Roll Torque, Pitch Torque, and Yaw Torque, $(F, \tau_x, \tau_y \tau_z)$, and in the case of a fixed-wing MAV, this is interpreted as throttle, aileron deflection, elevator deflection and rudder deflection $(T, \delta_a, \delta_e, \delta_r)$. The mixer then maps these commands to the 8 outputs available on the flight controller and executes the command. + +As an example, we will analyze the quadcopter-X mixing to show how it works. The rate controller, based on some higher-level input, calculates some command, $\bm{\omega}$. This is passed into the mixer, which is essentially the following 4x4 matrix: + +\begin{equation} + \begin{pmatrix} + 1 & 1 & 1 & 1 \\ + -1 &-1 & 1 & 1 \\ + -1 & 1 &-1 & 1 \\ + 1 &-1 &-1 & 1 \\ + \end{pmatrix} +\end{equation} + +The remaining outputs are made available to modification by the GPIO inputs to the FC via MAVlink. It is assumed that PID gains in higher-level functions perform the scaling between the different channels to acheive the desired output. + +In addition, each mixer contains information about what kind of output each output channel is. For example, in the case of a fixed-wing. The output of the mixer for the first channel is attached to a motor while the other three are attached to servos. The output of a mixer to a servo must lie between -500 and 500, after which it is shifted up to the center of the servo output, or 1500$\upmu$s. Motor commands, on the other hand, are restricted to lie between 0 and 1000, and mapped to the full PWM range for standard ESC operation. + + +\begin{figure}[h] + \centering + \includegraphics[scale=0.3]{fig/motor_layout.jpg} + \label{fig:motor_layout} + \caption{The motor layout for the mixers} +\end{figure} + +\section{Saturation} + +There are often agressive maneuvers which may cause multiple motor outputs to become saturated. This is of particular concern in multirotors, and can be illustrated in the example of the command of maximum roll while at full throttle in a quadcopter. Full throttle, with no other command, would normally cause all four motors to saturate at a maximum PWM command of 2000$\upmu$s. Mixing in a maximum roll command would cause two of the motors to reduce to 1500$\upmu$s, while the other two would go to 2500$\upmu$s. Because 2500$\upmu$s is beyond the maximum limit, the maximum roll command would actually be interpreted as a half-roll command as the difference between the motors on opposite sides of the MAV would be halved. To increase controllability in these sorts of situations, we take the motor control value from the mixer, before it is shifted up 1000$\upmu$s to the standard PWM range, and find the scaling factor which would reduce the maximum motor command to 1000$\upmu$s. We then apply this scaling factor to all other motors, and then shift them up to the standard PWM range of 1000$\upmu$s to 2000$\upmu$s. This does not completely solve the problem, because the maximum roll command is still reduced somewhat, but it trades off maximum thrust for some additional controllability. In the case of a simultaneous maximum roll and maximum throttle, two of the motors will receive a command of 2000$\upmu$s, while the other two will receive a command of 1333$\upmu$s, as opposed to the 1500$\upmu$s without the saturation, and maintains controllability even at high levels of throttle. + + + + +\end{document} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/rc.tex b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/rc.tex new file mode 100644 index 0000000..e2fa046 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/reports/rc.tex @@ -0,0 +1,355 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% Short Sectioned Assignment +% LaTeX Template +% Version 1.0 (5/5/12) +% +% This template has been downloaded from: +% http://www.LaTeXTemplates.com +% +% Original author: +% Frits Wenneker (http://www.howtotex.com) +% +% License: +% CC BY-NC-SA 3.0 (http://creativecommons.org/licenses/by-nc-sa/3.0/) +% +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +%---------------------------------------------------------------------------------------- +% PACKAGES AND OTHER DOCUMENT CONFIGURATIONS +%---------------------------------------------------------------------------------------- + +\documentclass[paper=a4, fontsize=11pt]{scrartcl} % A4 paper and 11pt font size + +\usepackage[T1]{fontenc} % Use 8-bit encoding that has 256 glyphs +\usepackage[english]{babel} % English language/hyphenation +\usepackage{amsmath,amsfonts,amsthm} % Math packages + +\usepackage{lipsum} % Used for inserting dummy 'Lorem ipsum' text into the template + +\usepackage{sectsty} % Allows customizing section commands +\allsectionsfont{\centering \normalfont\scshape} % Make all sections centered, the default font and small caps + +\usepackage{fancyhdr} % Custom headers and footers +\usepackage{bm} +\usepackage{upgreek} +\usepackage{tikz} +\usepackage{tabulary} +\usepackage{multirow} +\usepackage{array} +\usepackage{adjustbox} +\usepackage[section]{placeins} +\usetikzlibrary{shapes.geometric} +\usetikzlibrary{positioning} +\usetikzlibrary{shapes, arrows} +\renewcommand{\headrulewidth}{0pt} % Remove header underlines +\renewcommand{\footrulewidth}{0pt} % Remove footer underlines +\setlength{\headheight}{5pt} % Customize the height of the header + +%---------------------------------------------------------------------------------------- +% TITLE SECTION +%---------------------------------------------------------------------------------------- + +\newcommand{\horrule}[1]{\rule{\linewidth}{#1}} % Create horizontal rule command with 1 argument of height + +\title{ +\normalfont \normalsize +\textsc{MAGICC Lab - Brigham Young University} \\ [25pt] % Your university, school and/or department name(s) +\horrule{0.5pt} \\[0.4cm] % Thin top horizontal rule +\huge Offboard Control, RC and Safety Pilot Integration \\ % The assignment title +\horrule{2pt} \\[0.5cm] % Thick bottom horizontal rule +} + +\author{James Jackson} % Your name + +\date{\normalsize\today} % Today's date or a custom date + +\begin{document} + +\maketitle % Print the title + +%---------------------------------------------------------------------------------------- +% PROBLEM 1 +%---------------------------------------------------------------------------------------- + +\section{Introduction} + +A very important feature for ROSflight is the tight integration of an RC safety pilot. The safety pilot is usually a highly experienced RC operator who is capable of knowing when the computer is doing something unsafe and taking over fast enough to land the MAV safely so researchers can fix problems and try again. ROSflight can be used independently of an onboard computer similar to more fully-developed codes such as cleanflight and baseflight, however it is primarily designed to quickly test research code developed in ROS on hardware. This means that we can assume that the controls coming from the onboard computer may be suspect, and may at any time try to make the MAV do something drastic, (such as full-throttle into the ceiling or full-power front flips). While this may be exciting, it is often expensive and dangerous unless there is some safety pilot intervention. The RC controls are designed to be first interpreted, then mixed with the onboard controls in a way that the safety pilot has quick access to correct dangerous maneuvers commanded by the onboard computer but is primarily on stand-by while the computer has uninhibited access to the hardware. + +\begin{figure} + \centering + + \tikzstyle{block} = [draw, rectangle, + minimum height=3em, minimum width=6em] + \tikzstyle{node}=[draw, ellipse, minimum size=3em, + align=center] + + \begin{adjustbox}{max size={\textwidth}{0.2\textheight}} + \begin{tikzpicture} + \node[block] (rc) {RC}; + \node[block, right=5em of rc] (offboard) {MAVlink}; + \node[node, below right=2.5em and 1.5em of rc] (mux) {mux}; + \node[block, below=2.5em of mux] (combined) {Composite}; + + \draw[-triangle 60] (rc) -- (mux); + \draw[-triangle 60] (offboard) -- (mux); + \draw[-triangle 60] (mux) -- (combined); + \end{tikzpicture} + \end{adjustbox} + + \label{mux_configuration} + \caption{Diagram of how signals from RC and MAVlink are muxed in ROSflight} +\end{figure} + +\section{Building The Command Structure} + +To accomplish this task, a command structure is created from both the incoming rc commands and commands over the mavlink serial line. These structures are combined in the mux, as shown in figure~\ref{mux_configuration}. This structure has four channels, which represent the four actuatable degrees of freedom on the MAV. In general, the $x$ channel refers to roll, roll rate or aileron deflection, the $y$ channel to pitch, pitch rate or elevator deflection, the $z$ to yaw rate and rudder deflection and the $F$ channel to throttle. + + +\begin{table}[h] + \centering + \label{command_structure} + \caption{Command Structure} + \begin{tabular}{| c | c |} + \hline + \multirow{3}{*} {$x$ channel} + & flag \\ \cline{2-2} + & type \\ \cline{2-2} + & value \\ \hline + \multirow{3}{*} {$y$ channel} + & flag \\ \cline{2-2} + & type \\ \cline{2-2} + & value \\ \hline + \multirow{3}{*} {$z$ channel} + & flag \\ \cline{2-2} + & type \\ \cline{2-2} + & value \\ \hline + \multirow{3}{*} {$F$ channel} + & flag \\ \cline{2-2} + & type \\ \cline{2-2} + & value \\ \hline + \end{tabular} +\end{table} + +Each channel has three fields as shown in table~\ref{command_structure}. The flag field refers to whether or not that particular channel is being controlled in this message. If true, then the channel is active, and should be listened to. If false, then it should be ignored. If the message from both the offboard control and the RC are both inactive, then the RC signal is taken by default. The type field indicates the type of information being carried by this channel. For the $x$ and $y$ channels, this could be an angular rate in rad/s, or an angle in rad, or simply a servo command in $\upmu$s. the $z$ channel can carry only an angular rate in rad/s or servo command in $\upmu$s and the $F$ channel can carry a throttle from 0-1000$\upmu$s or an altitude command in m. The value field is simply the data being carried in the channel. This is interpreted according to the type field. + +The logic required to construct the rc command structure is shown in figure~\ref{fig:rc_flow}. The MAVLink structure is converted to its final form upon receiving the command, but the logic to do so is trivial, and is ommitted here for brevity. + +\begin{figure}[!htb] +\centering + \tikzstyle{block} = [draw, rectangle, + minimum height=3em, minimum width=6em, align=center] + \tikzstyle{node}=[draw, ellipse, minimum size=3em, + align=center] + \tikzstyle{dec}=[draw, diamond, aspect=3, align=center] + \tikzstyle{coordinate}=[draw, none] + \tikzstyle{a}=[-triangle 60] + + \begin{adjustbox}{max size={\textwidth}{0.79\textheight}} + \begin{tikzpicture}[scale=0.4] + + \node[node] (start) {start}; + \node[dec, below=2em of start] (time) {\footnotesize Has it been 20ms?}; + \node[node, right=2em of time] (done1) {done}; + \node[dec, below=1em of time] (fixed_wing) {Fixed Wing?}; + \node[dec, below left=2em and 4em of fixed_wing] (att_switch) {\footnotesize Att. Ctrl. Switch}; + \node[block, below right=2em and 4em of fixed_wing, text width = 11em] (pass) {\scriptsize x.type = PASSTHROUGH y.type = PASSTHROUGH z.type = PASSTHROUGH}; + \node [block, below left=2em and 2em of att_switch, text width = 7em] (angle) {\scriptsize x.type=ANGLE y.type=ANGLE}; + \node [block, below right=2em and 2em of att_switch, text width = 7em] (rate) {\scriptsize x.type=RATE y.type=RATE}; + \node [block, below=6em of att_switch, text width = 7em] (yaw_angle) {\scriptsize z.type=RATE}; + \node [dec, below=2em of yaw_angle] (f_switch) {\footnotesize F Ctrl. Switch}; + \node [block, below left=2em and 2em of f_switch] (F_alt) {\scriptsize F.type=ALTITUDE}; + \node [block, below right=2em and 2.5em of f_switch] (F_thr) {\scriptsize F.type=THROTTLE}; + + \node [block, below=2em of F_thr] (convert) {Convert PWM to Rad}; + + \node [dec, below=2em of convert] (att_over) {\scriptsize Att. override switch}; + + \node [dec, below left=2em and 2em of att_over] (lag) {\scriptsize override stick lag}; + \node [dec, left=2em of lag] (deviated) {\scriptsize sticks deviated?}; + + \node[block, below=10em of att_over, text width=6em] (xyz_active) {\scriptsize x.flag=ACTIVE y.flag=ACTIVE z.flag=ACTIVE}; + \node[block, below right=2em and 0em of deviated, text width = 6em] (set_lag) {\scriptsize set override stick lag}; + \node[block, below left=7em and 0em of deviated, text width=7em] (xyz_inactive) {\scriptsize x.flag=INACTIVE y.flag=INACTIVE z.flag=INACTIVE}; + + \node[dec, below=2em of xyz_active, text width=10em] (thr_over) {\scriptsize Thr override switch}; + \node[block, below left=2em and 2em of thr_over] (f_inactive){\scriptsize F.flag=INACTIVE}; + \node[block, below right=2em and 2em of thr_over] (f_active){\scriptsize F.flag=ACTIVE}; + + \node[node, below=4em of thr_over] (done2) {done}; + + + \draw[a] (start) -- (time); + \draw[a] (time) -- node[above] {no} (done1); + \draw[a] (time) -- node[left] {yes} (fixed_wing); + \draw[a] (fixed_wing) -| node[above, pos=0.25] {yes} (pass); + \draw[a] (fixed_wing) -| node[above, pos=0.25] {no} (att_switch); + \draw[a] (att_switch) -| node[above, pos=0.25] {on} (angle); + \draw[a] (att_switch) -| node[above, pos=0.25] {off} (rate); + \draw[a] (rate) |- (yaw_angle); + \draw[a] (angle) |- (yaw_angle); + \draw[a] (yaw_angle) -- (f_switch); + + \coordinate[above=1em of f_switch] (f_switch_merge) {}; + \draw (pass) |- (f_switch_merge); + + \draw[a] (f_switch) -| node[above, pos=0.25]{off} (F_thr); + \draw[a] (f_switch) -| node[above, pos=0.25]{on} (F_alt); + \draw[a] (F_thr) -- (convert); + \draw[a] (F_alt) |- (convert); + + \draw[a] (convert) -- (att_over); + \draw[a] (att_over) -| node[above, pos=0.25] {no} (lag); + \draw[a] (att_over) -- node[right] {yes} (xyz_active); + + \draw[a] (lag) -- node[above] {no} (deviated); + \coordinate[below=2em of att_over] (over_merge1); + \draw (lag) -- node[above] {yes} (over_merge1); + \draw[a] (deviated) |- node[left, pos=0.25] {yes} (set_lag); + \draw[a] (deviated) -| node[above, pos=0.25] {no} (xyz_inactive); + \coordinate[right=10.3em of set_lag] (over_merge2); + \draw (set_lag) -- (over_merge2); + + \coordinate[above=1em of thr_over] (thr_merge); + \draw (xyz_inactive) |- (thr_merge); + \draw[a] (xyz_active) -- (thr_over); + + \draw[a] (thr_over) -| node[above, pos=0.25] {off} (f_inactive); + \draw[a] (thr_over) -| node[above, pos=0.25] {on} (f_active); + + \draw[a] (f_inactive) |- (done2); + \draw[a] (f_active) |- (done2); + + \end{tikzpicture} + \end{adjustbox} + + \label{fig:rc_flow} + \caption{Logic used to construct of the RC command structure} +\end{figure} + +\section{Combinining the MAVLink and RC Command Structures} + +Once both the RC and offboard MAVlink command structures have been created from their respective sources, they must be combined into the composite command structure, which is then passed to the controller to be converted into desired torques, which is mixed into motor outputs. The three attitude channels $x$, $y$, and $z$ are all interpreted in the same way, as shown in Figure~\ref{fig:attitude_mux}, however, to handle minimum throttle cases, the logic to combined the $F$ channel is a bit more complex, as shown in Figure~\ref{fig:throttle_mux}. In order to mux throttles with the MIN\_THROTTLE param set true, altitude commands must be first converted into throttles using the altitude controller. They are then compared with one another and the lower of the two is taken. + +\begin{figure}[h] +\centering + \tikzstyle{block} = [draw, rectangle, + minimum height=3em, minimum width=6em, align=center] + \tikzstyle{node}=[draw, ellipse, minimum size=3em, + align=center] + \tikzstyle{dec}=[draw, diamond, aspect=3, align=center] + \tikzstyle{coordinate}=[draw, none] + \tikzstyle{a}=[-triangle 60] + + \begin{adjustbox}{max size={\textwidth}{\textheight}} + \begin{tikzpicture} + + \node[node] (start) {start}; + \node[dec, below=2em of start] (rc_active) {RC Active?}; + \node[dec, below=2em of rc_active] (off_active) {Offboard Active?}; + \node[block, below left=2em and 2em of off_active] (comb_rc) {Combined=RC}; + \node[block, below right=2em and 2em of off_active] (comb_off) {Combined=Offboard}; + \node[block, below=5em of off_active] (comb_active) {Combined=Active}; + \node[node, below=2em of comb_active] (done) {done}; + + \draw[a] (start) -- (rc_active); + \draw[a] (rc_active) -- node[right, pos=0.5] {no} (off_active); + \draw[a] (rc_active) -| node[above, pos=0.25] {yes} (comb_rc); + \draw[a] (off_active) -| node[above, pos=0.25] {no} (comb_rc); + \draw[a] (off_active) -| node[above, pos=0.25] {yes} (comb_off); + \draw[a] (comb_rc) |- (comb_active); + \draw[a] (comb_off) |- (comb_active); + \draw[a] (comb_active) -- (done); + + \end{tikzpicture} + \end{adjustbox} + + \caption{Logic used to mux any of the three attitude channels $x$, $y$, or $z$. This logic must be computed for each channel independently, as it is to have a combined output made up of both RC and Offboard control} + \label{fig:attitude_mux} +\end{figure} + +\begin{figure} +\centering + \tikzstyle{block} = [draw, rectangle, + minimum height=3em, minimum width=6em, align=center] + \tikzstyle{node}=[draw, ellipse, minimum size=3em, + align=center] + \tikzstyle{dec}=[draw, diamond, aspect=3, align=center] + \tikzstyle{coordinate}=[draw, none] + \tikzstyle{a}=[-triangle 60] + + \begin{adjustbox}{max size={\textwidth}{\textheight}} + \begin{tikzpicture} + + \node[node] (start) {start}; + \node[dec, below=2em of start] (rc_active) {RC Active?}; + \node[dec, below=2em of rc_active] (off_active) {Offboard Active?}; + \node[dec, below right=2em and 6em of off_active] (rc_thr) {RC=THROTTLE?}; + \node[block, below left=2em and 1em of rc_thr] (comb_rc) {Combined=RC}; + \node[block, below right=2em and 1em of rc_thr] (rc_alt) {RC=altCtrl(RC)}; + \node[node, below=2em of comb_rc] (done1) {done}; + + \draw[a] (start) -- (rc_active); + \draw[a] (rc_active) -- node[right, pos=0.5] {no} (off_active); + \draw[a] (rc_active) -| node[above, pos=0.25] {yes} (rc_thr); + \draw[a] (off_active) -| node[above, pos=0.25] {no} (rc_thr); + \draw[a] (rc_thr) -| node[above, pos=0.25] {no} (rc_alt); + \draw[a] (rc_thr) -| node[above, pos=0.25] {yes} (comb_rc); + \draw[a] (rc_alt) -- (comb_rc); + \draw[a] (comb_rc) -- (done1); + + \node[dec, below left=12em and 3em of off_active] (min_throttle) {MIN\_THROTTLE?}; + \node[dec, below right=2em and 2em of min_throttle] (off_thr) {offboard=THROTTLE?}; + \node[block, below right=2em and 0em of off_thr] (off_alt) {Offboard=altCtrl(Offboard)}; + \node[block, below left=2em and 0em of off_thr] (comb_off) {Combined=Offboard}; + \node[node, below=2em of comb_off] (done2) {done}; + \draw[a] (off_active) -| node[above, pos=0.25] {yes} (min_throttle); + \draw[a] (min_throttle) -| node[above, pos=0.25] {no} (off_thr); + \draw[a] (off_thr) -| node[above, pos=0.25] {yes} (comb_off); + \draw[a] (off_thr) -| node[above, pos=0.25] {no} (off_alt); + \draw[a] (off_alt) -- (comb_off); + \draw[a] (comb_off) -- (done2); + + \node[dec, below left=3em and 12em of min_throttle] (rc_thr2) {RC=THROTTLE?}; + \node[block, below right=1em and 2em of rc_thr2] (rc_alt2) {RC=altCtrl(RC)}; + \coordinate[below left=2.5em and 5.9em of rc_thr2] (rc_thr_merge); + \node[dec, below left=6em and 2em of rc_thr2](off_thr2){Offboard=THROTTLE?}; + + \draw[a] (min_throttle) -| node[above, pos=0.25] {yes} (rc_thr2); + \draw[a] (rc_thr2) -| node[above, pos=0.25] {no} (rc_alt2); + \draw[a] (rc_thr2) -| node[above, pos=0.25] {yes} (off_thr2); + \draw (rc_alt2) -- (rc_thr_merge); + + \node[block, below right=1em and 2em of off_thr2] (off_alt2) {Offboard=altCtrl(Offboard)}; + \coordinate[below left=2.5em and 5em of off_thr2] (off_thr_merge); + \node[dec, below left=6em and 2em of off_thr2](rc_off){RC > Offboard?}; + + \draw[a] (off_thr2) -| node[above, pos=0.25] {no} (off_alt2); + \draw[a] (off_thr2) -| node[above, pos=0.25] {yes} (rc_off); + \draw (off_alt2) -- (off_thr_merge); + + \node[block, below left=2em and 2em of rc_off] (comb_off2) {Combined=Offboard}; + \node[block, below right=2em and 2em of rc_off] (comb_rc2) {Combined=RC}; + \node[node, below=6em of rc_off] (done3) {done}; + + \draw[a] (rc_off) -| node[above, pos=0.25] {no} (comb_rc2); + \draw[a] (rc_off) -| node[above, pos=0.25] {yes} (comb_off2); + \draw[a] (comb_rc2) |- (done3); + \draw[a] (comb_off2) |- (done3); + + + \end{tikzpicture} + \end{adjustbox} + + \caption{Logic used to mux the throttle channel, $F$. The additional logic here is to account for the case in which altitudes have been commanded by one control source while throttles are commanded by the other. Both sources are first converted to throttle commands so as to compare equivalent channels when taking the minimum throttle} + \label{fig:throttle_mux} +\end{figure} + + + + + + + + +\end{document} + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/run_tests.sh b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/run_tests.sh new file mode 100644 index 0000000..34d78ae --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/run_tests.sh @@ -0,0 +1,42 @@ +#!/bin/bash + +function echo_red { echo -e "\033[1;31m$@\033[0m"; } +function echo_green { echo -e "\033[1;32m$@\033[0m"; } +function echo_blue { echo -e "\033[1;34m$@\033[0m"; } + +EXIT_CODE=0 + +function print_result() { + if [ $1 -eq 0 ]; then + echo_green "[Passed]" + else + echo_red "[Failed]" + EXIT_CODE=1 + fi + echo "" +} + +echo_blue "Test 1: Build firmware" +make clean +make +print_result $? + +echo_blue "Test 2: Build test suite" +mkdir -p test/build +cd test/build +rm -rf * +cmake .. -DCMAKE_BUILD_TYPE=RELEASE && make +print_result $? + +echo_blue "Test 3: Run test suite" +./unit_tests +print_result $? + + +if [ $EXIT_CODE -eq 0 ]; then + echo_green "All tests passed!" +else + echo_red "There were failed tests" +fi + +exit $EXIT_CODE diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/command_manager.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/command_manager.cpp new file mode 100644 index 0000000..dccc57d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/command_manager.cpp @@ -0,0 +1,312 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + + +#include +#include + +#include "command_manager.h" +#include "rosflight.h" + +namespace rosflight_firmware +{ + +typedef enum +{ + ATT_MODE_RATE, + ATT_MODE_ANGLE +} att_mode_t; + +typedef struct +{ + RC::Stick rc_channel; + uint32_t last_override_time; +} rc_stick_override_t; + +rc_stick_override_t rc_stick_override[] = +{ + { RC::STICK_X, 0 }, + { RC::STICK_Y, 0 }, + { RC::STICK_Z, 0 } +}; + +typedef struct +{ + control_channel_t *rc; + control_channel_t *onboard; + control_channel_t *combined; +} mux_t; + +CommandManager::CommandManager(ROSflight& _rf) : + RF_(_rf), + failsafe_command_(multirotor_failsafe_command_) +{} + +void CommandManager::init() +{ + RF_.params_.add_callback(std::bind(&CommandManager::param_change_callback, this, std::placeholders::_1), PARAM_FIXED_WING); + RF_.params_.add_callback(std::bind(&CommandManager::param_change_callback, this, std::placeholders::_1), PARAM_FAILSAFE_THROTTLE); + + init_failsafe(); +} + +void CommandManager::param_change_callback(uint16_t param_id) +{ + init_failsafe(); +} + +void CommandManager::init_failsafe() +{ + multirotor_failsafe_command_.F.value = RF_.params_.get_param_float(PARAM_FAILSAFE_THROTTLE); + + if (RF_.params_.get_param_int(PARAM_FIXED_WING)) + failsafe_command_ = fixedwing_failsafe_command_; + else + failsafe_command_ = multirotor_failsafe_command_; +} + +void CommandManager::interpret_rc(void) +{ + // get initial, unscaled RC values + rc_command_.x.value = RF_.rc_.stick(RC::STICK_X); + rc_command_.y.value = RF_.rc_.stick(RC::STICK_Y); + rc_command_.z.value = RF_.rc_.stick(RC::STICK_Z); + rc_command_.F.value = RF_.rc_.stick(RC::STICK_F); + + // determine control mode for each channel and scale command values accordingly + if (RF_.params_.get_param_int(PARAM_FIXED_WING)) + { + rc_command_.x.type = PASSTHROUGH; + rc_command_.y.type = PASSTHROUGH; + rc_command_.z.type = PASSTHROUGH; + rc_command_.F.type = THROTTLE; + } + else + { + // roll and pitch + control_type_t roll_pitch_type; + if (RF_.rc_.switch_mapped(RC::SWITCH_ATT_TYPE)) + { + roll_pitch_type = RF_.rc_.switch_on(RC::SWITCH_ATT_TYPE) ? ANGLE : RATE; + } + else + { + roll_pitch_type = (RF_.params_.get_param_int(PARAM_RC_ATTITUDE_MODE) == ATT_MODE_RATE) ? RATE: ANGLE; + } + + rc_command_.x.type = roll_pitch_type; + rc_command_.y.type = roll_pitch_type; + + // Scale command to appropriate units + switch (roll_pitch_type) + { + case RATE: + rc_command_.x.value *= RF_.params_.get_param_float(PARAM_RC_MAX_ROLLRATE); + rc_command_.y.value *= RF_.params_.get_param_float(PARAM_RC_MAX_PITCHRATE); + break; + case ANGLE: + rc_command_.x.value *= RF_.params_.get_param_float(PARAM_RC_MAX_ROLL); + rc_command_.y.value *= RF_.params_.get_param_float(PARAM_RC_MAX_PITCH); + } + + // yaw + rc_command_.z.type = RATE; + rc_command_.z.value *= RF_.params_.get_param_float(PARAM_RC_MAX_YAWRATE); + + // throttle + rc_command_.F.type = THROTTLE; + } +} + +bool CommandManager::stick_deviated(MuxChannel channel) +{ + uint32_t now = RF_.board_.clock_millis(); + + // if we are still in the lag time, return true + if (now < rc_stick_override_[channel].last_override_time + RF_.params_.get_param_int(PARAM_OVERRIDE_LAG_TIME)) + { + return true; + } + else + { + if (fabs(RF_.rc_.stick(rc_stick_override_[channel].rc_channel)) + > RF_.params_.get_param_float(PARAM_RC_OVERRIDE_DEVIATION)) + { + rc_stick_override_[channel].last_override_time = now; + return true; + } + return false; + } +} + +bool CommandManager::do_roll_pitch_yaw_muxing(MuxChannel channel) +{ + bool override_this_channel = false; + //Check if the override switch exists and is triggered, or if the sticks have deviated enough to trigger an override + if ((RF_.rc_.switch_mapped(RC::SWITCH_ATT_OVERRIDE) && RF_.rc_.switch_on(RC::SWITCH_ATT_OVERRIDE)) + || stick_deviated(channel)) + { + override_this_channel = true; + } + else // Otherwise only have RC override if the offboard channel is inactive + { + if (muxes[channel].onboard->active) + { + override_this_channel = false; + } + else + { + override_this_channel = true; + } + } + // set the combined channel output depending on whether RC is overriding for this channel or not + *muxes[channel].combined = override_this_channel ? *muxes[channel].rc : *muxes[channel].onboard; + return override_this_channel; +} + +bool CommandManager::do_throttle_muxing(void) +{ + bool override_this_channel = false; + // Check if the override switch exists and is triggered + if (RF_.rc_.switch_mapped(RC::SWITCH_THROTTLE_OVERRIDE) && RF_.rc_.switch_on(RC::SWITCH_THROTTLE_OVERRIDE)) + { + override_this_channel = true; + } + else // Otherwise check if the offboard throttle channel is active, if it isn't, have RC override + { + if (muxes[MUX_F].onboard->active) + { + // Check if the parameter flag is set to have us always take the smaller throttle + if (RF_.params_.get_param_int(PARAM_RC_OVERRIDE_TAKE_MIN_THROTTLE)) + { + override_this_channel = (muxes[MUX_F].rc->value < muxes[MUX_F].onboard->value); + } + else + { + override_this_channel = false; + } + } + else + { + override_this_channel = true; + } + } + + // Set the combined channel output depending on whether RC is overriding for this channel or not + *muxes[MUX_F].combined = override_this_channel ? *muxes[MUX_F].rc : *muxes[MUX_F].onboard; + return override_this_channel; +} + +bool CommandManager::rc_override_active() +{ + return rc_override_; +} + +bool CommandManager::offboard_control_active() +{ + for (int i = 0; i < 4; i++) + { + if (muxes[i].onboard->active) + return true; + } + return false; +} + +void CommandManager::set_new_offboard_command(control_t new_offboard_command) +{ + new_command_ = true; + offboard_command_ = new_offboard_command; +} + +void CommandManager::set_new_rc_command(control_t new_rc_command) +{ + new_command_ = true; + rc_command_ = new_rc_command; +} + +void CommandManager::override_combined_command_with_rc() +{ + new_command_ = true; + combined_command_ = rc_command_; +} + + +bool CommandManager::run() +{ + bool last_rc_override = rc_override_; + + // Check for and apply failsafe command + if (RF_.state_manager_.state().failsafe) + { + combined_command_ = failsafe_command_; + } + else if (RF_.rc_.new_command()) + { + // Read RC + interpret_rc(); + + // Check for offboard control timeout (100 ms) + if (RF_.board_.clock_millis() > offboard_command_.stamp_ms + 100) + { + // If it has been longer than 100 ms, then disable the offboard control + offboard_command_.F.active = false; + offboard_command_.x.active = false; + offboard_command_.y.active = false; + offboard_command_.z.active = false; + } + + // Perform muxing + rc_override_ = do_roll_pitch_yaw_muxing(MUX_X); + rc_override_ |= do_roll_pitch_yaw_muxing(MUX_Y); + rc_override_ |= do_roll_pitch_yaw_muxing(MUX_Z); + rc_override_ |= do_throttle_muxing(); + + // Light to indicate override + if (rc_override_) + { + RF_.board_.led0_on(); + } + else + { + RF_.board_.led0_off(); + } + } + + // There was a change in rc_override state + if (last_rc_override != rc_override_) + { + RF_.mavlink_.update_status(); + } + return true; +} + + +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/controller.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/controller.cpp new file mode 100644 index 0000000..248349a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/controller.cpp @@ -0,0 +1,289 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +#include "command_manager.h" +#include "estimator.h" +#include "rosflight.h" + +#include "controller.h" + +namespace rosflight_firmware +{ + +Controller::Controller(ROSflight& rf) : + RF_(rf) +{ + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_ROLL_ANGLE_P); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_ROLL_ANGLE_I); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_ROLL_ANGLE_D); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_ROLL_RATE_P); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_ROLL_RATE_I); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_ROLL_RATE_D); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_PITCH_ANGLE_P); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_PITCH_ANGLE_I); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_PITCH_ANGLE_D); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_PITCH_RATE_P); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_PITCH_RATE_I); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_PITCH_RATE_D); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_YAW_RATE_P); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_YAW_RATE_I); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_YAW_RATE_D); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_MAX_COMMAND); + RF_.params_.add_callback(std::bind(&Controller::param_change_callback, this, std::placeholders::_1), PARAM_PID_TAU); +} + +void Controller::init() +{ + prev_time_us_ = 0; + + float max = RF_.params_.get_param_float(PARAM_MAX_COMMAND); + float min = -max; + float tau = RF_.params_.get_param_float(PARAM_PID_TAU); + + roll_.init(RF_.params_.get_param_float(PARAM_PID_ROLL_ANGLE_P), + RF_.params_.get_param_float(PARAM_PID_ROLL_ANGLE_I), + RF_.params_.get_param_float(PARAM_PID_ROLL_ANGLE_D), + max, min, tau); + roll_rate_.init(RF_.params_.get_param_float(PARAM_PID_ROLL_RATE_P), + RF_.params_.get_param_float(PARAM_PID_ROLL_RATE_I), + RF_.params_.get_param_float(PARAM_PID_ROLL_RATE_D), + max, min, tau); + pitch_.init(RF_.params_.get_param_float(PARAM_PID_PITCH_ANGLE_P), + RF_.params_.get_param_float(PARAM_PID_PITCH_ANGLE_I), + RF_.params_.get_param_float(PARAM_PID_PITCH_ANGLE_D), + max, min, tau); + pitch_rate_.init(RF_.params_.get_param_float(PARAM_PID_PITCH_RATE_P), + RF_.params_.get_param_float(PARAM_PID_PITCH_RATE_I), + RF_.params_.get_param_float(PARAM_PID_PITCH_RATE_D), + max, min, tau); + yaw_rate_.init(RF_.params_.get_param_float(PARAM_PID_YAW_RATE_P), + RF_.params_.get_param_float(PARAM_PID_YAW_RATE_I), + RF_.params_.get_param_float(PARAM_PID_YAW_RATE_D), + max, min, tau); +} + +void Controller::run() +{ + // Time calculation + if (prev_time_us_ == 0) + { + prev_time_us_ = RF_.estimator_.state().timestamp_us; + return; + } + + int32_t dt_us = (RF_.estimator_.state().timestamp_us - prev_time_us_); + if ( dt_us < 0 ) + { + RF_.state_manager_.set_error(StateManager::ERROR_TIME_GOING_BACKWARDS); + prev_time_us_ = RF_.estimator_.state().timestamp_us; + return; + } + + // Check if integrators should be updated + //! @todo better way to figure out if throttle is high + bool update_integrators = (RF_.state_manager_.state().armed) && (RF_.command_manager_.combined_control().F.value > 0.1f) && dt_us < 100; + + // Run the PID loops + vector_t pid_output = run_pid_loops(dt_us, RF_.estimator_.state(), RF_.command_manager_.combined_control(), update_integrators); + + // Add feedforward torques + output_.x = pid_output.x + RF_.params_.get_param_float(PARAM_X_EQ_TORQUE); + output_.y = pid_output.y + RF_.params_.get_param_float(PARAM_Y_EQ_TORQUE); + output_.z = pid_output.z + RF_.params_.get_param_float(PARAM_Z_EQ_TORQUE); + output_.F = RF_.command_manager_.combined_control().F.value; +} + +void Controller::calculate_equilbrium_torque_from_rc() +{ + // Make sure we are disarmed + if (!(RF_.state_manager_.state().armed)) + { + // Tell the user that we are doing a equilibrium torque calibration + RF_.mavlink_.log(Mavlink::LOG_WARNING, "Capturing equilbrium offsets from RC"); + + // Prepare for calibration + // artificially tell the flight controller it is leveled + Estimator::State fake_state; + fake_state.angular_velocity.x = 0.0f; + fake_state.angular_velocity.y = 0.0f; + fake_state.angular_velocity.z = 0.0f; + + fake_state.attitude.x = 0.0f; + fake_state.attitude.y = 0.0f; + fake_state.attitude.z = 0.0f; + fake_state.attitude.w = 1.0f; + + fake_state.roll = 0.0f; + fake_state.pitch = 0.0f; + fake_state.yaw = 0.0f; + + // pass the rc_control through the controller + // dt is zero, so what this really does is applies the P gain with the settings + // your RC transmitter, which if it flies level is a really good guess for + // the static offset torques + vector_t pid_output = run_pid_loops(0, fake_state, RF_.command_manager_.rc_control(), false); + + // the output from the controller is going to be the static offsets + RF_.params_.set_param_float(PARAM_X_EQ_TORQUE, pid_output.x); + RF_.params_.set_param_float(PARAM_Y_EQ_TORQUE, pid_output.y); + RF_.params_.set_param_float(PARAM_Z_EQ_TORQUE, pid_output.z); + + RF_.mavlink_.log(Mavlink::LOG_WARNING, "Equilibrium torques found and applied."); + RF_.mavlink_.log(Mavlink::LOG_WARNING, "Please zero out trims on your transmitter"); + } + else + { + RF_.mavlink_.log(Mavlink::LOG_WARNING, "Cannot perform equilibrium offset calibration while armed"); + } +} + +void Controller::param_change_callback(uint16_t param_id) +{ + init(); +} + +vector_t Controller::run_pid_loops(uint32_t dt_us, const Estimator::State& state, const control_t& command, bool update_integrators) +{ + // Based on the control types coming from the command manager, run the appropriate PID loops + vector_t output; + + float dt = dt_us; + + // ROLL + if (command.x.type == RATE) + output.x = roll_rate_.run(dt, state.angular_velocity.x, command.x.value, update_integrators); + else if (command.x.type == ANGLE) + output.x = roll_.run(dt, state.roll, command.x.value, update_integrators, state.angular_velocity.x); + else + output.x = command.x.value; + + // PITCH + if (command.y.type == RATE) + output.y = pitch_rate_.run(dt, state.angular_velocity.y, command.y.value, update_integrators); + else if (command.y.type == ANGLE) + output.y = pitch_.run(dt, state.pitch, command.y.value, update_integrators, state.angular_velocity.y); + else + output.y = command.y.value; + + // YAW + if (command.z.type == RATE) + output.z = yaw_rate_.run(dt, state.angular_velocity.z, command.z.value, update_integrators); + else + output.z = command.z.value; + + return output; +} + +Controller::PID::PID() : + kp_(0.0f), + ki_(0.0f), + kd_(0.0f), + max_(1.0f), + min_(-1.0f), + integrator_(0.0f), + differentiator_(0.0f), + prev_x_(0.0f), + tau_(0.05) +{} + +void Controller::PID::init(float kp, float ki, float kd, float max, float min, float tau) +{ + kp_ = kp; + ki_ = ki; + kd_ = kd; + max_ = max; + min_ = min; + tau_ = tau; +} + +float Controller::PID::run(float dt, float x, float x_c, bool update_integrator) +{ + float xdot; + if (dt > 0.0001f) + { + // calculate D term (use dirty derivative if we don't have access to a measurement of the derivative) + // The dirty derivative is a sort of low-pass filtered version of the derivative. + //// (Include reference to Dr. Beard's notes here) + differentiator_ = (2.0f * tau_ - dt) / (2.0f * tau_ + dt) * differentiator_ + + 2.0f / (2.0f * tau_ + dt) * (x - prev_x_); + xdot = differentiator_; + } + else + { + xdot = 0.0f; + } + prev_x_ = x; + + return run(dt, x, x_c, update_integrator, xdot); +} + +float Controller::PID::run(float dt, float x, float x_c, bool update_integrator, float xdot) +{ + // Calculate Error + float error = x_c - x; + + // Initialize Terms + float p_term = error * kp_; + float i_term = 0.0f; + float d_term = 0.0f; + + // If there is a derivative term + if (kd_ > 0.0f) + { + d_term = kd_ * xdot; + } + + //If there is an integrator term and we are updating integrators + if ((ki_ > 0.0f) && update_integrator) + { + // integrate + integrator_ += error * dt; + // calculate I term + i_term = ki_ * integrator_; + } + + // sum three terms + float u = p_term - d_term + i_term; + + // Integrator anti-windup + //// Include reference to Dr. Beard's notes here + float u_sat = (u > max_) ? max_ : (u < min_) ? min_ : u; + if (u != u_sat && fabs(i_term) > fabs(u - p_term + d_term) && ki_ > 0.0f) + integrator_ = (u_sat - p_term + d_term)/ki_; + + // Set output + return u_sat; +} + +} // namespace rosflight_firmware diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/estimator.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/estimator.cpp new file mode 100644 index 0000000..56dd785 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/estimator.cpp @@ -0,0 +1,282 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include "estimator.h" +#include "rosflight.h" + +namespace rosflight_firmware +{ + +Estimator::Estimator(ROSflight &_rf): + RF_(_rf) +{} + +void Estimator::reset_state() +{ + state_.attitude.w = 1.0f; + state_.attitude.x = 0.0f; + state_.attitude.y = 0.0f; + state_.attitude.z = 0.0f; + + state_.angular_velocity.x = 0.0f; + state_.angular_velocity.y = 0.0f; + state_.angular_velocity.z = 0.0f; + + state_.roll = 0.0f; + state_.pitch = 0.0f; + state_.yaw = 0.0f; + + w1_.x = 0.0f; + w1_.y = 0.0f; + w1_.z = 0.0f; + + w2_.x = 0.0f; + w2_.y = 0.0f; + w2_.z = 0.0f; + + bias_.x = 0.0f; + bias_.y = 0.0f; + bias_.z = 0.0f; + + accel_LPF_.x = 0; + accel_LPF_.y = 0; + accel_LPF_.z = -9.80665; + + gyro_LPF_.x = 0; + gyro_LPF_.y = 0; + gyro_LPF_.z = 0; + + state_.timestamp_us = RF_.board_.clock_micros(); + + // Clear the unhealthy estimator flag + RF_.state_manager_.clear_error(StateManager::ERROR_UNHEALTHY_ESTIMATOR); +} + +void Estimator::reset_adaptive_bias() +{ + bias_.x = 0; + bias_.y = 0; + bias_.z = 0; +} + +void Estimator::init() +{ + last_time_ = 0; + last_acc_update_us_ = 0; + reset_state(); +} + +void Estimator::run_LPF() +{ + float alpha_acc = RF_.params_.get_param_float(PARAM_ACC_ALPHA); + const vector_t& raw_accel = RF_.sensors_.data().accel; + accel_LPF_.x = (1.0f-alpha_acc)*raw_accel.x + alpha_acc*accel_LPF_.x; + accel_LPF_.y = (1.0f-alpha_acc)*raw_accel.y + alpha_acc*accel_LPF_.y; + accel_LPF_.z = (1.0f-alpha_acc)*raw_accel.z + alpha_acc*accel_LPF_.z; + + float alpha_gyro = RF_.params_.get_param_float(PARAM_GYRO_ALPHA); + const vector_t& raw_gyro = RF_.sensors_.data().gyro; + gyro_LPF_.x = (1.0f-alpha_gyro)*raw_gyro.x + alpha_gyro*gyro_LPF_.x; + gyro_LPF_.y = (1.0f-alpha_gyro)*raw_gyro.y + alpha_gyro*gyro_LPF_.y; + gyro_LPF_.z = (1.0f-alpha_gyro)*raw_gyro.z + alpha_gyro*gyro_LPF_.z; +} + +void Estimator::run() +{ + float kp, ki; + uint64_t now_us = RF_.sensors_.data().imu_time; + if (last_time_ == 0) + { + last_time_ = now_us; + last_acc_update_us_ = last_time_; + return; + } + else if (now_us < last_time_) + { + // this shouldn't happen + RF_.state_manager_.set_error(StateManager::ERROR_TIME_GOING_BACKWARDS); + last_time_ = now_us; + return; + } + else if (now_us == last_time_) + { + volatile int debug = 1; + return; + } + + RF_.state_manager_.clear_error(StateManager::ERROR_TIME_GOING_BACKWARDS); + + float dt = (now_us - last_time_) * 1e-6f; + last_time_ = now_us; + state_.timestamp_us = now_us; + + // Crank up the gains for the first few seconds for quick convergence + if (now_us < (uint64_t)RF_.params_.get_param_int(PARAM_INIT_TIME)*1000) + { + kp = RF_.params_.get_param_float(PARAM_FILTER_KP)*10.0f; + ki = RF_.params_.get_param_float(PARAM_FILTER_KI)*10.0f; + } + else + { + kp = RF_.params_.get_param_float(PARAM_FILTER_KP); + ki = RF_.params_.get_param_float(PARAM_FILTER_KI); + } + + // Run LPF to reject a lot of noise + run_LPF(); + + // add in accelerometer + float a_sqrd_norm = sqrd_norm(accel_LPF_); + + vector_t w_acc; + if (RF_.params_.get_param_int(PARAM_FILTER_USE_ACC) + && a_sqrd_norm < 1.1f*1.1f*9.80665f*9.80665f && a_sqrd_norm > 0.9f*0.9f*9.80665f*9.80665f) + { + // Get error estimated by accelerometer measurement + last_acc_update_us_ = now_us; + // turn measurement into a unit vector + vector_t a = vector_normalize(accel_LPF_); + // Get the quaternion from accelerometer (low-frequency measure q) + // (Not in either paper) + quaternion_t q_acc_inv = quat_from_two_unit_vectors(g_, a); + // Get the error quaternion between observer and low-freq q + // Below Eq. 45 Mahony Paper + quaternion_t q_tilde = quaternion_multiply(q_acc_inv, state_.attitude); + // Correction Term of Eq. 47a and 47b Mahony Paper + // w_acc = 2*s_tilde*v_tilde + w_acc.x = -2.0f*q_tilde.w*q_tilde.x; + w_acc.y = -2.0f*q_tilde.w*q_tilde.y; + w_acc.z = 0.0f; // Don't correct z, because it's unobservable from the accelerometer + + // integrate biases from accelerometer feedback + // (eq 47b Mahony Paper, using correction term w_acc found above + bias_.x -= ki*w_acc.x*dt; + bias_.y -= ki*w_acc.y*dt; + bias_.z = 0.0; // Don't integrate z bias, because it's unobservable + } + else + { + w_acc.x = 0.0f; + w_acc.y = 0.0f; + w_acc.z = 0.0f; + } + + + // Handle Gyro Measurements + vector_t wbar; + if (RF_.params_.get_param_int(PARAM_FILTER_USE_QUAD_INT)) + { + // Quadratic Interpolation (Eq. 14 Casey Paper) + // this step adds 12 us on the STM32F10x chips + wbar = vector_add(vector_add(scalar_multiply(-1.0f/12.0f,w2_), scalar_multiply(8.0f/12.0f,w1_)), + scalar_multiply(5.0f/12.0f,gyro_LPF_)); + w2_ = w1_; + w1_ = gyro_LPF_; + } + else + { + wbar = gyro_LPF_; + } + + // Build the composite omega vector for kinematic propagation + // This the stuff inside the p function in eq. 47a - Mahony Paper + vector_t wfinal = vector_add(vector_sub(wbar, bias_), scalar_multiply(kp, w_acc)); + + // Propagate Dynamics (only if we've moved) + float sqrd_norm_w = sqrd_norm(wfinal); + if (sqrd_norm_w > 0.0f) + { + float p = wfinal.x; + float q = wfinal.y; + float r = wfinal.z; + + if (RF_.params_.get_param_int(PARAM_FILTER_USE_MAT_EXP)) + { + // Matrix Exponential Approximation (From Attitude Representation and Kinematic + // Propagation for Low-Cost UAVs by Robert T. Casey) + // (Eq. 12 Casey Paper) + // This adds 90 us on STM32F10x chips + float norm_w = sqrt(sqrd_norm_w); + quaternion_t qhat_np1; + float t1 = cos((norm_w*dt)/2.0f); + float t2 = 1.0f/norm_w * sin((norm_w*dt)/2.0f); + qhat_np1.w = t1*state_.attitude.w + t2*(-p*state_.attitude.x - q*state_.attitude.y - r*state_.attitude.z); + qhat_np1.x = t1*state_.attitude.x + t2*( p*state_.attitude.w + r*state_.attitude.y - q*state_.attitude.z); + qhat_np1.y = t1*state_.attitude.y + t2*( q*state_.attitude.w - r*state_.attitude.x + p*state_.attitude.z); + qhat_np1.z = t1*state_.attitude.z + t2*( r*state_.attitude.w + q*state_.attitude.x - p*state_.attitude.y); + state_.attitude = quaternion_normalize(qhat_np1); + } + else + { + // Euler Integration + // (Eq. 47a Mahony Paper), but this is pretty straight-forward + quaternion_t qdot = {0.5f * (-p*state_.attitude.x - q*state_.attitude.y - r*state_.attitude.z), + 0.5f * ( p*state_.attitude.w + r*state_.attitude.y - q*state_.attitude.z), + 0.5f * ( q*state_.attitude.w - r*state_.attitude.x + p*state_.attitude.z), + 0.5f * ( r*state_.attitude.w + q*state_.attitude.x - p*state_.attitude.y) + }; + state_.attitude.w += qdot.w*dt; + state_.attitude.x += qdot.x*dt; + state_.attitude.y += qdot.y*dt; + state_.attitude.z += qdot.z*dt; + state_.attitude = quaternion_normalize(state_.attitude); + } + // Make sure the quaternion is canoncial (w is always positive) + if (state_.attitude.w < 0.0f) + { + state_.attitude.w *= -1.0f; + state_.attitude.x *= -1.0f; + state_.attitude.y *= -1.0f; + state_.attitude.z *= -1.0f; + } + } + + // Extract Euler Angles for controller + euler_from_quat(state_.attitude, &state_.roll, &state_.pitch, &state_.yaw); + + // Save off adjust gyro measurements with estimated biases for control + state_.angular_velocity = vector_sub(gyro_LPF_, bias_); + + // If it has been more than 0.5 seconds since the acc update ran and we are supposed to be getting them + // then trigger an unhealthy estimator error + if (RF_.params_.get_param_int(PARAM_FILTER_USE_ACC) && now_us > 500000 + last_acc_update_us_ + && !RF_.params_.get_param_int(PARAM_FIXED_WING)) + { + RF_.state_manager_.set_error(StateManager::ERROR_UNHEALTHY_ESTIMATOR); + } + else + { + RF_.state_manager_.clear_error(StateManager::ERROR_UNHEALTHY_ESTIMATOR); + } +} + +} + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/mavlink.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/mavlink.cpp new file mode 100644 index 0000000..f33ad41 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/mavlink.cpp @@ -0,0 +1,621 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ +#include + +#include "mavlink.h" +#include "rosflight.h" + +namespace rosflight_firmware { + +Mavlink::Mavlink(ROSflight& _rf) : + RF_(_rf) +{ + initialized_ = false; +} + +// function definitions +void Mavlink::init() +{ + RF_.board_.serial_init(RF_.params_.get_param_int(PARAM_BAUD_RATE)); + + sysid_ = RF_.params_.get_param_int(PARAM_SYSTEM_ID); + compid_ = 250; + + offboard_control_time_ = 0; + send_params_index_ = PARAMS_COUNT; + + // Register Param change callbacks + RF_.params_.add_callback(std::bind(&Mavlink::set_streaming_rate, this, STREAM_ID_HEARTBEAT, std::placeholders::_1), PARAM_STREAM_HEARTBEAT_RATE); + RF_.params_.add_callback(std::bind(&Mavlink::set_streaming_rate, this, STREAM_ID_ATTITUDE, std::placeholders::_1), PARAM_STREAM_ATTITUDE_RATE); + RF_.params_.add_callback(std::bind(&Mavlink::set_streaming_rate, this, STREAM_ID_IMU, std::placeholders::_1), PARAM_STREAM_IMU_RATE); + RF_.params_.add_callback(std::bind(&Mavlink::set_streaming_rate, this, STREAM_ID_ATTITUDE, std::placeholders::_1), PARAM_STREAM_ATTITUDE_RATE); + RF_.params_.add_callback(std::bind(&Mavlink::set_streaming_rate, this, STREAM_ID_DIFF_PRESSURE, std::placeholders::_1), PARAM_STREAM_AIRSPEED_RATE); + RF_.params_.add_callback(std::bind(&Mavlink::set_streaming_rate, this, STREAM_ID_BARO, std::placeholders::_1), PARAM_STREAM_BARO_RATE); + RF_.params_.add_callback(std::bind(&Mavlink::set_streaming_rate, this, STREAM_ID_SONAR, std::placeholders::_1), PARAM_STREAM_SONAR_RATE); + RF_.params_.add_callback(std::bind(&Mavlink::set_streaming_rate, this, STREAM_ID_MAG, std::placeholders::_1), PARAM_STREAM_MAG_RATE); + RF_.params_.add_callback(std::bind(&Mavlink::set_streaming_rate, this, STREAM_ID_SERVO_OUTPUT_RAW, std::placeholders::_1), PARAM_STREAM_OUTPUT_RAW_RATE); + RF_.params_.add_callback(std::bind(&Mavlink::set_streaming_rate, this, STREAM_ID_RC_RAW, std::placeholders::_1), PARAM_STREAM_RC_RAW_RATE); + + initialized_ = true; + log(Mavlink::LOG_INFO, "Booting"); +} + +void Mavlink::send_message(const mavlink_message_t &msg) +{ + if (initialized_) + { + uint8_t data[MAVLINK_MAX_PACKET_LEN]; + uint16_t len = mavlink_msg_to_send_buffer(data, &msg); + RF_.board_.serial_write(data, len); + } +} + +void Mavlink::update_status() +{ + send_status(); +} + + +void Mavlink::update_param(uint16_t param_id) +{ + if (param_id < PARAMS_COUNT) + { + MAV_PARAM_TYPE type; + switch (RF_.params_.get_param_type(param_id)) + { + case PARAM_TYPE_INT32: + type = MAV_PARAM_TYPE_INT32; + break; + case PARAM_TYPE_FLOAT: + type = MAV_PARAM_TYPE_REAL32; + break; + default: + return; + } + + mavlink_message_t msg; + mavlink_msg_param_value_pack(RF_.params_.get_param_int(PARAM_SYSTEM_ID), 0, &msg, + RF_.params_.get_param_name(param_id), RF_.params_.get_param_float(param_id), type, PARAMS_COUNT, param_id); + send_message(msg); + } +} + +void Mavlink::handle_msg_param_request_list(void) +{ + send_params_index_ = 0; +} + +void Mavlink::handle_msg_param_request_read(const mavlink_message_t *const msg) +{ + mavlink_param_request_read_t read; + mavlink_msg_param_request_read_decode(msg, &read); + + if (read.target_system == (uint8_t) RF_.params_.get_param_int(PARAM_SYSTEM_ID)) // TODO check if component id matches? + { + uint16_t id = (read.param_index < 0) ? RF_.params_.lookup_param_id(read.param_id) : (uint16_t) read.param_index; + + if (id < PARAMS_COUNT) + update_param(id); + } +} + +void Mavlink::handle_msg_param_set(const mavlink_message_t *const msg) +{ + mavlink_param_set_t set; + mavlink_msg_param_set_decode(msg, &set); + + if (set.target_system == (uint8_t) RF_.params_.get_param_int(PARAM_SYSTEM_ID)) // TODO check if component id matches? + { + uint16_t id = RF_.params_.lookup_param_id(set.param_id); + + if (id < PARAMS_COUNT) + { + param_type_t candidate_type; + switch (set.param_type) + { + case MAV_PARAM_TYPE_INT32: + candidate_type = PARAM_TYPE_INT32; + break; + case MAV_PARAM_TYPE_REAL32: + candidate_type = PARAM_TYPE_FLOAT; + break; + default: + candidate_type = PARAM_TYPE_INVALID; + break; + } + + if (candidate_type == RF_.params_.get_param_type(id)) + { + switch (candidate_type) + { + case PARAM_TYPE_INT32: + RF_.params_.set_param_int(id, *(int32_t *) &set.param_value); + break; + case PARAM_TYPE_FLOAT: + RF_.params_.set_param_float(id, set.param_value); + break; + } + } + } + } +} + +void Mavlink::send_next_param(void) +{ + if (send_params_index_ < PARAMS_COUNT) + { + update_param((uint16_t) send_params_index_); + send_params_index_++; + } +} + + +void Mavlink::handle_msg_rosflight_cmd(const mavlink_message_t *const msg) +{ + mavlink_rosflight_cmd_t cmd; + mavlink_msg_rosflight_cmd_decode(msg, &cmd); + + uint8_t result; + bool reboot_flag = false; + bool reboot_to_bootloader_flag = false; + + // None of these actions can be performed if we are armed + if (RF_.state_manager_.state().armed) + { + result = false; + } + else + { + result = true; + switch (cmd.command) + { + case ROSFLIGHT_CMD_READ_PARAMS: + result = RF_.params_.read(); + break; + case ROSFLIGHT_CMD_WRITE_PARAMS: + result = RF_.params_.write(); + break; + case ROSFLIGHT_CMD_SET_PARAM_DEFAULTS: + RF_.params_.set_defaults(); + break; + case ROSFLIGHT_CMD_ACCEL_CALIBRATION: + result = RF_.sensors_.start_imu_calibration(); + break; + case ROSFLIGHT_CMD_GYRO_CALIBRATION: + result = RF_.sensors_.start_gyro_calibration(); + break; + case ROSFLIGHT_CMD_BARO_CALIBRATION: + result = RF_.sensors_.start_baro_calibration(); + break; + case ROSFLIGHT_CMD_AIRSPEED_CALIBRATION: + result = RF_.sensors_.start_diff_pressure_calibration(); + break; + case ROSFLIGHT_CMD_RC_CALIBRATION: + RF_.controller_.calculate_equilbrium_torque_from_rc(); + break; + case ROSFLIGHT_CMD_REBOOT: + reboot_flag = true; + break; + case ROSFLIGHT_CMD_REBOOT_TO_BOOTLOADER: + reboot_to_bootloader_flag = true; + break; + case ROSFLIGHT_CMD_SEND_VERSION: + mavlink_message_t msg; + mavlink_msg_rosflight_version_pack(sysid_, compid_, &msg, GIT_VERSION_STRING); + send_message(msg); + break; + default: + log(LOG_ERROR, "Unsupported ROSFLIGHT CMD %d", cmd.command); + result = false; + break; + } + } + + uint8_t response = (result) ? ROSFLIGHT_CMD_SUCCESS : ROSFLIGHT_CMD_FAILED; + + mavlink_message_t ack_msg; + mavlink_msg_rosflight_cmd_ack_pack(sysid_, compid_, &ack_msg, cmd.command, response); + send_message(ack_msg); + + if (reboot_flag || reboot_to_bootloader_flag) + { + RF_.board_.clock_delay(20); + RF_.board_.board_reset(reboot_to_bootloader_flag); + } +} + +void Mavlink::handle_msg_timesync(const mavlink_message_t *const msg) +{ + uint64_t now_us = RF_.board_.clock_micros(); + + mavlink_timesync_t tsync; + mavlink_msg_timesync_decode(msg, &tsync); + + if (tsync.tc1 == 0) // check that this is a request, not a response + { + mavlink_message_t msg; + mavlink_msg_timesync_pack(sysid_, compid_, &msg, (int64_t) now_us*1000, tsync.ts1); + send_message(msg); + } +} + +void Mavlink::handle_msg_offboard_control(const mavlink_message_t *const msg) +{ + mavlink_offboard_control_t mavlink_offboard_control; + mavlink_msg_offboard_control_decode(msg, &mavlink_offboard_control); + + // put values into a new command struct + control_t new_offboard_command; + new_offboard_command.x.value = mavlink_offboard_control.x; + new_offboard_command.y.value = mavlink_offboard_control.y; + new_offboard_command.z.value = mavlink_offboard_control.z; + new_offboard_command.F.value = mavlink_offboard_control.F; + + // Move flags into standard message + new_offboard_command.x.active = !(mavlink_offboard_control.ignore & IGNORE_VALUE1); + new_offboard_command.y.active = !(mavlink_offboard_control.ignore & IGNORE_VALUE2); + new_offboard_command.z.active = !(mavlink_offboard_control.ignore & IGNORE_VALUE3); + new_offboard_command.F.active = !(mavlink_offboard_control.ignore & IGNORE_VALUE4); + + // translate modes into standard message + switch (mavlink_offboard_control.mode) + { + case MODE_PASS_THROUGH: + new_offboard_command.x.type = PASSTHROUGH; + new_offboard_command.y.type = PASSTHROUGH; + new_offboard_command.z.type = PASSTHROUGH; + new_offboard_command.F.type = THROTTLE; + break; + case MODE_ROLLRATE_PITCHRATE_YAWRATE_THROTTLE: + new_offboard_command.x.type = RATE; + new_offboard_command.y.type = RATE; + new_offboard_command.z.type = RATE; + new_offboard_command.F.type = THROTTLE; + break; + case MODE_ROLL_PITCH_YAWRATE_THROTTLE: + new_offboard_command.x.type = ANGLE; + new_offboard_command.y.type = ANGLE; + new_offboard_command.z.type = RATE; + new_offboard_command.F.type = THROTTLE; + break; + // Handle error state + } + + // Tell the command_manager that we have a new command we need to mux + new_offboard_command.stamp_ms = RF_.board_.clock_millis(); + RF_.command_manager_.set_new_offboard_command(new_offboard_command); +} + +void Mavlink::handle_mavlink_message(void) +{ + switch (in_buf_.msgid) + { + case MAVLINK_MSG_ID_OFFBOARD_CONTROL: + handle_msg_offboard_control(&in_buf_); + break; + case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: + handle_msg_param_request_list(); + break; + case MAVLINK_MSG_ID_PARAM_REQUEST_READ: + handle_msg_param_request_read(&in_buf_); + break; + case MAVLINK_MSG_ID_PARAM_SET: + handle_msg_param_set(&in_buf_); + break; + case MAVLINK_MSG_ID_ROSFLIGHT_CMD: + handle_msg_rosflight_cmd(&in_buf_); + break; + case MAVLINK_MSG_ID_TIMESYNC: + handle_msg_timesync(&in_buf_); + break; + default: + break; + } +} + +// function definitions +void Mavlink::receive(void) +{ + while (RF_.board_.serial_bytes_available()) + { + if (mavlink_parse_char(MAVLINK_COMM_0, RF_.board_.serial_read(), &in_buf_, &status_)) + handle_mavlink_message(); + } +} + +void Mavlink::log(uint8_t severity, const char *fmt, ...) +{ + // Convert the format string to a raw char array + va_list args; + va_start(args, fmt); + char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; + rosflight_firmware::nanoprintf::tfp_sprintf(text, fmt, args); + va_end(args); + send_log_message(severity, text); +} + +void Mavlink::send_log_message(uint8_t severity, const char* text) +{ + mavlink_message_t msg; + mavlink_msg_statustext_pack(RF_.params_.get_param_int(PARAM_SYSTEM_ID), 0, &msg, + severity, + text); + send_message(msg); +} + + +void Mavlink::send_heartbeat(void) +{ + uint8_t control_mode = 0; + mavlink_message_t msg; + mavlink_msg_heartbeat_pack(RF_.params_.get_param_int(PARAM_SYSTEM_ID), 0, &msg, + RF_.params_.get_param_int(PARAM_FIXED_WING) ? MAV_TYPE_FIXED_WING : MAV_TYPE_QUADROTOR, + 0, 0, 0, 0); + send_message(msg); +} + +void Mavlink::send_status(void) +{ + if (!initialized_) + return; + + uint8_t control_mode = 0; + if (RF_.params_.get_param_int(PARAM_FIXED_WING)) + control_mode = MODE_PASS_THROUGH; + else if (RF_.command_manager_.combined_control().x.type == ANGLE) + control_mode = MODE_ROLL_PITCH_YAWRATE_THROTTLE; + else + control_mode = MODE_ROLLRATE_PITCHRATE_YAWRATE_THROTTLE; + + mavlink_message_t msg; + mavlink_msg_rosflight_status_pack(RF_.params_.get_param_int(PARAM_SYSTEM_ID), 0, &msg, + RF_.state_manager_.state().armed, + RF_.state_manager_.state().failsafe, + RF_.command_manager_.rc_override_active(), + RF_.command_manager_.offboard_control_active(), + RF_.state_manager_.state().error_codes, + control_mode, + RF_.board_.num_sensor_errors(), + RF_.get_loop_time_us()); + send_message(msg); +} + + +void Mavlink::send_attitude(void) +{ + mavlink_message_t msg; + mavlink_msg_attitude_quaternion_pack(sysid_, compid_, &msg, + RF_.estimator_.state().timestamp_us / 1000, + RF_.estimator_.state().attitude.w, + RF_.estimator_.state().attitude.x, + RF_.estimator_.state().attitude.y, + RF_.estimator_.state().attitude.z, + RF_.estimator_.state().angular_velocity.x, + RF_.estimator_.state().angular_velocity.y, + RF_.estimator_.state().angular_velocity.z); + send_message(msg); +} + +void Mavlink::send_imu(void) +{ + // if(RF_.sensors_.should_send_imu_data()) + // { + mavlink_message_t msg; + vector_t accel = RF_.sensors_.data().accel; + vector_t gyro = RF_.sensors_.data().gyro; + mavlink_msg_small_imu_pack(sysid_, compid_, &msg, + RF_.sensors_.data().imu_time, + accel.x, + accel.y, + accel.z, + gyro.x, + gyro.y, + gyro.z, + RF_.sensors_.data().imu_temperature); + send_message(msg); + // } + // else + // { + // Otherwise, wait and signal that we still need to send IMU + // mavlink_streams[STREAM_ID_IMU].next_time_us -= mavlink_streams[STREAM_ID_IMU].period_us; + // } + +} + +void Mavlink::send_output_raw(void) +{ + mavlink_message_t msg; + mavlink_msg_rosflight_output_raw_pack(sysid_, compid_, &msg, + RF_.board_.clock_millis(), + RF_.mixer_.get_outputs()); + send_message(msg); +} + +void Mavlink::send_rc_raw(void) +{ + mavlink_message_t msg; + mavlink_msg_rc_channels_pack(sysid_, compid_, &msg, + RF_.board_.clock_millis(), + 0, + RF_.board_.pwm_read(0), + RF_.board_.pwm_read(1), + RF_.board_.pwm_read(2), + RF_.board_.pwm_read(3), + RF_.board_.pwm_read(4), + RF_.board_.pwm_read(5), + RF_.board_.pwm_read(6), + RF_.board_.pwm_read(7), + 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 0); + send_message(msg); +} + +void Mavlink::send_diff_pressure(void) +{ + if (RF_.sensors_.data().diff_pressure_valid) + { + mavlink_message_t msg; + mavlink_msg_diff_pressure_pack(sysid_, compid_, &msg, + RF_.sensors_.data().diff_pressure_velocity, + RF_.sensors_.data().diff_pressure, + RF_.sensors_.data().diff_pressure_temp); + send_message(msg); + } +} + +void Mavlink::send_baro(void) +{ + if (RF_.sensors_.data().baro_valid) + { + mavlink_message_t msg; + mavlink_msg_small_baro_pack(sysid_, compid_, &msg, + RF_.sensors_.data().baro_altitude, + RF_.sensors_.data().baro_pressure, + RF_.sensors_.data().baro_temperature); + send_message(msg); + } +} + +void Mavlink::send_sonar(void) +{ + if (RF_.sensors_.data().sonar_range_valid) + { + mavlink_message_t msg; + mavlink_msg_small_range_pack(sysid_, compid_, &msg, + ROSFLIGHT_RANGE_SONAR, + RF_.sensors_.data().sonar_range, + 8.0, + 0.25); + send_message(msg); + } +} + +void Mavlink::send_mag(void) +{ + if (RF_.sensors_.data().mag_present) + { + mavlink_message_t msg; + mavlink_msg_small_mag_pack(sysid_, compid_, &msg, + RF_.sensors_.data().mag.x, + RF_.sensors_.data().mag.y, + RF_.sensors_.data().mag.z); + send_message(msg); + } +} + +void Mavlink::send_low_priority(void) +{ + send_next_param(); +} + +// function definitions +void Mavlink::stream() +{ + uint64_t time_us = RF_.board_.clock_micros(); + for (int i = 0; i < STREAM_COUNT; i++) + { + if (mavlink_streams_[i].period_us > 0 && time_us >= mavlink_streams_[i].next_time_us) + { + // If you fall behind, skip messages + do + { + mavlink_streams_[i].next_time_us += mavlink_streams_[i].period_us; + } while(mavlink_streams_[i].next_time_us < time_us); + + (this->*mavlink_streams_[i].send_function)(); + } + } +} + +void Mavlink::set_streaming_rate(uint8_t stream_id, int16_t param_id) +{ + mavlink_streams_[stream_id].period_us = (RF_.params_.get_param_int(param_id) == 0 ? 0 : 1000000/RF_.params_.get_param_int(param_id)); +} + +void Mavlink::stream_set_period(uint8_t stream_id, uint32_t period_us) +{ + mavlink_streams_[stream_id].period_us = period_us; +} + + +void Mavlink::send_named_value_int(const char *const name, int32_t value) +{ + mavlink_message_t msg; + mavlink_msg_named_value_int_pack(sysid_, compid_, &msg, RF_.board_.clock_millis(), name, value); + send_message(msg); +} + +void Mavlink::send_named_value_float(const char *const name, float value) +{ + mavlink_message_t msg; + mavlink_msg_named_value_float_pack(sysid_, compid_, &msg, RF_.board_.clock_millis(), name, value); + send_message(msg); +} + +//void Mavlink::mavlink_send_named_command_struct(const char *const name, control_t command_struct) +//{ +// uint8_t control_mode; +// if (command_struct.x.type == RATE && command_struct.y.type == RATE) +// { +// control_mode = MODE_ROLLRATE_PITCHRATE_YAWRATE_THROTTLE; +// } +// else if (command_struct.x.type == ANGLE && command_struct.y.type == ANGLE) +// { +// if (command_struct.x.type == ALTITUDE) +// { +// control_mode = MODE_ROLL_PITCH_YAWRATE_ALTITUDE; +// } +// else +// { +// control_mode = MODE_ROLL_PITCH_YAWRATE_THROTTLE; +// } +// } +// else +// { +// control_mode = MODE_PASS_THROUGH; +// } +// uint8_t ignore = !(command_struct.x.active) || +// !(command_struct.y.active) << 1 || +// !(command_struct.z.active) << 2 || +// !(command_struct.F.active) << 3; +// mavlink_message_t msg; +// mavlink_msg_named_command_struct_pack(sysid, compid, &msg, name, +// control_mode, +// ignore, +// command_struct.x.value, +// command_struct.y.value, +// command_struct.z.value, +// command_struct.F.value); +// send_message(msg); +//} + + +} + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/mixer.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/mixer.cpp new file mode 100644 index 0000000..f98b47e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/mixer.cpp @@ -0,0 +1,205 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +#include "mixer.h" +#include "rosflight.h" + +namespace rosflight_firmware +{ + +Mixer::Mixer(ROSflight &_rf) : + RF_(_rf) +{} + +void Mixer::init() +{ + RF_.params_.add_callback(std::bind(&Mixer::param_change_callback, this, std::placeholders::_1), PARAM_MOTOR_PWM_SEND_RATE); + RF_.params_.add_callback(std::bind(&Mixer::param_change_callback, this, std::placeholders::_1), PARAM_MOTOR_MIN_PWM); + RF_.params_.add_callback(std::bind(&Mixer::param_change_callback, this, std::placeholders::_1), PARAM_RC_TYPE); + RF_.params_.add_callback(std::bind(&Mixer::param_change_callback, this, std::placeholders::_1), PARAM_MIXER); + + init_mixing(); + init_PWM(); +} + +void Mixer::param_change_callback(uint16_t param_id) +{ + switch (param_id) + { + case PARAM_MIXER: + init_mixing(); + break; + default: + init_PWM(); + break; + } +} + + +void Mixer::init_mixing() +{ + // clear the invalid mixer error + RF_.state_manager_.clear_error(StateManager::ERROR_INVALID_MIXER); + + uint8_t mixer_choice = RF_.params_.get_param_int(PARAM_MIXER); + + if (mixer_choice >= NUM_MIXERS) + { + RF_.mavlink_.log(Mavlink::LOG_ERROR, "Invalid Mixer Choice"); + mixer_choice = 0; + + // set the invalid mixer flag + RF_.state_manager_.set_error(StateManager::ERROR_INVALID_MIXER); + } + + mixer_to_use_ = array_of_mixers_[mixer_choice]; + + for (int8_t i=0; i<8; i++) + { + raw_outputs_[i] = 0.0f; + unsaturated_outputs_[i] = 0.0f; + } +} + +void Mixer::init_PWM() +{ + bool useCPPM = false; + if (RF_.params_.get_param_int(PARAM_RC_TYPE) == 1) + { + useCPPM = true; + } + int16_t motor_refresh_rate = RF_.params_.get_param_int(PARAM_MOTOR_PWM_SEND_RATE); + int16_t off_pwm = RF_.params_.get_param_int(PARAM_MOTOR_MIN_PWM); + RF_.board_.pwm_init(useCPPM, motor_refresh_rate, off_pwm); +} + + +void Mixer::write_motor(uint8_t index, float value) +{ + if (RF_.state_manager_.state().armed) + { + if (value > 1.0) + { + value = 1.0; + } + else if (value < RF_.params_.get_param_float(PARAM_MOTOR_IDLE_THROTTLE) + && RF_.params_.get_param_int(PARAM_SPIN_MOTORS_WHEN_ARMED)) + { + value = RF_.params_.get_param_float(PARAM_MOTOR_IDLE_THROTTLE); + } + else if (value < 0.0) + { + value = 0.0; + } + } + else + { + value = 0.0; + } + raw_outputs_[index] = value; + int32_t pwm_us = value * (RF_.params_.get_param_int(PARAM_MOTOR_MAX_PWM) - RF_.params_.get_param_int( + PARAM_MOTOR_MIN_PWM)) + RF_.params_.get_param_int(PARAM_MOTOR_MIN_PWM); + RF_.board_.pwm_write(index, pwm_us); +} + + +void Mixer::write_servo(uint8_t index, float value) +{ + if (value > 1.0) + { + value = 1.0; + } + else if (value < -1.0) + { + value = -1.0; + } + raw_outputs_[index] = value; + RF_.board_.pwm_write(index, raw_outputs_[index] * 500 + 1500); +} + + +void Mixer::mix_output() +{ + Controller::Output commands = RF_.controller_.output(); + float max_output = 1.0f; + + // Reverse Fixedwing channels just before mixing if we need to + if (RF_.params_.get_param_int(PARAM_FIXED_WING)) + { + commands.x *= RF_.params_.get_param_int(PARAM_AILERON_REVERSE) ? -1 : 1; + commands.y *= RF_.params_.get_param_int(PARAM_ELEVATOR_REVERSE) ? -1 : 1; + commands.z *= RF_.params_.get_param_int(PARAM_RUDDER_REVERSE) ? -1 : 1; + } + + for (int8_t i=0; i<8; i++) + { + if (mixer_to_use_->output_type[i] != NONE) + { + // Matrix multiply to mix outputs + unsaturated_outputs_[i] = (commands.F*mixer_to_use_->F[i] + commands.x*mixer_to_use_->x[i] + + commands.y*mixer_to_use_->y[i] + commands.z*mixer_to_use_->z[i]); + + // Save off the largest control output if it is greater than 1.0 for future scaling + if (unsaturated_outputs_[i] > max_output) + { + max_output = unsaturated_outputs_[i]; + } + } + } + + // saturate outputs to maintain controllability even during aggressive maneuvers + float scale_factor = 1.0; + if (max_output > 1.0) + { + scale_factor = 1.0/max_output; + } + + + + for (int8_t i=0; i<8; i++) + { + // Write output to motors + if (mixer_to_use_->output_type[i] == S) + { + write_servo(i, unsaturated_outputs_[i]); + } + else if (mixer_to_use_->output_type[i] == M) + { + // scale all motor outputs by scale factor (this is usually 1.0, unless we saturated) + unsaturated_outputs_[i] *= scale_factor; + write_motor(i, unsaturated_outputs_[i]); + } + } +} + +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/nanoprintf.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/nanoprintf.cpp new file mode 100644 index 0000000..974756c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/nanoprintf.cpp @@ -0,0 +1,263 @@ +/* + * Copyright (c) 2004,2012 Kustaa Nyholm / SpareTimeLabs + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or other + * materials provided with the distribution. + * + * Neither the name of the Kustaa Nyholm or SpareTimeLabs nor the names of its + * contributors may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. + * IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, + * INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, + * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY + * OF SUCH DAMAGE. + */ + +#include "nanoprintf.h" + +namespace rosflight_firmware +{ +namespace nanoprintf +{ + +typedef void (*putcf)(void *,char); +static putcf stdout_putf; +static void *stdout_putp; + + +#ifdef PRINTF_LONG_SUPPORT + +static void uli2a(unsigned long int num, unsigned int base, int uc,char *bf) +{ + int n=0; + unsigned int d=1; + while (num/d >= base) + d*=base; + while (d!=0) + { + int dgt = num / d; + num%=d; + d/=base; + if (n || dgt>0|| d==0) + { + *bf++ = dgt+(dgt<10 ? '0' : (uc ? 'A' : 'a')-10); + ++n; + } + } + *bf=0; +} + +static void li2a(long num, char *bf) +{ + if (num<0) + { + num=-num; + *bf++ = '-'; + } + uli2a(num,10,0,bf); +} + +#endif + +static void ui2a(unsigned int num, unsigned int base, int uc,char *bf) +{ + int n=0; + unsigned int d=1; + while (num/d >= base) + d*=base; + while (d!=0) + { + int dgt = num / d; + num%= d; + d/=base; + if (n || dgt>0 || d==0) + { + *bf++ = dgt+(dgt<10 ? '0' : (uc ? 'A' : 'a')-10); + ++n; + } + } + *bf=0; +} + +static void i2a(int num, char *bf) +{ + if (num<0) + { + num=-num; + *bf++ = '-'; + } + ui2a(num,10,0,bf); +} + +static int a2d(char ch) +{ + if (ch>='0' && ch<='9') + return ch-'0'; + else if (ch>='a' && ch<='f') + return ch-'a'+10; + else if (ch>='A' && ch<='F') + return ch-'A'+10; + else return -1; +} + +static char a2i(char ch, char **src,int base,int *nump) +{ + char *p= *src; + int num=0; + int digit; + while ((digit=a2d(ch))>=0) + { + if (digit>base) break; + num=num*base+digit; + ch=*p++; + } + *src=p; + *nump=num; + return ch; +} + +static void putchw(void *putp,putcf putf,int n, char z, char *bf) +{ + char fc=z? '0' : ' '; + char ch; + char *p=bf; + while (*p++ && n > 0) + n--; + while (n-- > 0) + putf(putp,fc); + while ((ch= *bf++)) + putf(putp,ch); +} + +void tfp_format(void *putp, putcf putf, const char *fmt, va_list va) +{ + char bf[12]; + + char ch; + + + while ((ch=*(fmt++))) + { + if (ch!='%') + putf(putp,ch); + else + { + char lz=0; +#ifdef PRINTF_LONG_SUPPORT + char lng=0; +#endif + int w=0; + ch=*(fmt++); + if (ch=='0') + { + ch=*(fmt++); + lz=1; + } + if (ch>='0' && ch<='9') + { + ch=a2i(ch, (char **)&fmt, 10, &w); + } +#ifdef PRINTF_LONG_SUPPORT + if (ch=='l') + { + ch=*(fmt++); + lng=1; + } +#endif + switch (ch) + { + case 0: + goto abort; + case 'u' : + { +#ifdef PRINTF_LONG_SUPPORT + if (lng) + uli2a(va_arg(va, unsigned long int),10,0,bf); + else +#endif + ui2a(va_arg(va, unsigned int),10,0,bf); + putchw(putp,putf,w,lz,bf); + break; + } + case 'd' : + { +#ifdef PRINTF_LONG_SUPPORT + if (lng) + li2a(va_arg(va, unsigned long int),bf); + else +#endif + i2a(va_arg(va, int),bf); + putchw(putp,putf,w,lz,bf); + break; + } + case 'x': + case 'X' : +#ifdef PRINTF_LONG_SUPPORT + if (lng) + uli2a(va_arg(va, unsigned long int),16,(ch=='X'),bf); + else +#endif + ui2a(va_arg(va, unsigned int),16,(ch=='X'),bf); + putchw(putp,putf,w,lz,bf); + break; + case 'c' : + putf(putp,(char)(va_arg(va, int))); + break; + case 's' : + putchw(putp,putf,w,0,va_arg(va, char *)); + break; + case '%' : + putf(putp,ch); + default: + break; + } + } + } +abort: + ; +} + + +void init_printf(void *putp, void (*putf)(void *, char)) +{ + stdout_putf=putf; + stdout_putp=putp; +} + +void tfp_printf(const char *fmt, ...) +{ + va_list va; + va_start(va,fmt); + tfp_format(stdout_putp,stdout_putf,fmt,va); + va_end(va); +} + +static void putcp(void *p,char c) +{ + *(*((char **)p))++ = c; +} + +void tfp_sprintf(char *s, const char *fmt, va_list va) +{ + tfp_format(&s,putcp,fmt,va); + putcp(&s,0); +} + +} // namespace nanoprintf +} // namespace rosflight_firmware diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/param.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/param.cpp new file mode 100644 index 0000000..9f6a20c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/param.cpp @@ -0,0 +1,349 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#pragma GCC diagnostic ignored "-Wstrict-aliasing" + +#include +#include +#include + +#include "board.h" +#include "mavlink.h" +#include "mixer.h" + +#include "param.h" + +#include "rosflight.h" + +namespace rosflight_firmware +{ + +Params::Params(ROSflight& _rf) : + RF_(_rf) +{ + for (uint16_t id = 0; id < PARAMS_COUNT; id++) + callbacks[id] = NULL; +} + +// local function definitions +void Params::init_param_int(uint16_t id, const char name[PARAMS_NAME_LENGTH], int32_t value) +{ + memcpy(params.names[id], name, PARAMS_NAME_LENGTH); + params.values[id] = value; + params.types[id] = PARAM_TYPE_INT32; +} + +void Params::init_param_float(uint16_t id, const char name[PARAMS_NAME_LENGTH], float value) +{ + memcpy(params.names[id], name, PARAMS_NAME_LENGTH); + params.values[id] = *((int32_t *) &value); + params.types[id] = PARAM_TYPE_FLOAT; +} + +uint8_t Params::compute_checksum(void) +{ + uint8_t chk = 0; + const uint8_t *p; + + for (p = (const uint8_t *)¶ms.values; p < ((const uint8_t *)¶ms.values + 4*PARAMS_COUNT); p++) + chk ^= *p; + for (p = (const uint8_t *)¶ms.names; p < ((const uint8_t *)¶ms.names + PARAMS_COUNT*PARAMS_NAME_LENGTH); p++) + chk ^= *p; + for (p = (const uint8_t *)¶ms.types; p < ((const uint8_t *)¶ms.types + PARAMS_COUNT); p++) + chk ^= *p; + + return chk; +} + +// function definitions +void Params::init() +{ + RF_.board_.memory_init(); + if (!read()) + { + set_defaults(); + write(); + } +} + +void Params::set_defaults(void) +{ + /******************************/ + /*** HARDWARE CONFIGURATION ***/ + /******************************/ + init_param_int(PARAM_BAUD_RATE, "BAUD_RATE", 921600); // Baud rate of MAVlink communication with onboard computer | 9600 | 921600 + + /*****************************/ + /*** MAVLINK CONFIGURATION ***/ + /*****************************/ + init_param_int(PARAM_SYSTEM_ID, "SYS_ID", 1); // Mavlink System ID | 1 | 255 + init_param_int(PARAM_STREAM_HEARTBEAT_RATE, "STRM_HRTBT", 1); // Rate of heartbeat streaming (Hz) | 0 | 1000 + init_param_int(PARAM_STREAM_STATUS_RATE, "STRM_STATUS", 10); // Rate of status streaming (Hz) | 0 | 1000 + + init_param_int(PARAM_STREAM_ATTITUDE_RATE, "STRM_ATTITUDE", 200); // Rate of attitude stream (Hz) | 0 | 1000 + init_param_int(PARAM_STREAM_IMU_RATE, "STRM_IMU", 500); // Rate of IMU stream (Hz) | 0 | 1000 + init_param_int(PARAM_STREAM_MAG_RATE, "STRM_MAG", 50); // Rate of magnetometer stream (Hz) | 0 | 75 + init_param_int(PARAM_STREAM_BARO_RATE, "STRM_BARO", 50); // Rate of barometer stream (Hz) | 0 | 100 + init_param_int(PARAM_STREAM_AIRSPEED_RATE, "STRM_AIRSPEED", 20); // Rate of airspeed stream (Hz) | 0 | 50 + init_param_int(PARAM_STREAM_SONAR_RATE, "STRM_SONAR", 40); // Rate of sonar stream (Hz) | 0 | 40 + + init_param_int(PARAM_STREAM_OUTPUT_RAW_RATE, "STRM_SERVO", 50); // Rate of raw output stream | 0 | 490 + init_param_int(PARAM_STREAM_RC_RAW_RATE, "STRM_RC", 50); // Rate of raw RC input stream | 0 | 50 + + /********************************/ + /*** CONTROLLER CONFIGURATION ***/ + /********************************/ + init_param_float(PARAM_MAX_COMMAND, "PARAM_MAX_CMD", 1.0); // saturation point for PID controller output | 0 | 1.0 + + init_param_float(PARAM_PID_ROLL_RATE_P, "PID_ROLL_RATE_P", 0.070f); // Roll Rate Proportional Gain | 0.0 | 1000.0 + init_param_float(PARAM_PID_ROLL_RATE_I, "PID_ROLL_RATE_I", 0.000f); // Roll Rate Integral Gain | 0.0 | 1000.0 + init_param_float(PARAM_PID_ROLL_RATE_D, "PID_ROLL_RATE_D", 0.000f); // Rall Rate Derivative Gain | 0.0 | 1000.0 + + init_param_float(PARAM_PID_PITCH_RATE_P, "PID_PITCH_RATE_P", 0.070f); // Pitch Rate Proporitional Gain | 0.0 | 1000.0 + init_param_float(PARAM_PID_PITCH_RATE_I, "PID_PITCH_RATE_I", 0.0000f); // Pitch Rate Integral Gain | 0.0 | 1000.0 + init_param_float(PARAM_PID_PITCH_RATE_D, "PID_PITCH_RATE_D", 0.0000f); // Pitch Rate Derivative Gain | 0.0 | 1000.0 + + init_param_float(PARAM_PID_YAW_RATE_P, "PID_YAW_RATE_P", 0.25f); // Yaw Rate Proporitional Gain | 0.0 | 1000.0 + init_param_float(PARAM_PID_YAW_RATE_I, "PID_YAW_RATE_I", 0.0f); // Yaw Rate Integral Gain | 0.0 | 1000.0 + init_param_float(PARAM_PID_YAW_RATE_D, "PID_YAW_RATE_D", 0.0f); // Yaw Rate Derivative Gain | 0.0 | 1000.0 + + init_param_float(PARAM_PID_ROLL_ANGLE_P, "PID_ROLL_ANG_P", 0.15f); // Roll Angle Proporitional Gain | 0.0 | 1000.0 + init_param_float(PARAM_PID_ROLL_ANGLE_I, "PID_ROLL_ANG_I", 0.0f); // Roll Angle Integral Gain | 0.0 | 1000.0 + init_param_float(PARAM_PID_ROLL_ANGLE_D, "PID_ROLL_ANG_D", 0.05f); // Roll Angle Derivative Gain | 0.0 | 1000.0 + + init_param_float(PARAM_PID_PITCH_ANGLE_P, "PID_PITCH_ANG_P", 0.15f); // Pitch Angle Proporitional Gain | 0.0 | 1000.0 + init_param_float(PARAM_PID_PITCH_ANGLE_I, "PID_PITCH_ANG_I", 0.0f); // Pitch Angle Integral Gain | 0.0 | 1000.0 + init_param_float(PARAM_PID_PITCH_ANGLE_D, "PID_PITCH_ANG_D", 0.05f); // Pitch Angle Derivative Gain | 0.0 | 1000.0 + + init_param_float(PARAM_X_EQ_TORQUE, "X_EQ_TORQUE", 0.0f); // Equilibrium torque added to output of controller on x axis | -1.0 | 1.0 + init_param_float(PARAM_Y_EQ_TORQUE, "Y_EQ_TORQUE", 0.0f); // Equilibrium torque added to output of controller on y axis | -1.0 | 1.0 + init_param_float(PARAM_Z_EQ_TORQUE, "Z_EQ_TORQUE", 0.0f); // Equilibrium torque added to output of controller on z axis | -1.0 | 1.0 + + init_param_float(PARAM_PID_TAU, "PID_TAU", 0.05f); // Dirty Derivative time constant - See controller documentation | 0.0 | 1.0 + + + /*************************/ + /*** PWM CONFIGURATION ***/ + /*************************/ + init_param_int(PARAM_MOTOR_PWM_SEND_RATE, "MOTOR_PWM_UPDATE", 490); // Refresh rate of motor commands to motors - See motor documentation | 0 | 1000 + init_param_float(PARAM_MOTOR_IDLE_THROTTLE, "MOTOR_IDLE_THR", 0.1); // min throttle command sent to motors when armed (Set above 0.1 to spin when armed) | 0.0 | 1.0 + init_param_float(PARAM_FAILSAFE_THROTTLE, "FAILSAFE_THR", 0.3); // Throttle sent to motors in failsafe condition (set just below hover throttle) | 0.0 | 1.0 + init_param_int(PARAM_MOTOR_MIN_PWM, "MOTOR_MIN_PWM", 1000); // PWM value sent to motor ESCs at zero throttle | 1000 | 2000 + init_param_int(PARAM_MOTOR_MAX_PWM, "MOTOR_MAX_PWM", 2000); // PWM value sent to motor ESCs at full throttle | 1000 | 2000 + init_param_int(PARAM_SPIN_MOTORS_WHEN_ARMED, "ARM_SPIN_MOTORS", true); // Enforce MOTOR_IDLE_THR | 0 | 1 + + /*******************************/ + /*** ESTIMATOR CONFIGURATION ***/ + /*******************************/ + init_param_int(PARAM_INIT_TIME, "FILTER_INIT_T", 3000); // Time in ms to initialize estimator | 0 | 100000 + init_param_float(PARAM_FILTER_KP, "FILTER_KP", 0.5f); // estimator proportional gain - See estimator documentation | 0 | 10.0 + init_param_float(PARAM_FILTER_KI, "FILTER_KI", 0.05f); // estimator integral gain - See estimator documentation | 0 | 1.0 + + init_param_int(PARAM_FILTER_USE_QUAD_INT, "FILTER_QUAD_INT", 1); // Perform a quadratic averaging of LPF gyro data prior to integration (adds ~20 us to estimation loop on F1 processors) | 0 | 1 + init_param_int(PARAM_FILTER_USE_MAT_EXP, "FILTER_MAT_EXP", 1); // 1 - Use matrix exponential to improve gyro integration (adds ~90 us to estimation loop in F1 processors) 0 - use euler integration | 0 | 1 + init_param_int(PARAM_FILTER_USE_ACC, "FILTER_USE_ACC", 1); // Use accelerometer to correct gyro integration drift (adds ~70 us to estimation loop) | 0 | 1 + + init_param_int(PARAM_CALIBRATE_GYRO_ON_ARM, "CAL_GYRO_ARM", false); // True if desired to calibrate gyros on arm | 0 | 1 + + init_param_float(PARAM_GYRO_ALPHA, "GYRO_LPF_ALPHA", 0.3f); // Low-pass filter constant - See estimator documentation | 0 | 1.0 + init_param_float(PARAM_ACC_ALPHA, "ACC_LPF_ALPHA", 0.5f); // Low-pass filter constant - See estimator documentation | 0 | 1.0 + + init_param_float(PARAM_GYRO_X_BIAS, "GYRO_X_BIAS", 0.0f); // Constant x-bias of gyroscope readings | -1.0 | 1.0 + init_param_float(PARAM_GYRO_Y_BIAS, "GYRO_Y_BIAS", 0.0f); // Constant y-bias of gyroscope readings | -1.0 | 1.0 + init_param_float(PARAM_GYRO_Z_BIAS, "GYRO_Z_BIAS", 0.0f); // Constant z-bias of gyroscope readings | -1.0 | 1.0 + init_param_float(PARAM_ACC_X_BIAS, "ACC_X_BIAS", 0.0f); // Constant x-bias of accelerometer readings | -2.0 | 2.0 + init_param_float(PARAM_ACC_Y_BIAS, "ACC_Y_BIAS", 0.0f); // Constant y-bias of accelerometer readings | -2.0 | 2.0 + init_param_float(PARAM_ACC_Z_BIAS, "ACC_Z_BIAS", 0.0f); // Constant z-bias of accelerometer readings | -2.0 | 2.0 + init_param_float(PARAM_ACC_X_TEMP_COMP, "ACC_X_TEMP_COMP", 0.0f); // Linear x-axis temperature compensation constant | -2.0 | 2.0 + init_param_float(PARAM_ACC_Y_TEMP_COMP, "ACC_Y_TEMP_COMP", 0.0f); // Linear y-axis temperature compensation constant | -2.0 | 2.0 + init_param_float(PARAM_ACC_Z_TEMP_COMP, "ACC_Z_TEMP_COMP", 0.0f); // Linear z-axis temperature compensation constant | -2.0 | 2.0 + + init_param_float(PARAM_MAG_A11_COMP, "MAG_A11_COMP", 1.0f); // Soft iron compensation constant | -999.0 | 999.0 + init_param_float(PARAM_MAG_A12_COMP, "MAG_A12_COMP", 0.0f); // Soft iron compensation constant | -999.0 | 999.0 + init_param_float(PARAM_MAG_A13_COMP, "MAG_A13_COMP", 0.0f); // Soft iron compensation constant | -999.0 | 999.0 + init_param_float(PARAM_MAG_A21_COMP, "MAG_A21_COMP", 0.0f); // Soft iron compensation constant | -999.0 | 999.0 + init_param_float(PARAM_MAG_A22_COMP, "MAG_A22_COMP", 1.0f); // Soft iron compensation constant | -999.0 | 999.0 + init_param_float(PARAM_MAG_A23_COMP, "MAG_A23_COMP", 0.0f); // Soft iron compensation constant | -999.0 | 999.0 + init_param_float(PARAM_MAG_A31_COMP, "MAG_A31_COMP", 0.0f); // Soft iron compensation constant | -999.0 | 999.0 + init_param_float(PARAM_MAG_A32_COMP, "MAG_A32_COMP", 0.0f); // Soft iron compensation constant | -999.0 | 999.0 + init_param_float(PARAM_MAG_A33_COMP, "MAG_A33_COMP", 1.0f); // Soft iron compensation constant | -999.0 | 999.0 + init_param_float(PARAM_MAG_X_BIAS, "MAG_X_BIAS", 0.0f); // Hard iron compensation constant | -999.0 | 999.0 + init_param_float(PARAM_MAG_Y_BIAS, "MAG_Y_BIAS", 0.0f); // Hard iron compensation constant | -999.0 | 999.0 + init_param_float(PARAM_MAG_Z_BIAS, "MAG_Z_BIAS", 0.0f); // Hard iron compensation constant | -999.0 | 999.0 + + init_param_float(PARAM_BARO_BIAS, "BARO_BIAS", 0.0f); // Barometer measurement bias (Pa) | 0 | inf + init_param_float(PARAM_GROUND_LEVEL, "GROUND_LEVEL", 1387.0f); // Altitude of ground level (m) | -1000 | 10000 + + init_param_float(PARAM_DIFF_PRESS_BIAS, "DIFF_PRESS_BIAS", 0.0f); // Differential Pressure Bias (Pa) | -10 | 10 + + /************************/ + /*** RC CONFIGURATION ***/ + /************************/ + init_param_int(PARAM_RC_TYPE, "RC_TYPE", 1); // Type of RC input 0 - Parallel PWM (PWM), 1 - Pulse-Position Modulation (PPM) | 0 | 1 + init_param_int(PARAM_RC_X_CHANNEL, "RC_X_CHN", 0); // RC input channel mapped to x-axis commands [0 - indexed] | 0 | 3 + init_param_int(PARAM_RC_Y_CHANNEL, "RC_Y_CHN", 1); // RC input channel mapped to y-axis commands [0 - indexed] | 0 | 3 + init_param_int(PARAM_RC_Z_CHANNEL, "RC_Z_CHN", 3); // RC input channel mapped to z-axis commands [0 - indexed] | 0 | 3 + init_param_int(PARAM_RC_F_CHANNEL, "RC_F_CHN", 2); // RC input channel mapped to F-axis commands [0 - indexed] | 0 | 3 + init_param_int(PARAM_RC_ATTITUDE_OVERRIDE_CHANNEL, "RC_ATT_OVRD_CHN", 4); // RC switch mapped to attitude override [0 indexed, -1 to disable] | 4 | 7 + init_param_int(PARAM_RC_THROTTLE_OVERRIDE_CHANNEL, "RC_THR_OVRD_CHN", 4); // RC switch channel mapped to throttle override [0 indexed, -1 to disable] | 4 | 7 + init_param_int(PARAM_RC_ATT_CONTROL_TYPE_CHANNEL, "RC_ATT_CTRL_CHN", -1); // RC switch channel mapped to attitude control type [0 indexed, -1 to disable] | 4 | 7 + init_param_int(PARAM_RC_ARM_CHANNEL, "ARM_CHANNEL", -1); // RC switch channel mapped to arming (only if PARAM_ARM_STICKS is false) [0 indexed, -1 to disable] | 4 | 7 + init_param_int(PARAM_RC_NUM_CHANNELS, "RC_NUM_CHN", 6); // number of RC input channels | 1 | 8 + + init_param_int(PARAM_RC_SWITCH_5_DIRECTION, "SWITCH_5_DIR", 1); // RC switch 5 toggle direction | -1 | 1 + init_param_int(PARAM_RC_SWITCH_6_DIRECTION, "SWITCH_6_DIR", 1); // RC switch 6 toggle direction | -1 | 1 + init_param_int(PARAM_RC_SWITCH_7_DIRECTION, "SWITCH_7_DIR", 1); // RC switch 7 toggle direction | -1 | 1 + init_param_int(PARAM_RC_SWITCH_8_DIRECTION, "SWITCH_8_DIR", 1); // RC switch 8 toggle direction | -1 | 1 + + init_param_float(PARAM_RC_OVERRIDE_DEVIATION, "RC_OVRD_DEV", 0.1); // RC stick deviation from center for overrride | 0.0 | 1.0 + init_param_int(PARAM_OVERRIDE_LAG_TIME, "OVRD_LAG_TIME", 1000); // RC stick deviation lag time before returning control (ms) | 0 | 100000 + init_param_int(PARAM_RC_OVERRIDE_TAKE_MIN_THROTTLE, "MIN_THROTTLE", false); // Take minimum throttle between RC and computer at all times | 0 | 1 + + init_param_int(PARAM_RC_ATTITUDE_MODE, "RC_ATT_MODE", 1); // Attitude mode for RC sticks (0: rate, 1: angle). Overridden if RC_ATT_CTRL_CHN is set. | 0 | 1 + init_param_float(PARAM_RC_MAX_ROLL, "RC_MAX_ROLL", 0.786f); // Maximum roll angle command sent by full deflection of RC sticks | 0.0 | 3.14159 + init_param_float(PARAM_RC_MAX_PITCH, "RC_MAX_PITCH", 0.786f); // Maximum pitch angle command sent by full stick deflection of RC sticks | 0.0 | 3.14159 + init_param_float(PARAM_RC_MAX_ROLLRATE, "RC_MAX_ROLLRATE", 3.14159f); // Maximum roll rate command sent by full stick deflection of RC sticks | 0.0 | 9.42477796077 + init_param_float(PARAM_RC_MAX_PITCHRATE, "RC_MAX_PITCHRATE", 3.14159f); // Maximum pitch command sent by full stick deflection of RC sticks | 0.0 | 3.14159 + init_param_float(PARAM_RC_MAX_YAWRATE, "RC_MAX_YAWRATE", 1.507f); // Maximum pitch command sent by full stick deflection of RC sticks | 0.0 | 3.14159 + + /***************************/ + /*** FRAME CONFIGURATION ***/ + /***************************/ + init_param_int(PARAM_MIXER, "MIXER", Mixer::INVALID_MIXER); // Which mixer to choose - See Mixer documentation | 0 | 10 + + init_param_int(PARAM_FIXED_WING, "FIXED_WING", false); // switches on passthrough commands for fixedwing operation | 0 | 1 + init_param_int(PARAM_ELEVATOR_REVERSE, "ELEVATOR_REV", 0); // reverses elevator servo output | 0 | 1 + init_param_int(PARAM_AILERON_REVERSE, "AIL_REV", 0); // reverses aileron servo output | 0 | 1 + init_param_int(PARAM_RUDDER_REVERSE, "RUDDER_REV", 0); // reverses rudder servo output | 0 | 1 + + /********************/ + /*** ARMING SETUP ***/ + /********************/ + init_param_float(PARAM_ARM_THRESHOLD, "ARM_THRESHOLD", 0.15); // RC deviation from max/min in yaw and throttle for arming and disarming check (us) | 0 | 500 +} + +void Params::add_callback(std::function callback, uint16_t param_id) +{ + callbacks[param_id] = callback; + callback(param_id); +} + +bool Params::read(void) +{ + if (!RF_.board_.memory_read(¶ms, sizeof(params_t))) + return false; + + if (params.version != GIT_VERSION_HASH) + return false; + + if (params.size != sizeof(params_t) || params.magic_be != 0xBE || params.magic_ef != 0xEF) + return false; + + if (compute_checksum() != params.chk) + return false; + + return true; +} + +bool Params::write(void) +{ + params.version = GIT_VERSION_HASH; + params.size = sizeof(params_t); + params.magic_be = 0xBE; + params.magic_ef = 0xEF; + params.chk = compute_checksum(); + + if (!RF_.board_.memory_write(¶ms, sizeof(params_t))) + return false; + return true; +} + +void Params::change_callback(uint16_t id) +{ + // call the callback function + if(callbacks[id]) + callbacks[id](id); +} + +uint16_t Params::lookup_param_id(const char name[PARAMS_NAME_LENGTH]) +{ + for (uint16_t id = 0; id < PARAMS_COUNT; id++) + { + bool match = true; + for (uint8_t i = 0; i < PARAMS_NAME_LENGTH; i++) + { + // compare each character + if (name[i] != params.names[id][i]) + { + match = false; + break; + } + + // stop comparing if end of string is reached + if (params.names[id][i] == '\0') + break; + } + + if (match) + return (uint16_t) id; + } + + return PARAMS_COUNT; +} + +bool Params::set_param_int(uint16_t id, int32_t value) +{ + if (id < PARAMS_COUNT && value != params.values[id]) + { + params.values[id] = value; + change_callback(id); + RF_.mavlink_.update_param(id); + return true; + } + return false; +} + +bool Params::set_param_float(uint16_t id, float value) +{ + return set_param_int(id, *(int32_t *) &value); +} + +bool Params::set_param_by_name_int(const char name[PARAMS_NAME_LENGTH], int32_t value) +{ + uint16_t id = lookup_param_id(name); + return set_param_int(id, value); +} + +bool Params::set_param_by_name_float(const char name[PARAMS_NAME_LENGTH], float value) +{ + return set_param_by_name_int(name, *(int32_t *) &value); +} +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/rc.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/rc.cpp new file mode 100644 index 0000000..32518c4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/rc.cpp @@ -0,0 +1,322 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include "rc.h" +#include "rosflight.h" + +namespace rosflight_firmware +{ + +RC::RC(ROSflight &_rf) : + RF_(_rf) +{} + +void RC::init() +{ + RF_.params_.add_callback(std::bind(&RC::param_change_callback, this, std::placeholders::_1), PARAM_RC_ATTITUDE_OVERRIDE_CHANNEL); + RF_.params_.add_callback(std::bind(&RC::param_change_callback, this, std::placeholders::_1), PARAM_RC_THROTTLE_OVERRIDE_CHANNEL); + RF_.params_.add_callback(std::bind(&RC::param_change_callback, this, std::placeholders::_1), PARAM_RC_ATT_CONTROL_TYPE_CHANNEL); + RF_.params_.add_callback(std::bind(&RC::param_change_callback, this, std::placeholders::_1), PARAM_RC_ARM_CHANNEL); + RF_.params_.add_callback(std::bind(&RC::param_change_callback, this, std::placeholders::_1), PARAM_RC_X_CHANNEL); + RF_.params_.add_callback(std::bind(&RC::param_change_callback, this, std::placeholders::_1), PARAM_RC_Y_CHANNEL); + RF_.params_.add_callback(std::bind(&RC::param_change_callback, this, std::placeholders::_1), PARAM_RC_Z_CHANNEL); + RF_.params_.add_callback(std::bind(&RC::param_change_callback, this, std::placeholders::_1), PARAM_RC_F_CHANNEL); + RF_.params_.add_callback(std::bind(&RC::param_change_callback, this, std::placeholders::_1), PARAM_RC_SWITCH_5_DIRECTION); + RF_.params_.add_callback(std::bind(&RC::param_change_callback, this, std::placeholders::_1), PARAM_RC_SWITCH_6_DIRECTION); + RF_.params_.add_callback(std::bind(&RC::param_change_callback, this, std::placeholders::_1), PARAM_RC_SWITCH_7_DIRECTION); + RF_.params_.add_callback(std::bind(&RC::param_change_callback, this, std::placeholders::_1), PARAM_RC_SWITCH_8_DIRECTION); + init_rc(); + new_command_ = false; +} + +void RC::init_rc() +{ + init_sticks(); + init_switches(); +} + +void RC::param_change_callback(uint16_t param_id) +{ + init_rc(); +} + +float RC::stick(Stick channel) +{ + return stick_values[channel]; +} + +bool RC::switch_on(Switch channel) +{ + return switch_values[channel]; +} + +bool RC::switch_mapped(Switch channel) +{ + return switches[channel].mapped; +} + + +void RC::init_sticks(void) +{ + sticks[STICK_X].channel = RF_.params_.get_param_int(PARAM_RC_X_CHANNEL); + sticks[STICK_X].one_sided = false; + + sticks[STICK_Y].channel = RF_.params_.get_param_int(PARAM_RC_Y_CHANNEL); + sticks[STICK_Y].one_sided = false; + + sticks[STICK_Z].channel = RF_.params_.get_param_int(PARAM_RC_Z_CHANNEL); + sticks[STICK_Z].one_sided = false; + + sticks[STICK_F].channel = RF_.params_.get_param_int(PARAM_RC_F_CHANNEL); + sticks[STICK_F].one_sided = true; +} + +void RC::init_switches() +{ + for (uint8_t chan = 0; chan < (uint8_t) SWITCHES_COUNT; chan++) + { + char channel_name[18]; + switch (chan) + { + case SWITCH_ARM: + strcpy(channel_name, "ARM"); + switches[chan].channel = RF_.params_.get_param_int(PARAM_RC_ARM_CHANNEL); + break; + case SWITCH_ATT_OVERRIDE: + strcpy(channel_name, "ATTITUDE OVERRIDE"); + switches[chan].channel = RF_.params_.get_param_int(PARAM_RC_ATTITUDE_OVERRIDE_CHANNEL); + break; + case SWITCH_THROTTLE_OVERRIDE: + strcpy(channel_name, "THROTTLE OVERRIDE"); + switches[chan].channel = RF_.params_.get_param_int(PARAM_RC_THROTTLE_OVERRIDE_CHANNEL); + break; + case SWITCH_ATT_TYPE: + strcpy(channel_name, "ATTITUDE TYPE"); + switches[chan].channel = RF_.params_.get_param_int(PARAM_RC_ATT_CONTROL_TYPE_CHANNEL); + break; + default: + strcpy(channel_name, "INVALID"); + switches[chan].channel = 255; + break; + } + + switches[chan].mapped = switches[chan].channel > 3 + && switches[chan].channel < RF_.params_.get_param_int(PARAM_RC_NUM_CHANNELS); + + switch (switches[chan].channel) + { + case 4: + switches[chan].direction = RF_.params_.get_param_int(PARAM_RC_SWITCH_5_DIRECTION); + break; + case 5: + switches[chan].direction = RF_.params_.get_param_int(PARAM_RC_SWITCH_6_DIRECTION); + break; + case 6: + switches[chan].direction = RF_.params_.get_param_int(PARAM_RC_SWITCH_7_DIRECTION); + break; + case 7: + switches[chan].direction = RF_.params_.get_param_int(PARAM_RC_SWITCH_8_DIRECTION); + break; + default: + switches[chan].direction = 1; + break; + } + + if (switches[chan].mapped) + RF_.mavlink_.log(Mavlink::LOG_INFO, "%s switch mapped to RC channel %d", channel_name, switches[chan].channel); + else + RF_.mavlink_.log(Mavlink::LOG_INFO, "%s switch not mapped", channel_name); + } +} + +bool RC::check_rc_lost() +{ + bool failsafe = false; + + // If the board reports that we have lost RC, tell the state manager + if (RF_.board_.pwm_lost()) + { + failsafe = true; + } + else + { + // go into failsafe if we get an invalid RC command for any channel + for (int8_t i = 0; i 2100) + { + failsafe = true; + } + } + } + + if (failsafe) + // set the RC Lost error flag + RF_.state_manager_.set_event(StateManager::EVENT_RC_LOST); + else + // Clear the RC Lost Error + RF_.state_manager_.set_event(StateManager::EVENT_RC_FOUND); + + return failsafe; +} + +void RC::look_for_arm_disarm_signal() +{ + uint32_t now_ms = RF_.board_.clock_millis(); + uint32_t dt = now_ms - prev_time_ms; + prev_time_ms = now_ms; + // check for arming switch + if (!switch_mapped(SWITCH_ARM)) + { + if (!RF_.state_manager_.state().armed) // we are DISARMED + { + // if left stick is down and to the right + if ((RF_.rc_.stick(STICK_F) < RF_.params_.get_param_float(PARAM_ARM_THRESHOLD)) + && (RF_.rc_.stick(STICK_Z) > (1.0f - RF_.params_.get_param_float(PARAM_ARM_THRESHOLD)))) + { + time_sticks_have_been_in_arming_position_ms += dt; + } + else + { + time_sticks_have_been_in_arming_position_ms = 0; + } + if (time_sticks_have_been_in_arming_position_ms > 1000) + { + RF_.state_manager_.set_event(StateManager::EVENT_REQUEST_ARM); + } + } + else // we are ARMED + { + // if left stick is down and to the left + if (RF_.rc_.stick(STICK_F) < RF_.params_.get_param_float(PARAM_ARM_THRESHOLD) + && RF_.rc_.stick(STICK_Z) < -(1.0f - RF_.params_.get_param_float(PARAM_ARM_THRESHOLD))) + { + time_sticks_have_been_in_arming_position_ms += dt; + } + else + { + time_sticks_have_been_in_arming_position_ms = 0; + } + if (time_sticks_have_been_in_arming_position_ms > 1000) + { + RF_.state_manager_.set_event(StateManager::EVENT_REQUEST_DISARM); + time_sticks_have_been_in_arming_position_ms = 0; + } + } + } + else // ARMING WITH SWITCH + { + if (RF_.rc_.switch_on(SWITCH_ARM)) + { + if (!RF_.state_manager_.state().armed) + RF_.state_manager_.set_event(StateManager::EVENT_REQUEST_ARM);; + } + else + { + RF_.state_manager_.set_event(StateManager::EVENT_REQUEST_DISARM); + } + } +} + + +bool RC::run() +{ + static uint32_t last_rc_receive_time = 0; + + uint32_t now = RF_.board_.clock_millis(); + + // if it has been more than 20ms then look for new RC values and parse them + if (now - last_rc_receive_time < 20) + { + return false; + } + last_rc_receive_time = now; + + + // Check for rc lost + if (check_rc_lost()) + return false; + + + // read and normalize stick values + for (uint8_t channel = 0; channel < (uint8_t)STICKS_COUNT; channel++) + { + uint16_t pwm = RF_.board_.pwm_read(sticks[channel].channel); + if (sticks[channel].one_sided) //generally only F is one_sided + { + stick_values[channel] = ((float)(pwm - 1000)) / 1000.0f; + } + else + { + stick_values[channel] = (float)(2*(pwm - 1500)) / (1000.0); + } + } + + // read and interpret switch values + for (uint8_t channel = 0; channel < (uint8_t)SWITCHES_COUNT; channel++) + { + if (switches[channel].mapped) + { + if (switches[channel].direction < 0) + { + switch_values[channel] = RF_.board_.pwm_read(switches[channel].channel) < 1200; + } + else + { + switch_values[channel] = RF_.board_.pwm_read(switches[channel].channel) >= 1800; + } + } + else + { + switch_values[channel] = false; + } + } + + // Look for arming and disarming signals + look_for_arm_disarm_signal(); + + // Signal to the mux that we need to compute a new combined command + new_command_ = true; + return true; +} + +bool RC::new_command() +{ + if (new_command_) + { + new_command_ = false; + return true; + } + else + return false;; +} + +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/rosflight.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/rosflight.cpp new file mode 100644 index 0000000..4c85030 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/rosflight.cpp @@ -0,0 +1,134 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include "rosflight.h" + +namespace rosflight_firmware +{ + +ROSflight::ROSflight(Board& board) : + board_(board), + sensors_(*this), + state_manager_(*this), + controller_(*this), + estimator_(*this), + params_(*this), + mixer_(*this), + rc_(*this), + mavlink_(*this), + command_manager_(*this) +{ +} + +// Initialization Routine +void ROSflight::init() +{ + // Initialize the board + board_.init_board(); + + // Initialize the arming finite state machine + state_manager_.init(); + + // Read EEPROM to get initial params + params_.init(); + + // Initialize Mixer + mixer_.init(); + + /***********************/ + /*** Hardware Setup ***/ + /***********************/ + + // Initialize PWM and RC + rc_.init(); + + // Initialize MAVlink Communication + mavlink_.init(); + + // Initialize Sensors + sensors_.init(); + + /***********************/ + /*** Software Setup ***/ + /***********************/ + + // Initialize Estimator + estimator_.init(); + + // Initialize Controller + controller_.init(); + + // Initialize the command muxer + command_manager_.init(); +} + + +// Main loop +void ROSflight::run() +{ + /*********************/ + /*** Control Loop ***/ + /*********************/ + uint64_t start = board_.clock_micros(); + if (sensors_.run()) + { + // If I have new IMU data, then perform control + estimator_.run(); + controller_.run(); + mixer_.mix_output(); + loop_time_us = board_.clock_micros() - start; + } + + /*********************/ + /*** Post-Process ***/ + /*********************/ +// // internal timers figure out what and when to send + mavlink_.stream(); + + // receive mavlink messages + mavlink_.receive(); + + // update the state machine, an internal timer runs this at a fixed rate + state_manager_.run(); + + // get RC, an internal timer runs this every 20 ms (50 Hz) + rc_.run(); + + // update commands (internal logic tells whether or not we should do anything or not) + command_manager_.run(); +} + +uint32_t ROSflight::get_loop_time_us() +{ + return loop_time_us; +} + +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/sensors.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/sensors.cpp new file mode 100644 index 0000000..6738db1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/sensors.cpp @@ -0,0 +1,591 @@ +/* + * Copyright (c) 2017, James Jackson, Daniel Koch, and Craig Bidstrup, + * BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +#include "sensors.h" +#include "rosflight.h" + +#include +#include + +namespace rosflight_firmware +{ + +const float Sensors::BARO_MAX_CHANGE_RATE = 200.0f; // approx 200 m/s +const float Sensors::BARO_SAMPLE_RATE = 50.0f; +const float Sensors::DIFF_MAX_CHANGE_RATE = 225.0f; // approx 15 m/s^2 +const float Sensors::DIFF_SAMPLE_RATE = 50.0f; +const float Sensors::SONAR_MAX_CHANGE_RATE = 100.0f; // 100 m/s +const float Sensors::SONAR_SAMPLE_RATE = 50.0f; + +const int Sensors::SENSOR_CAL_DELAY_CYCLES = 128; +const int Sensors::SENSOR_CAL_CYCLES = 127; + +const float Sensors::BARO_MAX_CALIBRATION_VARIANCE = 25.0; // standard dev about 0.2 m +const float Sensors::DIFF_PRESSURE_MAX_CALIBRATION_VARIANCE = 100.0; // standard dev about 3 m/s + +Sensors::Sensors(ROSflight& rosflight) : + rf_(rosflight) +{} + +void Sensors::init() +{ + new_imu_data_ = false; + + // clear the IMU read error + rf_.state_manager_.clear_error(StateManager::ERROR_IMU_NOT_RESPONDING); + rf_.board_.sensors_init(); + + // See if the IMU is uncalibrated, and throw an error if it is + if (rf_.params_.get_param_float(PARAM_ACC_X_BIAS) == 0.0 && rf_.params_.get_param_float(PARAM_ACC_Y_BIAS) == 0.0 && + rf_.params_.get_param_float(PARAM_ACC_Z_BIAS) == 0.0 && rf_.params_.get_param_float(PARAM_GYRO_X_BIAS) == 0.0 && + rf_.params_.get_param_float(PARAM_GYRO_Y_BIAS) == 0.0 && rf_.params_.get_param_float(PARAM_GYRO_Z_BIAS) == 0.0) + { + rf_.state_manager_.set_error(StateManager::ERROR_UNCALIBRATED_IMU); + } + next_sensor_to_update_ = BAROMETER; + + float alt = rf_.params_.get_param_float(PARAM_GROUND_LEVEL); + ground_pressure_ = 101325.0f*(float)pow((1-2.25694e-5 * alt), 5.2553); + + baro_outlier_filt_.init(BARO_MAX_CHANGE_RATE, BARO_SAMPLE_RATE, ground_pressure_); + diff_outlier_filt_.init(DIFF_MAX_CHANGE_RATE, DIFF_SAMPLE_RATE, 0.0f); + sonar_outlier_filt_.init(SONAR_MAX_CHANGE_RATE, SONAR_SAMPLE_RATE, 0.0f); +} + + +bool Sensors::run(void) +{ + // First, check for new IMU data + if (update_imu()) + { + return true; + } + else + { + if (!rf_.state_manager_.state().armed) + look_for_disabled_sensors(); + + // Update other sensors + update_other_sensors(); + return false; + } +} + + +void Sensors::update_other_sensors() +{ + uint32_t now = rf_.board_.clock_millis(); + switch (next_sensor_to_update_) + { + case LowPrioritySensors::BAROMETER: + if (data_.baro_present) + { + float raw_pressure; + float raw_temp; + rf_.board_.baro_read(&raw_pressure, &raw_temp); + data_.baro_valid = baro_outlier_filt_.update(raw_pressure, &data_.baro_pressure); + if (data_.baro_valid) + { + data_.baro_temperature = raw_temp; + correct_baro(); + } + } + break; + case LowPrioritySensors::DIFF_PRESSURE: + if (data_.diff_pressure_present) + { + float raw_pressure; + float raw_temp; + rf_.board_.diff_pressure_read(&raw_pressure, &raw_temp); + data_.diff_pressure_valid = diff_outlier_filt_.update(raw_pressure, &data_.diff_pressure); + if (data_.diff_pressure_valid) + { + data_.diff_pressure_temp = raw_temp; + correct_diff_pressure(); + } + } + break; + case LowPrioritySensors::SONAR: + if (data_.sonar_present) + { + data_.sonar_range_valid = sonar_outlier_filt_.update(rf_.board_.sonar_read(), &data_.sonar_range); + } + break; + case LowPrioritySensors::MAGNETOMETER: + if (data_.mag_present) + { + float mag[3]; + rf_.board_.mag_read(mag); + data_.mag.x = mag[0]; + data_.mag.y = mag[1]; + data_.mag.z = mag[2]; + correct_mag(); + } + break; + } + next_sensor_to_update_ = (LowPrioritySensors) ((next_sensor_to_update_ + 1) % NUM_LOW_PRIORITY_SENSORS); +} + + +void Sensors::look_for_disabled_sensors() +{ + // Look for disabled sensors while disarmed (poll every second) + // These sensors need power to respond, so they might not have been + // detected on startup, but will be detected whenever power is applied + // to the 5V rail. + uint32_t now = rf_.board_.clock_millis(); + if (now > (last_time_look_for_disarmed_sensors_ + 1000)) + { + last_time_look_for_disarmed_sensors_ = now; + if (!data_.sonar_present) + { + if (rf_.board_.sonar_check()) + { + data_.sonar_present = true; + rf_.mavlink_.log(Mavlink::LOG_INFO, "FOUND SONAR"); + } + } + if (!data_.diff_pressure_present) + { + if (rf_.board_.diff_pressure_check()) + { + data_.diff_pressure_present = true; + rf_.mavlink_.log(Mavlink::LOG_INFO, "FOUND DIFF PRESS"); + } + } + if (!data_.baro_present) + { + if (rf_.board_.baro_check()) + { + data_.baro_present = true; + rf_.mavlink_.log(Mavlink::LOG_INFO, "FOUND BAROMETER"); + } + } + if (!data_.mag_present) + { + if (rf_.board_.mag_check()) + { + data_.mag_present = true; + rf_.mavlink_.log(Mavlink::LOG_INFO, "FOUND MAGNETOMETER"); + } + } + } +} + +bool Sensors::start_imu_calibration(void) +{ + start_gyro_calibration(); + + calibrating_acc_flag_ = true; + rf_.params_.set_param_float(PARAM_ACC_X_BIAS, 0.0); + rf_.params_.set_param_float(PARAM_ACC_Y_BIAS, 0.0); + rf_.params_.set_param_float(PARAM_ACC_Z_BIAS, 0.0); + return true; +} + +bool Sensors::start_gyro_calibration(void) +{ + calibrating_gyro_flag_ = true; + rf_.params_.set_param_float(PARAM_GYRO_X_BIAS, 0.0); + rf_.params_.set_param_float(PARAM_GYRO_Y_BIAS, 0.0); + rf_.params_.set_param_float(PARAM_GYRO_Z_BIAS, 0.0); + return true; +} + +bool Sensors::start_baro_calibration() +{ + baro_calibration_mean_ = 0.0f; + baro_calibration_var_ = 0.0f; + baro_calibration_count_ = 0; + baro_calibrated_ = false; + rf_.params_.set_param_float(PARAM_BARO_BIAS, 0.0f); + return true; +} + +bool Sensors::start_diff_pressure_calibration() +{ + diff_pressure_calibration_mean_ = 0.0f; + diff_pressure_calibration_var_ = 0.0f; + diff_pressure_calibration_count_ = 0; + diff_pressure_calibrated_ = false; + rf_.params_.set_param_float(PARAM_DIFF_PRESS_BIAS, 0.0f); + return true; +} + +bool Sensors::gyro_calibration_complete(void) +{ + return !calibrating_gyro_flag_; +} + +//================================================================== +// local function definitions +bool Sensors::update_imu(void) +{ + if (rf_.board_.new_imu_data()) + { + rf_.state_manager_.clear_error(StateManager::ERROR_IMU_NOT_RESPONDING); + last_imu_update_ms_ = rf_.board_.clock_millis(); + if (!rf_.board_.imu_read(accel_, &data_.imu_temperature, gyro_, &data_.imu_time)) + { + return false; + } + + data_.accel.x = accel_[0]; + data_.accel.y = accel_[1]; + data_.accel.z = accel_[2]; + + data_.gyro.x = gyro_[0]; + data_.gyro.y = gyro_[1]; + data_.gyro.z = gyro_[2]; + + if (calibrating_acc_flag_) + calibrate_accel(); + if (calibrating_gyro_flag_) + calibrate_gyro(); + + correct_imu(); + return true; + } + else + { + // if we have lost 10 IMU messages then something is wrong + if (rf_.board_.clock_millis() > last_imu_update_ms_ + 10) + { + // Tell the board to fix it + last_imu_update_ms_ = rf_.board_.clock_millis(); + rf_.board_.imu_not_responding_error(); + + // Indicate an IMU error + rf_.state_manager_.set_error(StateManager::ERROR_IMU_NOT_RESPONDING); + } + return false; + } +} + +//====================================================================== +// Calibration Functions +void Sensors::calibrate_gyro() +{ + gyro_sum_ = vector_add(gyro_sum_, data_.gyro); + gyro_calibration_count_++; + + if (gyro_calibration_count_ > 1000) + { + // Gyros are simple. Just find the average during the calibration + vector_t gyro_bias = scalar_multiply(1.0/(float)gyro_calibration_count_, gyro_sum_); + + if (norm(gyro_bias) < 1.0) + { + rf_.params_.set_param_float(PARAM_GYRO_X_BIAS, gyro_bias.x); + rf_.params_.set_param_float(PARAM_GYRO_Y_BIAS, gyro_bias.y); + rf_.params_.set_param_float(PARAM_GYRO_Z_BIAS, gyro_bias.z); + + // Tell the estimator to reset it's bias estimate, because it should be zero now + rf_.estimator_.reset_adaptive_bias(); + + // Tell the state manager that we just completed a gyro calibration + rf_.state_manager_.set_event(StateManager::EVENT_CALIBRATION_COMPLETE); + } + else + { + // Tell the state manager that we just failed a gyro calibration + rf_.state_manager_.set_event(StateManager::EVENT_CALIBRATION_FAILED); + rf_.mavlink_.log(Mavlink::LOG_ERROR, "Too much movement for gyro cal"); + } + + // reset calibration in case we do it again + calibrating_gyro_flag_ = false; + gyro_calibration_count_ = 0; + gyro_sum_.x = 0.0f; + gyro_sum_.y = 0.0f; + gyro_sum_.z = 0.0f; + } +} + +vector_t vector_max(vector_t a, vector_t b) +{ + vector_t out = {a.x > b.x ? a.x : b.x, + a.y > b.y ? a.y : b.y, + a.z > b.z ? a.z : b.z + }; + return out; +} + +vector_t vector_min(vector_t a, vector_t b) +{ + vector_t out = {a.x < b.x ? a.x : b.x, + a.y < b.y ? a.y : b.y, + a.z < b.z ? a.z : b.z + }; + return out; +} + + +void Sensors::calibrate_accel(void) +{ + acc_sum_ = vector_add(vector_add(acc_sum_, data_.accel), gravity_); + acc_temp_sum_ += data_.imu_temperature; + max_ = vector_max(max_, data_.accel); + min_ = vector_min(min_, data_.accel); + accel_calibration_count_++; + + if (accel_calibration_count_ > 1000) + { + // The temperature bias is calculated using a least-squares regression. + // This is computationally intensive, so it is done by the onboard computer in + // fcu_io and shipped over to the flight controller. + vector_t accel_temp_bias = + { + rf_.params_.get_param_float(PARAM_ACC_X_TEMP_COMP), + rf_.params_.get_param_float(PARAM_ACC_Y_TEMP_COMP), + rf_.params_.get_param_float(PARAM_ACC_Z_TEMP_COMP) + }; + + // Figure out the proper accel bias. + // We have to consider the contribution of temperature during the calibration, + // Which is why this line is so confusing. What we are doing, is first removing + // the contribution of temperature to the measurements during the calibration, + // Then we are dividing by the number of measurements. + vector_t accel_bias = scalar_multiply(1.0/(float)accel_calibration_count_, vector_sub(acc_sum_, + scalar_multiply(acc_temp_sum_, accel_temp_bias))); + + // Sanity Check - + // If the accelerometer is upside down or being spun around during the calibration, + // then don't do anything + if (norm(vector_sub(max_, min_)) > 1.0) + { + rf_.mavlink_.log(Mavlink::LOG_ERROR, "Too much movement for IMU cal"); + calibrating_acc_flag_ = false; + } + else + { + // reset the estimated state + rf_.estimator_.reset_state(); + calibrating_acc_flag_ = false; + + if (norm(accel_bias) < 3.0) + { + rf_.params_.set_param_float(PARAM_ACC_X_BIAS, accel_bias.x); + rf_.params_.set_param_float(PARAM_ACC_Y_BIAS, accel_bias.y); + rf_.params_.set_param_float(PARAM_ACC_Z_BIAS, accel_bias.z); + rf_.mavlink_.log(Mavlink::LOG_INFO, "IMU offsets captured"); + + // clear uncalibrated IMU flag + rf_.state_manager_.clear_error(StateManager::ERROR_UNCALIBRATED_IMU); + } + else + { + // This usually means the user has the FCU in the wrong orientation, or something is wrong + // with the board IMU (like it's a cheap chinese clone) + rf_.mavlink_.log(Mavlink::LOG_ERROR, "large accel bias: norm = %d.%d", + (uint32_t)norm(accel_bias), (uint32_t)(norm(accel_bias)*1000)%1000); + } + } + + // reset calibration counters in case we do it again + accel_calibration_count_ = 0; + acc_sum_.x = 0.0f; + acc_sum_.y = 0.0f; + acc_sum_.z = 0.0f; + acc_temp_sum_ = 0.0f; + max_.x = -1000.0f; + max_.y = -1000.0f; + max_.z = -1000.0f; + min_.x = 1000.0f; + min_.y = 1000.0f; + min_.z = 1000.0f; + } +} + +void Sensors::calibrate_baro() +{ + if (rf_.board_.clock_millis() > last_baro_cal_iter_ms_ + 20) + { + baro_calibration_count_++; + + // calibrate pressure reading to where it should be + if (baro_calibration_count_ > SENSOR_CAL_DELAY_CYCLES + SENSOR_CAL_CYCLES) + { + // if sample variance within acceptable range, flag calibration as done + // else reset cal variables and start over + if (baro_calibration_var_ < BARO_MAX_CALIBRATION_VARIANCE) + { + rf_.params_.set_param_float(PARAM_BARO_BIAS, baro_calibration_mean_); + baro_calibrated_ = true; + rf_.mavlink_.log(Mavlink::LOG_INFO, "Baro Cal successful!"); + } + else + { + rf_.mavlink_.log(Mavlink::LOG_ERROR, "Too much movement for barometer cal"); + } + baro_calibration_mean_ = 0.0f; + baro_calibration_var_ = 0.0f; + baro_calibration_count_ = 0; + } + + else if (baro_calibration_count_ > SENSOR_CAL_DELAY_CYCLES) + { + float measurement = data_.baro_pressure - ground_pressure_; + float delta = measurement - baro_calibration_mean_; + baro_calibration_mean_ += delta / (baro_calibration_count_ - SENSOR_CAL_DELAY_CYCLES); + float delta2 = measurement - baro_calibration_mean_; + baro_calibration_var_ += delta * delta2 / (SENSOR_CAL_CYCLES - 1); + } + last_baro_cal_iter_ms_ = rf_.board_.clock_millis(); + } +} + +void Sensors::calibrate_diff_pressure() +{ + if (rf_.board_.clock_millis() > last_diff_pressure_cal_iter_ms_ + 20) + { + diff_pressure_calibration_count_++; + + if(diff_pressure_calibration_count_ > SENSOR_CAL_DELAY_CYCLES + SENSOR_CAL_CYCLES) + { + // if sample variance within acceptable range, flag calibration as done + // else reset cal variables and start over + if (diff_pressure_calibration_var_ < DIFF_PRESSURE_MAX_CALIBRATION_VARIANCE) + { + rf_.params_.set_param_float(PARAM_DIFF_PRESS_BIAS, diff_pressure_calibration_mean_); + diff_pressure_calibrated_ = true; + rf_.mavlink_.log(Mavlink::LOG_INFO, "Airspeed Cal Successful!"); + } + else + { + rf_.mavlink_.log(Mavlink::LOG_ERROR, "Too much movement for diff pressure cal"); + } + diff_pressure_calibration_mean_ = 0.0f; + diff_pressure_calibration_var_ = 0.0f; + diff_pressure_calibration_count_ = 0; + } + else if (diff_pressure_calibration_count_ > SENSOR_CAL_DELAY_CYCLES) + { + float delta = data_.diff_pressure - diff_pressure_calibration_mean_; + diff_pressure_calibration_mean_ += delta / (diff_pressure_calibration_count_ - SENSOR_CAL_DELAY_CYCLES); + float delta2 = data_.diff_pressure - diff_pressure_calibration_mean_; + diff_pressure_calibration_var_ += delta * delta2 / (SENSOR_CAL_CYCLES - 1); + } + last_diff_pressure_cal_iter_ms_ = rf_.board_.clock_millis(); + } +} + + +//====================================================== +// Correction Functions (These apply calibration constants) +void Sensors::correct_imu(void) +{ + // correct according to known biases and temperature compensation + data_.accel.x -= rf_.params_.get_param_float(PARAM_ACC_X_TEMP_COMP)*data_.imu_temperature + + rf_.params_.get_param_float(PARAM_ACC_X_BIAS); + data_.accel.y -= rf_.params_.get_param_float(PARAM_ACC_Y_TEMP_COMP)*data_.imu_temperature + + rf_.params_.get_param_float(PARAM_ACC_Y_BIAS); + data_.accel.z -= rf_.params_.get_param_float(PARAM_ACC_Z_TEMP_COMP)*data_.imu_temperature + + rf_.params_.get_param_float(PARAM_ACC_Z_BIAS); + + data_.gyro.x -= rf_.params_.get_param_float(PARAM_GYRO_X_BIAS); + data_.gyro.y -= rf_.params_.get_param_float(PARAM_GYRO_Y_BIAS); + data_.gyro.z -= rf_.params_.get_param_float(PARAM_GYRO_Z_BIAS); +} + +void Sensors::correct_mag(void) +{ + // correct according to known hard iron bias + float mag_hard_x = data_.mag.x - rf_.params_.get_param_float(PARAM_MAG_X_BIAS); + float mag_hard_y = data_.mag.y - rf_.params_.get_param_float(PARAM_MAG_Y_BIAS); + float mag_hard_z = data_.mag.z - rf_.params_.get_param_float(PARAM_MAG_Z_BIAS); + + // correct according to known soft iron bias - converts to nT + data_.mag.x = rf_.params_.get_param_float(PARAM_MAG_A11_COMP)*mag_hard_x + rf_.params_.get_param_float( + PARAM_MAG_A12_COMP)*mag_hard_y + + rf_.params_.get_param_float(PARAM_MAG_A13_COMP)*mag_hard_z; + data_.mag.y = rf_.params_.get_param_float(PARAM_MAG_A21_COMP)*mag_hard_x + rf_.params_.get_param_float( + PARAM_MAG_A22_COMP)*mag_hard_y + + rf_.params_.get_param_float(PARAM_MAG_A23_COMP)*mag_hard_z; + data_.mag.z = rf_.params_.get_param_float(PARAM_MAG_A31_COMP)*mag_hard_x + rf_.params_.get_param_float( + PARAM_MAG_A32_COMP)*mag_hard_y + + rf_.params_.get_param_float(PARAM_MAG_A33_COMP)*mag_hard_z; +} + +void Sensors::correct_baro(void) +{ + if (!baro_calibrated_) + calibrate_baro(); + data_.baro_pressure -= rf_.params_.get_param_float(PARAM_BARO_BIAS); + data_.baro_altitude = fast_alt(data_.baro_pressure) - rf_.params_.get_param_float(PARAM_GROUND_LEVEL); +} + +void Sensors::correct_diff_pressure() +{ + if (!diff_pressure_calibrated_) + calibrate_diff_pressure(); + data_.diff_pressure -= rf_.params_.get_param_float(PARAM_DIFF_PRESS_BIAS); + float atm = 101325.0f; + if (data_.baro_present) + atm = data_.baro_pressure; + data_.diff_pressure_velocity = fsign(data_.diff_pressure) * 24.574f/turboInvSqrt((fabs(data_.diff_pressure) * data_.diff_pressure_temp / atm)); +} + +void Sensors::OutlierFilter::init(float max_change_rate, float update_rate, float center) +{ + max_change_ = max_change_rate / update_rate; + window_size_ = 1; + center_ = center; + init_ = true; +} + +bool Sensors::OutlierFilter::update(float new_val, float *val) +{ + float diff = new_val - center_; + if (fabs(diff) < window_size_ * max_change_) + { + *val = new_val; + + center_ += fsign(diff) * fmin(max_change_, fabs(diff)); + if (window_size_ > 1) + { + window_size_--; + } + return true; + } + else + { + window_size_++; + return false; + } +} + +} // namespace rosflight_firmware diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/state_manager.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/state_manager.cpp new file mode 100644 index 0000000..07fb91d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/src/state_manager.cpp @@ -0,0 +1,257 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include "state_manager.h" +#include "rosflight.h" + +namespace rosflight_firmware +{ + +StateManager::StateManager(ROSflight& parent) : + RF_(parent), fsm_state_(FSM_STATE_INIT) +{ + state_.armed = false; + state_.error = false; + state_.failsafe = false; + state_.error_codes = 0x00; +} + +void StateManager::init() +{ + set_event(EVENT_INITIALIZED); + process_errors(); + + // Initialize LEDs + RF_.board_.led1_off(); +} + +void StateManager::run() +{ + // I'm putting this here for the case where we've switched states with existing errors, + // but those errors might not have been processed yet for the new state. We could replace + // this with a recursive call to process_errors() if the state changed in update_fsm()? + process_errors(); // check for any error events + update_leds(); +} + +void StateManager::set_error(uint16_t error) +{ + // Set the error code + state_.error_codes |= error; + + // Tell the FSM that we have had an error change + process_errors(); + RF_.mavlink_.update_status(); +} + +void StateManager::clear_error(uint16_t error) +{ + // If this error code was set, + if (state_.error_codes & error) + { + // Clear the error code + state_.error_codes &= ~(error); + + // If there are no errors, tell the FSM + process_errors(); + + // Send a status update (for logging) + RF_.mavlink_.update_status(); + } +} + +void StateManager::set_event(StateManager::Event event) +{ + switch (fsm_state_) + { + case FSM_STATE_INIT: + if (event == EVENT_INITIALIZED) + { + fsm_state_ = FSM_STATE_PREFLIGHT; + } + break; + + case FSM_STATE_PREFLIGHT: + switch (event) + { + case EVENT_RC_FOUND: + clear_error(ERROR_RC_LOST); + state_.failsafe = false; + break; + case EVENT_RC_LOST: + set_error(ERROR_RC_LOST); + break; + case EVENT_ERROR: + state_.error = true; + fsm_state_ = FSM_STATE_ERROR; + break; + case EVENT_REQUEST_ARM: + if (RF_.params_.get_param_int(PARAM_CALIBRATE_GYRO_ON_ARM)) + { + fsm_state_ = FSM_STATE_CALIBRATING; + RF_.sensors_.start_gyro_calibration(); + } + else + { + state_.armed = true; + RF_.mavlink_.update_status(); + fsm_state_ = FSM_STATE_ARMED; + } + break; + } + break; + + case FSM_STATE_ERROR: + switch (event) + { + case EVENT_RC_LOST: + set_error(ERROR_RC_LOST); // sometimes redundant, but reports RC lost error if another error got reported first + break; + case EVENT_RC_FOUND: + clear_error(ERROR_RC_LOST); + state_.failsafe = false; + break; + case EVENT_NO_ERROR: + state_.error = false; + fsm_state_ = FSM_STATE_PREFLIGHT; + break; + case EVENT_REQUEST_ARM: + RF_.mavlink_.log(Mavlink::LOG_ERROR, "unable to arm due to error code 0x%x", state_.error_codes); + break; + } + break; + + case FSM_STATE_CALIBRATING: + switch (event) + { + case EVENT_CALIBRATION_COMPLETE: + state_.armed = true; + fsm_state_ = FSM_STATE_ARMED; + break; + case EVENT_CALIBRATION_FAILED: + fsm_state_ = FSM_STATE_PREFLIGHT; + break; + case EVENT_RC_LOST: + set_error(ERROR_RC_LOST); + break; + case EVENT_ERROR: + fsm_state_ = FSM_STATE_ERROR; + state_.error = true; + break; + case EVENT_NO_ERROR: + state_.error = false; + break; + } + break; + + case FSM_STATE_ARMED: + switch (event) + { + case EVENT_RC_LOST: + state_.failsafe = true; + RF_.mavlink_.update_status(); + fsm_state_ = FSM_STATE_FAILSAFE; + set_error(ERROR_RC_LOST); + break; + case EVENT_REQUEST_DISARM: + state_.armed = false; + RF_.mavlink_.update_status(); + if (state_.error) + fsm_state_ = FSM_STATE_ERROR; + else + fsm_state_ = FSM_STATE_PREFLIGHT; + break; + case EVENT_ERROR: + state_.error = true; + break; + case EVENT_NO_ERROR: + state_.error = false; + break; + } + break; + + case FSM_STATE_FAILSAFE: + switch (event) + { + case EVENT_ERROR: + state_.error = true; + break; + case EVENT_REQUEST_DISARM: + state_.armed = false; + fsm_state_ = FSM_STATE_ERROR; + break; + case EVENT_RC_FOUND: + RF_.mavlink_.update_status(); + state_.failsafe = false; + fsm_state_ = FSM_STATE_ARMED; + clear_error(ERROR_RC_LOST); + break; + } + break; + } +} + +void StateManager::process_errors() +{ + if (state_.error_codes) + set_event(EVENT_ERROR); + else + set_event(EVENT_NO_ERROR); +} + +void StateManager::update_leds() +{ + // blink fast if in failsafe + if (state_.failsafe) + { + if (next_led_blink_ms_ < RF_.board_.clock_millis()) + { + RF_.board_.led1_toggle(); + next_led_blink_ms_ = RF_.board_.clock_millis() + 100; + } + } + // blink slowly if in error + else if (state_.error) + { + if (next_led_blink_ms_ < RF_.board_.clock_millis()) + { + RF_.board_.led1_toggle(); + next_led_blink_ms_ = RF_.board_.clock_millis() + 500; + } + } + // off if disarmed, on if armed + else if (!state_.armed) + RF_.board_.led1_off(); + else + RF_.board_.led1_on(); +} + +} //namespace rosflight_firmware diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/CMakeLists.txt new file mode 100644 index 0000000..a03c8fd --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/CMakeLists.txt @@ -0,0 +1,40 @@ +cmake_minimum_required(VERSION 2.6) + +add_definitions(-std=c++11) + +# Locate GTest +find_package(GTest REQUIRED) +include_directories(${GTEST_INCLUDE_DIRS}) + +include_directories(../include) +include_directories(../lib) +include_directories(${EIGEN3_INCLUDE_DIRS}) +include_directories(/usr/include/eigen3) + + +set(ROSFLIGHT_SRC + ../src/rosflight.cpp + ../src/param.cpp + ../src/sensors.cpp + ../src/state_manager.cpp + ../src/estimator.cpp + ../src/mavlink.cpp + ../src/nanoprintf.cpp + ../src/controller.cpp + ../src/command_manager.cpp + ../src/rc.cpp + ../src/mixer.cpp + ../lib/turbotrig/turbotrig.cpp + ../lib/turbotrig/turbovec.cpp + ) + +add_executable(unit_tests + ${ROSFLIGHT_SRC} + command_manager_test.cpp + test_board.cpp + turbotrig_test.cpp + state_machine_test.cpp + command_manager_test.cpp + estimator_test.cpp + ) +target_link_libraries(unit_tests ${GTEST_LIBRARIES} pthread) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/command_manager_test.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/command_manager_test.cpp new file mode 100644 index 0000000..ffa46a2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/command_manager_test.cpp @@ -0,0 +1,699 @@ +#include +#include "rosflight.h" +#include "test_board.h" +#include "cmath" + +#define EXPECT_INTHESAMEBALLPARK(x, y) EXPECT_LE(std::abs(x - y), 0.1) +#define EXPECT_PRETTYCLOSE(x, y) EXPECT_LE(std::abs(x - y), 0.01) +#define EXPECT_CLOSE(x, y) EXPECT_LE(std::abs(x - y), 0.001) +#define EXPECT_BASICALLYTHESAME(x, y) EXPECT_LE(std::abs(x - y), 0.00001) + +#define CHN_LOW 1100 +#define CHN_HIGH 1900 + + +using namespace rosflight_firmware; + +// Initialize the full firmware, so that the state_manager can do its thing +void step_firmware(ROSflight& rf, testBoard& board, uint32_t us) +{ + uint64_t start_time_us = board.clock_micros(); + float dummy_acc[3] = {0, 0, -9.80665}; + float dummy_gyro[3] = {0, 0, 0}; + while(board.clock_micros() < start_time_us + us) + { + board.set_imu(dummy_acc, dummy_gyro, board.clock_micros() + 1000); + rf.run(); + } +} + +TEST(command_manager_test, rc) { + testBoard board; + ROSflight rf(board); + + // Initialize the firmware + rf.init(); + + uint16_t rc_values[8]; + for (int i = 0; i < 8; i++) + { + rc_values[i] = 1500; + } + rc_values[2] = 1000; + + float max_roll = rf.params_.get_param_float(PARAM_RC_MAX_ROLL); + float max_pitch = rf.params_.get_param_float(PARAM_RC_MAX_PITCH); + float max_yawrate = rf.params_.get_param_float(PARAM_RC_MAX_YAWRATE); + + + //================================================= + // RC Commands Test + //================================================= + // First, lets just try sending rc_commands alone + board.set_rc(rc_values); + step_firmware(rf, board, 20000); + + control_t output = rf.command_manager_.combined_control(); + EXPECT_EQ(output.x.type, ANGLE); + EXPECT_PRETTYCLOSE(output.x.value, 0.0); + EXPECT_EQ(output.y.type, ANGLE); + EXPECT_PRETTYCLOSE(output.y.value, 0.0); + EXPECT_EQ(output.z.type, RATE); + EXPECT_PRETTYCLOSE(output.z.value, 0.0); + EXPECT_EQ(output.F.type, THROTTLE); + EXPECT_PRETTYCLOSE(output.F.value, 0.0); + + rc_values[0] = 2000; + rc_values[1] = 1000; + rc_values[2] = 1500; + rc_values[3] = 1250; + board.set_rc(rc_values); + step_firmware(rf, board, 20000); + + output = rf.command_manager_.combined_control(); + EXPECT_EQ(output.x.type, ANGLE); + EXPECT_PRETTYCLOSE(output.x.value, 1.0*max_roll); + EXPECT_EQ(output.y.type, ANGLE); + EXPECT_PRETTYCLOSE(output.y.value, -1.0*max_pitch); + EXPECT_EQ(output.z.type, RATE); + EXPECT_PRETTYCLOSE(output.z.value, -0.5*max_yawrate); + EXPECT_EQ(output.F.type, THROTTLE); + EXPECT_PRETTYCLOSE(output.F.value, 0.5); +} + + +TEST(command_manager_test, rc_arm_disarm) { + testBoard board; + ROSflight rf(board); + + // Make sure that rc is hooked up + board.set_pwm_lost(false); + + // Initialize the firmware + rf.init(); + + uint16_t rc_values[8]; + for (int i = 0; i < 8; i++) + { + rc_values[i] = 1500; + } + rc_values[2] = 1000; + + float max_roll = rf.params_.get_param_float(PARAM_RC_MAX_ROLL); + float max_pitch = rf.params_.get_param_float(PARAM_RC_MAX_PITCH); + float max_yawrate = rf.params_.get_param_float(PARAM_RC_MAX_YAWRATE); + + // Let's clear all errors in the state_manager + rf.state_manager_.clear_error(rf.state_manager_.state().error_codes); + + //================================================= + // RC Arming Test + //================================================= + + // Let's send an arming signal + rc_values[0] = 1500; + rc_values[1] = 1500; + rc_values[2] = 1000; + rc_values[3] = 2000; + board.set_rc(rc_values); + // Step halfway long enough to arm (shouldn't be armed yet) + step_firmware(rf, board, 500000); + EXPECT_EQ(rf.state_manager_.state().armed, false); + + + // Wait the rest of the time + step_firmware(rf, board, 600000); + // Check the output + control_t output = rf.command_manager_.combined_control(); + EXPECT_EQ(output.x.type, ANGLE); + EXPECT_PRETTYCLOSE(output.x.value, 0.0*max_roll); + EXPECT_EQ(output.y.type, ANGLE); + EXPECT_PRETTYCLOSE(output.y.value, 0.0*max_pitch); + EXPECT_EQ(output.z.type, RATE); + EXPECT_PRETTYCLOSE(output.z.value, 1.0*max_yawrate); + EXPECT_EQ(output.F.type, THROTTLE); + EXPECT_PRETTYCLOSE(output.F.value, 0.0); + + // See that we are armed + EXPECT_EQ(rf.state_manager_.state().armed, true); + + // Let's send a disarming signal + rc_values[0] = 1500; + rc_values[1] = 1500; + rc_values[2] = 1000; + rc_values[3] = 1000; + board.set_rc(rc_values); + // Step long enough for an arm to happen + step_firmware(rf, board, 1200000); + + // See that we are disarmed + EXPECT_EQ(rf.state_manager_.state().armed, false); + EXPECT_EQ(rf.state_manager_.state().error, false); + EXPECT_EQ(rf.state_manager_.state().failsafe, false); + + + //================================================= + // Switch Arming Test + //================================================= + rf.params_.set_param_int(PARAM_RC_ARM_CHANNEL, 4); + rc_values[0] = 1500; + rc_values[1] = 1500; + rc_values[2] = 1000; + rc_values[3] = 1500; + rc_values[4] = 1500; + + // Set all stick neutral position + board.set_rc(rc_values); + step_firmware(rf, board, 20000); + // make sure we are still disarmed + EXPECT_EQ(rf.state_manager_.state().armed, false); + EXPECT_EQ(rf.state_manager_.state().error, false); + EXPECT_EQ(rf.state_manager_.state().failsafe, false); + + // flip the arm switch on + rc_values[4] = CHN_HIGH; + board.set_rc(rc_values); + step_firmware(rf, board, 20000); + // we should be armed + EXPECT_EQ(rf.state_manager_.state().armed, true); + EXPECT_EQ(rf.state_manager_.state().error, false); + EXPECT_EQ(rf.state_manager_.state().failsafe, false); + + // flip the arm switch off + rc_values[4] = CHN_LOW; + board.set_rc(rc_values); + step_firmware(rf, board, 20000); + // we should be disarmed + EXPECT_EQ(rf.state_manager_.state().armed, false); + EXPECT_EQ(rf.state_manager_.state().error, false); + EXPECT_EQ(rf.state_manager_.state().failsafe, false); + + // Try reversing the arm channel + rf.params_.set_param_int(PARAM_RC_SWITCH_5_DIRECTION, -1); + rc_values[4] = CHN_LOW; + board.set_rc(rc_values); + step_firmware(rf, board, 20000); + // we should be armed + EXPECT_EQ(rf.state_manager_.state().armed, true); + EXPECT_EQ(rf.state_manager_.state().error, false); + EXPECT_EQ(rf.state_manager_.state().failsafe, false); + + // now it should be off + rc_values[4] = CHN_HIGH; + board.set_rc(rc_values); + step_firmware(rf, board, 20000); + // we should be disarmed + EXPECT_EQ(rf.state_manager_.state().armed, false); + EXPECT_EQ(rf.state_manager_.state().error, false); + EXPECT_EQ(rf.state_manager_.state().failsafe, false); + + + //================================================= + // Edge Cases + //================================================= + + // Try to arm with the sticks + // Let's send an arming signal (it shouldn't work) + rc_values[0] = 1500; + rc_values[1] = 1500; + rc_values[2] = 1000; + rc_values[3] = 2000; + board.set_rc(rc_values); + step_firmware(rf, board, 1100000); + // Check the output + output = rf.command_manager_.combined_control(); + EXPECT_EQ(rf.state_manager_.state().armed, false); + + // Go back to arming with sticks + rf.params_.set_param_int(PARAM_RC_ARM_CHANNEL, -1); + rf.params_.set_param_int(PARAM_RC_SWITCH_5_DIRECTION, -1); + + // try to arm with all the switches (first put all switches CHN_HIGH) + rc_values[0] = 1500; + rc_values[1] = 1500; + rc_values[2] = 1000; + rc_values[3] = 1500; + rc_values[4] = CHN_HIGH; + rc_values[5] = CHN_HIGH; + rc_values[6] = CHN_HIGH; + rc_values[7] = CHN_HIGH; + board.set_rc(rc_values); + step_firmware(rf, board, 20000); + // we should not be armed + EXPECT_EQ(rf.state_manager_.state().armed, false); + // now all switches CHN_LOW + rc_values[4] = CHN_LOW; + rc_values[5] = CHN_LOW; + rc_values[6] = CHN_LOW; + rc_values[7] = CHN_LOW; + board.set_rc(rc_values); + step_firmware(rf, board, 20000); + // we should not be armed + EXPECT_EQ(rf.state_manager_.state().armed, false); +} + + +TEST(command_manager_test, rc_failsafe_test) { + testBoard board; + ROSflight rf(board); + + // Make sure that rc is hooked up + board.set_pwm_lost(false); + + // Initialize the firmware + rf.init(); + + uint16_t rc_values[8]; + for (int i = 0; i < 8; i++) + { + rc_values[i] = 1500; + } + rc_values[2] = 1000; + + float max_roll = rf.params_.get_param_float(PARAM_RC_MAX_ROLL); + float max_pitch = rf.params_.get_param_float(PARAM_RC_MAX_PITCH); + float max_yawrate = rf.params_.get_param_float(PARAM_RC_MAX_YAWRATE); + float failsafe_throttle = rf.params_.get_param_float(PARAM_FAILSAFE_THROTTLE); + + // Let's clear all errors in the state_manager + rf.state_manager_.clear_error(rf.state_manager_.state().error_codes); + + //================================================= + // Disarmed Failsafe + //================================================= + + // Let's lose rc while disarmed + board.set_pwm_lost(true); + step_firmware(rf, board, 20000); + // Check the output - This should be the last rc value + control_t output = rf.command_manager_.combined_control(); + EXPECT_EQ(output.x.type, ANGLE); + EXPECT_PRETTYCLOSE(output.x.value, 0.0*max_roll); + EXPECT_EQ(output.y.type, ANGLE); + EXPECT_PRETTYCLOSE(output.y.value, 0.0*max_pitch); + EXPECT_EQ(output.z.type, RATE); + EXPECT_PRETTYCLOSE(output.z.value, 0.0*max_yawrate); + EXPECT_EQ(output.F.type, THROTTLE); + EXPECT_PRETTYCLOSE(output.F.value, 0.0); + + // We should also be disarmed and in error + EXPECT_EQ(rf.state_manager_.state().armed, false); + EXPECT_EQ(rf.state_manager_.state().failsafe, false); + EXPECT_EQ(rf.state_manager_.state().error, true); + EXPECT_EQ(rf.state_manager_.state().error_codes, StateManager::ERROR_RC_LOST); + + // Lets regain rc + board.set_pwm_lost(false); + board.set_rc(rc_values); + step_firmware(rf, board, 20000); + output = rf.command_manager_.combined_control(); + EXPECT_PRETTYCLOSE(output.x.value, 0.0*max_roll); + EXPECT_PRETTYCLOSE(output.y.value, 0.0*max_pitch); + EXPECT_PRETTYCLOSE(output.z.value, 0.0*max_yawrate); + EXPECT_PRETTYCLOSE(output.F.value, 0.0); + + // We should still be disarmed, but no failsafe or error + EXPECT_EQ(rf.state_manager_.state().armed, false); + EXPECT_EQ(rf.state_manager_.state().failsafe, false); + EXPECT_EQ(rf.state_manager_.state().error, false); + EXPECT_EQ(rf.state_manager_.state().error_codes, 0x00); + + //================================================= + // Armed Failsafe + //================================================= + + // Let's send an arming signal + rc_values[0] = 1500; + rc_values[1] = 1500; + rc_values[2] = 1000; + rc_values[3] = 2000; + board.set_rc(rc_values); + // Step long enough for an arm to happen + while (board.clock_millis() < 1200000) + { + step_firmware(rf, board, 20000); + } + + // check that we are armed + EXPECT_EQ(rf.state_manager_.state().armed, true); + EXPECT_EQ(rf.state_manager_.state().error, false); + EXPECT_EQ(rf.state_manager_.state().failsafe, false); + + // Set a command on the sticks + rc_values[0] = 1750; + rc_values[1] = 1250; + rc_values[2] = 1600; + rc_values[3] = CHN_LOW; + + // Lost RC + board.set_rc(rc_values); + board.set_pwm_lost(true); + step_firmware(rf, board, 20000); + // Check the output - This should be the failsafe control + output = rf.command_manager_.combined_control(); + EXPECT_EQ(output.x.type, ANGLE); + EXPECT_PRETTYCLOSE(output.x.value, 0.0*max_roll); + EXPECT_EQ(output.y.type, ANGLE); + EXPECT_PRETTYCLOSE(output.y.value, 0.0*max_pitch); + EXPECT_EQ(output.z.type, RATE); + EXPECT_PRETTYCLOSE(output.z.value, 0.0*max_yawrate); + EXPECT_EQ(output.F.type, THROTTLE); + EXPECT_PRETTYCLOSE(output.F.value, failsafe_throttle); + + // We should still be armed, but now in failsafe + EXPECT_EQ(rf.state_manager_.state().armed, true); + EXPECT_EQ(rf.state_manager_.state().error, true); + EXPECT_EQ(rf.state_manager_.state().failsafe, true); + + // Regain RC + board.set_pwm_lost(false); + step_firmware(rf, board, 20000); + // Check the output - This should be our rc control + output = rf.command_manager_.combined_control(); + EXPECT_EQ(output.x.type, ANGLE); + EXPECT_PRETTYCLOSE(output.x.value, 0.5*max_roll); + EXPECT_EQ(output.y.type, ANGLE); + EXPECT_PRETTYCLOSE(output.y.value, -0.5*max_pitch); + EXPECT_EQ(output.z.type, RATE); + EXPECT_PRETTYCLOSE(output.z.value, -0.8*max_yawrate); + EXPECT_EQ(output.F.type, THROTTLE); + EXPECT_PRETTYCLOSE(output.F.value, 0.6); +} + + + +#define OFFBOARD_X -1.0 +#define OFFBOARD_Y 0.5 +#define OFFBOARD_Z -0.7 +#define OFFBOARD_F 0.9 + +#define RC_X_PWM 1800 +#define RC_X ((RC_X_PWM - 1500)/500.0 * rf.params_.get_param_float(PARAM_RC_MAX_ROLL)) + +TEST(command_manager_test, rc_offboard_muxing_test ) { + + testBoard board; + ROSflight rf(board); + + // Make sure that rc is hooked up + board.set_pwm_lost(false); + + // Initialize the firmware + rf.init(); + + uint16_t rc_values[8]; + for (int i = 0; i < 8; i++) + { + rc_values[i] = 1500; + } + rc_values[2] = 1000; + + // Let's clear all errors in the state_manager + rf.state_manager_.clear_error(rf.state_manager_.state().error_codes); + + //================================================= + // Offboard Command Integration + //================================================= + + control_t offboard_command = + { + 20000, + {true, ANGLE, OFFBOARD_X}, + {true, ANGLE, OFFBOARD_Y}, + {true, RATE, OFFBOARD_Z}, + {true, THROTTLE, OFFBOARD_F} + }; + + // First, just set an offboard command and rc, mux it and see what happens + board.set_rc(rc_values); + // step a bunch of times to clear the "lag time" on RC + while (board.clock_micros() < 1000000) + { + step_firmware(rf, board, 20000); + } + + offboard_command.stamp_ms = board.clock_millis(); + rf.command_manager_.set_new_offboard_command(offboard_command); + step_firmware(rf, board, 20000); + + // We don't have an override channel mapped, so this should be offboard + control_t output = rf.command_manager_.combined_control(); + EXPECT_PRETTYCLOSE(output.x.value, OFFBOARD_X); + EXPECT_PRETTYCLOSE(output.y.value, OFFBOARD_Y); + EXPECT_PRETTYCLOSE(output.z.value, OFFBOARD_Z); + EXPECT_PRETTYCLOSE(output.F.value, OFFBOARD_F); + + rf.params_.set_param_int(PARAM_RC_ATTITUDE_OVERRIDE_CHANNEL, 4); + rf.params_.set_param_int(PARAM_RC_THROTTLE_OVERRIDE_CHANNEL, 4); + rf.params_.set_param_int(PARAM_RC_SWITCH_5_DIRECTION, 1); + + // ensure that the override switch is off + rc_values[4] = CHN_LOW; + + board.set_rc(rc_values); + offboard_command.stamp_ms = board.clock_millis(); + rf.command_manager_.set_new_offboard_command(offboard_command); + step_firmware(rf, board, 20000); + + // This should be offboard + output = rf.command_manager_.combined_control(); + EXPECT_PRETTYCLOSE(output.x.value, OFFBOARD_X); + EXPECT_PRETTYCLOSE(output.y.value, OFFBOARD_Y); + EXPECT_PRETTYCLOSE(output.z.value, OFFBOARD_Z); + EXPECT_PRETTYCLOSE(output.F.value, OFFBOARD_F); + + // flip override switch on + rc_values[4] = CHN_HIGH; + board.set_rc(rc_values); + offboard_command.stamp_ms = board.clock_millis(); + rf.command_manager_.set_new_offboard_command(offboard_command); + step_firmware(rf, board, 20000); + + // This should be RC + output = rf.command_manager_.combined_control(); + EXPECT_PRETTYCLOSE(output.x.value, 0.0); + EXPECT_PRETTYCLOSE(output.y.value, 0.0); + EXPECT_PRETTYCLOSE(output.z.value, 0.0); + EXPECT_PRETTYCLOSE(output.F.value, 0.0); + + + //================================================= + // Partial Offboard Command Integration + //================================================= + + // Only override attitude + rf.params_.set_param_int(PARAM_RC_ATTITUDE_OVERRIDE_CHANNEL, 4); + rf.params_.set_param_int(PARAM_RC_THROTTLE_OVERRIDE_CHANNEL, -1); + + board.set_rc(rc_values); + offboard_command.stamp_ms = board.clock_millis(); + rf.command_manager_.set_new_offboard_command(offboard_command); + step_firmware(rf, board, 20000); + + // Throttle should be offboard + output = rf.command_manager_.combined_control(); + EXPECT_PRETTYCLOSE(output.x.value, 0.0); + EXPECT_PRETTYCLOSE(output.y.value, 0.0); + EXPECT_PRETTYCLOSE(output.z.value, 0.0); + EXPECT_PRETTYCLOSE(output.F.value, OFFBOARD_F); + + + // Only override throttle + rf.params_.set_param_int(PARAM_RC_ATTITUDE_OVERRIDE_CHANNEL, -1); + rf.params_.set_param_int(PARAM_RC_THROTTLE_OVERRIDE_CHANNEL, 4); + + board.set_rc(rc_values); + offboard_command.stamp_ms = board.clock_millis(); + rf.command_manager_.set_new_offboard_command(offboard_command); + step_firmware(rf, board, 20000); + + // Throttle should be rc + output = rf.command_manager_.combined_control(); + EXPECT_PRETTYCLOSE(output.x.value, OFFBOARD_X); + EXPECT_PRETTYCLOSE(output.y.value, OFFBOARD_Y); + EXPECT_PRETTYCLOSE(output.z.value, OFFBOARD_Z); + EXPECT_PRETTYCLOSE(output.F.value, 0.0); + + + //================================================= + // RC Intervention + //================================================= + + // Only override attitude + rf.params_.set_param_int(PARAM_RC_ATTITUDE_OVERRIDE_CHANNEL, 4); + rf.params_.set_param_int(PARAM_RC_THROTTLE_OVERRIDE_CHANNEL, 4); + + // switch is off, but roll channel is deviated + rc_values[4] = CHN_LOW; + rc_values[0] = RC_X_PWM; + rc_values[2] = 1000; // move throttle to neutral position + + board.set_rc(rc_values); + offboard_command.stamp_ms = board.clock_millis(); + rf.command_manager_.set_new_offboard_command(offboard_command); + step_firmware(rf, board, 20000); + + output = rf.command_manager_.combined_control(); + EXPECT_PRETTYCLOSE(output.x.value, RC_X); // This channel should be overwritten + EXPECT_PRETTYCLOSE(output.y.value, OFFBOARD_Y); + EXPECT_PRETTYCLOSE(output.z.value, OFFBOARD_Z); + EXPECT_PRETTYCLOSE(output.F.value, OFFBOARD_F); + + //================================================= + // RC Override Lag Test + //================================================= + + // Switch is still off, and rc no longer deviated. There should still be lag though + rc_values[0] = 1500; + rc_values[2] = 1000; + board.set_rc(rc_values); + uint64_t start_ms = board.clock_millis(); + step_firmware(rf, board, 20000); + while (board.clock_millis() < rf.params_.get_param_int(PARAM_OVERRIDE_LAG_TIME) + start_ms) + { + output = rf.command_manager_.combined_control(); + EXPECT_PRETTYCLOSE(output.x.value, 0.0); // This channel should be overwritten + EXPECT_PRETTYCLOSE(output.y.value, OFFBOARD_Y); + EXPECT_PRETTYCLOSE(output.z.value, OFFBOARD_Z); + EXPECT_PRETTYCLOSE(output.F.value, OFFBOARD_F); + offboard_command.stamp_ms = board.clock_millis(); + rf.command_manager_.set_new_offboard_command(offboard_command); + step_firmware(rf, board, 20000); + } + offboard_command.stamp_ms = board.clock_millis(); + rf.command_manager_.set_new_offboard_command(offboard_command); + step_firmware(rf, board, 20000); + output = rf.command_manager_.combined_control(); + EXPECT_PRETTYCLOSE(output.x.value, -1.0); // This channel should no longer be overwritten + + + //================================================= + // Offboard Command Stale + //================================================= + + start_ms = board.clock_millis(); + while (board.clock_millis() < 100 + start_ms) + { + output = rf.command_manager_.combined_control(); + EXPECT_PRETTYCLOSE(output.x.value, OFFBOARD_X); // Offboard Command is still valid + EXPECT_PRETTYCLOSE(output.y.value, OFFBOARD_Y); + EXPECT_PRETTYCLOSE(output.z.value, OFFBOARD_Z); + EXPECT_PRETTYCLOSE(output.F.value, OFFBOARD_F); + step_firmware(rf, board, 20000); + } + + // Offboard command has timed out -> revert to RC + output = rf.command_manager_.combined_control(); + EXPECT_PRETTYCLOSE(output.x.value, 0.0); + EXPECT_PRETTYCLOSE(output.y.value, 0.0); + EXPECT_PRETTYCLOSE(output.z.value, 0.0); + EXPECT_PRETTYCLOSE(output.F.value, 0.0); +} + + +TEST(command_manager_test, partial_muxing_test ) { + + testBoard board; + ROSflight rf(board); + + // Make sure that rc is hooked up + board.set_pwm_lost(false); + + // Initialize the firmware + rf.init(); + + uint16_t rc_values[8]; + for (int i = 0; i < 8; i++) + { + rc_values[i] = 1500; + } + rc_values[2] = 1000; + + float max_roll = rf.params_.get_param_float(PARAM_RC_MAX_ROLL); + + // Let's clear all errors in the state_manager + rf.state_manager_.clear_error(rf.state_manager_.state().error_codes); + + //================================================= + // Min Throttle Test + //================================================= + + rf.params_.set_param_int(PARAM_RC_OVERRIDE_TAKE_MIN_THROTTLE, true); + + control_t offboard_command = + { + 20000, + {true, ANGLE, OFFBOARD_X}, + {true, ANGLE, OFFBOARD_Y}, + {true, RATE, OFFBOARD_Z}, + {true, THROTTLE, OFFBOARD_F} + }; + + // step a bunch of times to clear the "lag time" on RC + while (board.clock_micros() < 1000000) + { + step_firmware(rf, board, 20000); + } + + rc_values[2] = 1200; + + // RC is the min throttle + board.set_rc(rc_values); + offboard_command.stamp_ms = board.clock_millis(); + rf.command_manager_.set_new_offboard_command(offboard_command); + step_firmware(rf, board, 20000); + control_t output = rf.command_manager_.combined_control(); + EXPECT_PRETTYCLOSE(output.F.value, 0.2); + + // Now, offboard is the min throttle + offboard_command.F.value = 0.2; + rc_values[2] = 1500; + + board.set_rc(rc_values); + offboard_command.stamp_ms = board.clock_millis(); + rf.command_manager_.set_new_offboard_command(offboard_command); + step_firmware(rf, board, 20000); + output = rf.command_manager_.combined_control(); + EXPECT_PRETTYCLOSE(output.F.value, 0.2); + + // Okay, remove the Min throttle setting + rf.params_.set_param_int(PARAM_RC_OVERRIDE_TAKE_MIN_THROTTLE, false); + + rc_values[2] = 1200; + offboard_command.F.value = OFFBOARD_F; + + // RC is the min throttle + board.set_rc(rc_values); + offboard_command.stamp_ms = board.clock_millis(); + rf.command_manager_.set_new_offboard_command(offboard_command); + step_firmware(rf, board, 20000); + output = rf.command_manager_.combined_control(); + // We should get offboard command, even though RC is lower + EXPECT_PRETTYCLOSE(output.F.value, OFFBOARD_F); + + + // Now, let's disable the pitch channel on the onboard command + offboard_command.y.active = false; + offboard_command.stamp_ms = board.clock_millis(); + rf.command_manager_.set_new_offboard_command(offboard_command); + + step_firmware(rf, board, 20000); + output = rf.command_manager_.combined_control(); + EXPECT_PRETTYCLOSE(output.x.value, OFFBOARD_X); + EXPECT_PRETTYCLOSE(output.y.value, 0.0); + EXPECT_PRETTYCLOSE(output.z.value, OFFBOARD_Z); + EXPECT_PRETTYCLOSE(output.F.value, OFFBOARD_F); + + // Let's change the type on the x channel + offboard_command.x.type = RATE; + offboard_command.stamp_ms = board.clock_millis(); + rf.command_manager_.set_new_offboard_command(offboard_command); + + step_firmware(rf, board, 20000); + output = rf.command_manager_.combined_control(); + EXPECT_EQ(output.x.type, RATE); + EXPECT_EQ(output.y.type, ANGLE); + EXPECT_EQ(output.z.type, RATE); + EXPECT_EQ(output.F.type, THROTTLE); +} + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/estimator_test.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/estimator_test.cpp new file mode 100644 index 0000000..c38fd8c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/estimator_test.cpp @@ -0,0 +1,418 @@ +#include +#include "math.h" +#include "rosflight.h" +#include "test_board.h" +#include +#include "eigen3/Eigen/Core" +#include "eigen3/Eigen/Geometry" +#include "eigen3/unsupported/Eigen/MatrixFunctions" +#include +#include + +//#define DEBUG + + +#define EXPECT_CLOSE(x, y) EXPECT_LE(std::abs(x - y), 0.01); +#define EXPECT_FABSCLOSE(x, y) EXPECT_LE(fabs(x) - fabs(y), 0.01) + +double quaternion_error(Eigen::Quaterniond q_eig, quaternion_t q) +{ + Eigen::Quaterniond est_quat(q.w, q.x, q.y, q.z); + Eigen::Quaterniond q_tilde = q_eig * est_quat.inverse(); + Eigen::Vector3d v_tilde = atan2(q_tilde.vec().norm(), q_tilde.w())*q_tilde.vec()/q_tilde.vec().norm(); + return v_tilde.norm(); +} + +using namespace rosflight_firmware; + +double sign(double y) +{ + return (y > 0.0) - (y < 0.0); +} + +double run_estimator_test(std::string filename, ROSflight& rf, testBoard& board, std::vector params) +{ + double x_freq = params[0]; + double y_freq = params[1]; + double z_freq = params[2]; + double x_amp = params[3]; + double y_amp = params[4]; + double z_amp = params[5]; + double tmax = params[6]; + double error_limit = params[7]; + + double dt = 0.001; + + Eigen::Vector3d gravity; + gravity << 0.0, 0.0, -9.80665; + Eigen::Matrix3d rotation = Eigen::Matrix3d::Identity(); + +#ifdef DEBUG + // File for saving simulation results + std::ofstream file; + file.open(filename.c_str()); +#endif + + double max_error = 0.0; + double t = 0.0; + while(t < tmax) + { + // euler integration of S03 (probably a better way that isn't so intensive) + double ddt = 0.00005; + Eigen::Matrix3d omega_skew; + double step = t + dt; + while (t < step) + { + double p = x_amp*sin(x_freq/(2.0*M_PI)*t); + double q = y_amp*sin(y_freq/(2.0*M_PI)*t); + double r = z_amp*sin(z_freq/(2.0*M_PI)*t); + + omega_skew << 0.0, -r, q, + r, 0.0, -p, + -q, p, 0.0; + rotation = rotation*(omega_skew*ddt).exp(); + t += ddt; + } + + // Extract Accel Orientation + Eigen::Vector3d y_acc = rotation.transpose() * gravity; + + // Create gyro measurement + double p = x_amp*sin(x_freq/(2.0*M_PI)*t); + double q = y_amp*sin(y_freq/(2.0*M_PI)*t); + double r = z_amp*sin(z_freq/(2.0*M_PI)*t); + + float acc[3] = {(float)y_acc(0), (float)y_acc(1), (float)y_acc(2)}; + float gyro[3] = {(float)p, (float)q, (float)r}; + + // Simulate measurements + board.set_imu(acc, gyro, (uint64_t)(t*1e6)); + + // Run firmware + rf.run(); + + Eigen::Quaterniond eig_quat(rotation); + quaternion_t estimate = rf.estimator_.state().attitude; + + double pos_error = quaternion_error(eig_quat, estimate); + eig_quat.coeffs() *= -1.0; + double neg_error = quaternion_error(eig_quat, estimate); + double error = (pos_error < neg_error) ? pos_error : neg_error; + + if (pos_error < neg_error) + { + eig_quat.coeffs() *= -1.0; + } + + // output to file for plotting +#ifdef DEBUG + file << t << ", " << (error > error_limit) << ", "; + file << estimate.w << ", " << estimate.x << ", " << estimate.y << ", " << estimate.z << ", "; + file << eig_quat.w() << ", " << eig_quat.x() << ", " << eig_quat.y() << ", " << eig_quat.z() << ", "; + file << rf.estimator_.state().roll << ", " << rf.estimator_.state().pitch << ", " < max_error) + max_error = error; + } + } + return max_error; +} + + +TEST(estimator_test, linear_gyro_integration) { + testBoard board; + ROSflight rf(board); + + std::vector params = { + 10.0, // xfreq + 0.1, // yfreq + 0.5, // zfreq + 1.5, // xamp + 0.4, // yamp + 1.0, // zamp + 30.0, // tmax + 0.000505487 // error_limit + }; + + // Initialize the firmware + rf.init(); + + rf.params_.set_param_int(PARAM_FILTER_USE_ACC, false); + rf.params_.set_param_int(PARAM_FILTER_USE_QUAD_INT, false); + rf.params_.set_param_int(PARAM_FILTER_USE_MAT_EXP, false); + rf.params_.set_param_int(PARAM_ACC_ALPHA, 0); + rf.params_.set_param_int(PARAM_GYRO_ALPHA, 0); + + double max_error = run_estimator_test("linear_gyro_sim.csv", rf, board, params); + + EXPECT_LE(max_error, params[7]); + +#ifdef DEBUG + printf("max_error = %.7f\n", max_error); +#endif +} + + +TEST(estimator_test, quadratic_gyro_integration) { + testBoard board; + ROSflight rf(board); + + std::vector params = { + 10.0, // xfreq + 0.1, // yfreq + 0.5, // zfreq + 1.5, // xamp + 0.4, // yamp + 1.0, // zamp + 30.0, // tmax + 0.0000389 // error_limit + }; + + + // Initialize the firmware + rf.init(); + + rf.params_.set_param_int(PARAM_FILTER_USE_ACC, false); + rf.params_.set_param_int(PARAM_FILTER_USE_QUAD_INT, true); + rf.params_.set_param_int(PARAM_FILTER_USE_MAT_EXP, false); + rf.params_.set_param_int(PARAM_ACC_ALPHA, 0); + rf.params_.set_param_int(PARAM_GYRO_ALPHA, 0); + + double max_error = run_estimator_test("quad_int_sim.csv", rf, board, params); + + EXPECT_LE(max_error, params[7]); + +#ifdef DEBUG + printf("max_error = %.7f\n", max_error); +#endif +} + +TEST(estimator_test, mat_exp_integration) { + testBoard board; + ROSflight rf(board); + + std::vector params = { + 10.0, // xfreq + 0.1, // yfreq + 0.5, // zfreq + 1.5, // xamp + 0.4, // yamp + 1.0, // zamp + 30.0, // tmax + 0.0005028 // error_limit + }; + + // Initialize the firmware + rf.init(); + + rf.params_.set_param_int(PARAM_FILTER_USE_ACC, false); + rf.params_.set_param_int(PARAM_FILTER_USE_QUAD_INT, false); + rf.params_.set_param_int(PARAM_FILTER_USE_MAT_EXP, true); + rf.params_.set_param_int(PARAM_ACC_ALPHA, 0); + rf.params_.set_param_int(PARAM_GYRO_ALPHA, 0); + + double max_error = run_estimator_test("mat_exp_sim.csv", rf, board, params); + EXPECT_LE(max_error, params[7]); +#ifdef DEBUG + printf("max_error = %.7f\n", max_error); +#endif +} + +TEST(estimator_test, mat_exp_quad_int) { + testBoard board; + ROSflight rf(board); + + std::vector params = { + 10.0, // xfreq + 0.1, // yfreq + 0.5, // zfreq + 1.5, // xamp + 0.4, // yamp + 1.0, // zamp + 30.0, // tmax + 0.0280459 // error_limit + }; + + // Initialize the firmware + rf.init(); + + rf.params_.set_param_int(PARAM_FILTER_USE_ACC, false); + rf.params_.set_param_int(PARAM_FILTER_USE_QUAD_INT, true); + rf.params_.set_param_int(PARAM_FILTER_USE_MAT_EXP, true); + rf.params_.set_param_int(PARAM_ACC_ALPHA, 0); + rf.params_.set_param_int(PARAM_GYRO_ALPHA, 0); + + double max_error = run_estimator_test("mat_exp_quad_sim.csv", rf, board, params); + EXPECT_LE(max_error, params[7]); + +#ifdef DEBUG + printf("max_error = %.7f\n", max_error); +#endif +} + + +TEST(estimator_test, accel) { + testBoard board; + ROSflight rf(board); + + std::vector params = { + 10.0, // xfreq + 0.1, // yfreq + 0.5, // zfreq + 1.5, // xamp + 0.4, // yamp + 1.0, // zamp + 30.0, // tmax + 0.0280459 // error_limit + }; + + + // Initialize the firmware + rf.init(); + + rf.params_.set_param_int(PARAM_FILTER_USE_ACC, true); + rf.params_.set_param_int(PARAM_FILTER_USE_QUAD_INT, false); + rf.params_.set_param_int(PARAM_FILTER_USE_MAT_EXP, false); + rf.params_.set_param_int(PARAM_ACC_ALPHA, 0); + rf.params_.set_param_int(PARAM_GYRO_ALPHA, 0); + rf.params_.set_param_int(PARAM_FILTER_KP, 3.0f); + rf.params_.set_param_int(PARAM_INIT_TIME, 0.0f); + + double max_error = run_estimator_test("accel_sim.csv", rf, board, params); + EXPECT_LE(max_error, params[7]); +#ifdef DEBUG + printf("max_error = %.7f\n", max_error); +#endif +} + +TEST(estimator_test, all_features) { + testBoard board; + ROSflight rf(board); + + std::vector params = { + 10.0, // xfreq + 0.1, // yfreq + 0.5, // zfreq + 1.5, // xamp + 0.4, // yamp + 1.0, // zamp + 30.0, // tmax + 0.0632316 // error_limit + }; + + // Initialize the firmware + rf.init(); + + rf.params_.set_param_int(PARAM_FILTER_USE_ACC, true); + rf.params_.set_param_int(PARAM_FILTER_USE_QUAD_INT, true); + rf.params_.set_param_int(PARAM_FILTER_USE_MAT_EXP, true); + rf.params_.set_param_float(PARAM_FILTER_KP, 2.0f); + rf.params_.set_param_float(PARAM_ACC_ALPHA, 0.0f); + rf.params_.set_param_float(PARAM_GYRO_ALPHA, 0.0f); + rf.params_.set_param_float(PARAM_GYRO_X_BIAS, 0.0); + rf.params_.set_param_float(PARAM_GYRO_Y_BIAS, 0.0); + rf.params_.set_param_float(PARAM_GYRO_Z_BIAS, 0.0); // We don't converge on z bias + + double max_error = run_estimator_test("full_estimator_sim.csv", rf, board, params); + EXPECT_LE(max_error, params[7]); + +#ifdef DEBUG + printf("max_error = %.7f\n", max_error); +#endif +} + +TEST(estimator_test, level_bias_sim) { + testBoard board; + ROSflight rf(board); + + + std::vector params = { + 0.0, // xfreq + 0.0, // yfreq + 0.0, // zfreq + 0.0, // xamp + 0.0, // yamp + 0.0, // zamp + 60.0, // tmax + 0.0280459 // error_limit + }; + + // Initialize the firmware + rf.init(); + + vector_t true_bias = {0.25, -0.15, 0.0}; + + rf.params_.set_param_int(PARAM_FILTER_USE_ACC, true); + rf.params_.set_param_int(PARAM_FILTER_USE_QUAD_INT, true); + rf.params_.set_param_int(PARAM_FILTER_USE_MAT_EXP, true); + rf.params_.set_param_float(PARAM_FILTER_KP, 2.0f); + rf.params_.set_param_float(PARAM_FILTER_KI, 0.2f); + rf.params_.set_param_float(PARAM_ACC_ALPHA, 0.0f); + rf.params_.set_param_float(PARAM_GYRO_ALPHA, 0.0f); + rf.params_.set_param_float(PARAM_GYRO_X_BIAS, true_bias.x); + rf.params_.set_param_float(PARAM_GYRO_Y_BIAS, true_bias.y); + rf.params_.set_param_float(PARAM_GYRO_Z_BIAS, 0.0); // We don't converge on z bias + + run_estimator_test("level_bias_sim.csv", rf, board, params); + + // Check bias at the end + vector_t bias = vector_sub(rf.estimator_.state().angular_velocity, rf.sensors_.data().gyro); + vector_t error_vec = vector_sub(bias, true_bias); + float error_mag = norm(error_vec); + EXPECT_LE(error_mag, 0.001); + +#ifdef DEBUG + printf("estimated_bias = %.7f, %.7f\n", bias.x, bias.y); +#endif +} + +TEST(estimator_test, moving_bias_sim) { + testBoard board; + ROSflight rf(board); + + + std::vector params = { + 5.0, // xfreq + 0.5, // yfreq + 0.0, // zfreq + 0.02, // xamp + 0.01, // yamp + 0.0, // zamp + 60.0, // tmax + 0.0280459 // error_limit + }; + + // Initialize the firmware + rf.init(); + + vector_t true_bias = {0.01, -0.005, 0.0}; + + rf.params_.set_param_int(PARAM_FILTER_USE_ACC, true); + rf.params_.set_param_int(PARAM_FILTER_USE_QUAD_INT, true); + rf.params_.set_param_int(PARAM_FILTER_USE_MAT_EXP, true); + rf.params_.set_param_float(PARAM_FILTER_KP, 2.0f); + rf.params_.set_param_float(PARAM_FILTER_KI, 0.2f); + rf.params_.set_param_float(PARAM_ACC_ALPHA, 0.0f); + rf.params_.set_param_float(PARAM_GYRO_ALPHA, 0.0f); + rf.params_.set_param_float(PARAM_GYRO_X_BIAS, true_bias.x); + rf.params_.set_param_float(PARAM_GYRO_Y_BIAS, true_bias.y); + rf.params_.set_param_float(PARAM_GYRO_Z_BIAS, 0.0); // We don't converge on z bias + + run_estimator_test("moving_bias_sim.csv", rf, board, params); + + // Check bias at the end + vector_t bias = vector_sub(rf.estimator_.state().angular_velocity, rf.sensors_.data().gyro); + vector_t error_vec = vector_sub(bias, true_bias); + float error_mag = norm(error_vec); + EXPECT_LE(error_mag, 0.01); + +#ifdef DEBUG + printf("estimated_bias = %.7f, %.7f\n", bias.x, bias.y); +#endif +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/gtest_setup.md b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/gtest_setup.md new file mode 100644 index 0000000..03733a3 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/gtest_setup.md @@ -0,0 +1,37 @@ +# Setting up gtest for running unit tests + +## Install gtest +``` bash +sudo apt-get install libgtest-dev +``` + +## Compile gtest +You just downloaded a bunch of source files, which you now have to go build + +``` bash +sudo apt install cmake +cd /usr/src/gtest +sudo cmake CMakeLists.txt +sudo make +``` + +Copy the archive files you just build to the `/usr/lib` directory so CMake can find them later + +``` +sudo cp *.a /usr/lib +``` + +## Build the Unit Tests + +``` bash +cd /test +mkdir build +cd build +cmake .. +make +``` + +## Run the Unit Tests +``` bash +./turbotrig_test +./state_machine_test diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/sample.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/sample.cpp new file mode 100644 index 0000000..25326ae --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/sample.cpp @@ -0,0 +1,29 @@ +// tests.cpp +#include +#include + +double squareRoot(const double a) { + double b = sqrt(a); + if(b != b) { // nan check + return -1.0; + }else{ + return sqrt(a); + } +} + +TEST(SquareRootTest, PositiveNos) { + ASSERT_EQ(6, squareRoot(36.0)); + ASSERT_EQ(18.0, squareRoot(324.0)); + ASSERT_EQ(25.4, squareRoot(645.16)); + ASSERT_EQ(0, squareRoot(0.0)); +} + +TEST(SquareRootTest, NegativeNos) { + ASSERT_EQ(-1.0, squareRoot(-15.0)); + ASSERT_EQ(-1.0, squareRoot(-0.2)); +} + +int main(int argc, char **argv) { + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} \ No newline at end of file diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/state_machine_test.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/state_machine_test.cpp new file mode 100644 index 0000000..977de8c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/state_machine_test.cpp @@ -0,0 +1,344 @@ +#include + +#include "rosflight.h" +#include "test_board.h" + +using namespace rosflight_firmware; + +TEST(state_machine_test, error_check) { + + // Initialize the full firmware, so that the state_manager can do its thing + testBoard board; + ROSflight rf(board); + + // Initialize just a subset of the modules + // (some modules set errors when they initialize) + rf.board_.init_board(); + rf.state_manager_.init(); + rf.params_.init(); + + // Should be in PREFLIGHT MODE + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x00); + ASSERT_EQ(rf.state_manager_.state().error, false); + + // Try setting and clearing all the errors + for (int error = 0x0001; error <= StateManager::ERROR_UNCALIBRATED_IMU; error *= 2) + { + // set the error + rf.state_manager_.set_error(error); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, error); + ASSERT_EQ(rf.state_manager_.state().error, true); + + // clear the error + rf.state_manager_.clear_error(error); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, StateManager::ERROR_NONE); + ASSERT_EQ(rf.state_manager_.state().error, false); + } + + // Try combinations of errors + uint32_t error = StateManager::ERROR_IMU_NOT_RESPONDING | + StateManager::ERROR_TIME_GOING_BACKWARDS | + StateManager::ERROR_UNCALIBRATED_IMU; + rf.state_manager_.set_error(error); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x32); + ASSERT_EQ(rf.state_manager_.state().error, true); + + // Add another error + rf.state_manager_.set_error(StateManager::ERROR_INVALID_MIXER); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x33); + ASSERT_EQ(rf.state_manager_.state().error, true); + + // Clear an error + rf.state_manager_.clear_error(StateManager::ERROR_UNCALIBRATED_IMU); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x13); + ASSERT_EQ(rf.state_manager_.state().error, true); + + // Clear two errors + rf.state_manager_.clear_error(StateManager::ERROR_IMU_NOT_RESPONDING | + StateManager::ERROR_TIME_GOING_BACKWARDS); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x01); + ASSERT_EQ(rf.state_manager_.state().error, true); + + // Clear final error + rf.state_manager_.clear_error(StateManager::ERROR_INVALID_MIXER); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x00); + ASSERT_EQ(rf.state_manager_.state().error, false); +} + +TEST(state_machine_test, arm_check) { + // Build the full firmware, so that the state_manager can do its thing + testBoard board; + ROSflight rf(board); + + // Initialize just a subset of the modules + // (some modules set errors when they initialize) + rf.board_.init_board(); + rf.state_manager_.init(); + rf.params_.init(); + + // Should be in PREFLIGHT MODE + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x00); + ASSERT_EQ(rf.state_manager_.state().error, false); + + //====================================================== + // Basic arming test + //====================================================== + + // Make sure that the parameter to calibrate before arm is off + rf.params_.set_param_int(PARAM_CALIBRATE_GYRO_ON_ARM, false); + + // Now add, an error, and then try to arm + rf.state_manager_.set_error(StateManager::ERROR_INVALID_MIXER); + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_ARM); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, StateManager::ERROR_INVALID_MIXER); + ASSERT_EQ(rf.state_manager_.state().error, true); + + + // Clear the error, and then try again to arm + rf.state_manager_.clear_error(StateManager::ERROR_INVALID_MIXER); + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_ARM); + ASSERT_EQ(rf.state_manager_.state().armed, true); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, StateManager::ERROR_NONE); + ASSERT_EQ(rf.state_manager_.state().error, false); + + // Disarm + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_DISARM); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, StateManager::ERROR_NONE); + ASSERT_EQ(rf.state_manager_.state().error, false); + + + //====================================================== + // Preflight calibration arming test + //====================================================== + // turn preflight calibration on + rf.params_.set_param_int(PARAM_CALIBRATE_GYRO_ON_ARM, true); + + // try to arm + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_ARM); + // We shouldn't have armed yet + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, StateManager::ERROR_NONE); + ASSERT_EQ(rf.state_manager_.state().error, false); + + // Set an error + rf.state_manager_.set_error(StateManager::ERROR_INVALID_MIXER); + // We shouldn't have armed yet + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, StateManager::ERROR_INVALID_MIXER); + ASSERT_EQ(rf.state_manager_.state().error, true); + + // Clear the error, and try again + rf.state_manager_.clear_error(StateManager::ERROR_INVALID_MIXER); + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_ARM); + // Tell it that the calibration failed + rf.state_manager_.set_event(StateManager::EVENT_CALIBRATION_FAILED); + // We shouldn't have armed yet + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x00); + ASSERT_EQ(rf.state_manager_.state().error, false); + + // Try again, but this time the calibration succeeds + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_ARM); + rf.state_manager_.set_event(StateManager::EVENT_CALIBRATION_COMPLETE); + // We should be armed + ASSERT_EQ(rf.state_manager_.state().armed, true); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x00); + ASSERT_EQ(rf.state_manager_.state().error, false); + + //====================================================== + // Errors while armed test + //====================================================== + // turn preflight calibration off + rf.params_.set_param_int(PARAM_CALIBRATE_GYRO_ON_ARM, false); + + // While armed, let's set some errors + rf.state_manager_.set_error(StateManager::ERROR_TIME_GOING_BACKWARDS); + // We should still be armed, but have an error + ASSERT_EQ(rf.state_manager_.state().armed, true); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, StateManager::ERROR_TIME_GOING_BACKWARDS); + ASSERT_EQ(rf.state_manager_.state().error, true); + + // What happens if we disarm now? + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_DISARM); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, StateManager::ERROR_TIME_GOING_BACKWARDS); + ASSERT_EQ(rf.state_manager_.state().error, true); + + // Try to arm, it should fail + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_ARM); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, StateManager::ERROR_TIME_GOING_BACKWARDS); + ASSERT_EQ(rf.state_manager_.state().error, true); + + // Clear the error and try again + rf.state_manager_.clear_error(StateManager::ERROR_TIME_GOING_BACKWARDS); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x00); + ASSERT_EQ(rf.state_manager_.state().error, false); + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_ARM); + ASSERT_EQ(rf.state_manager_.state().armed, true); + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_DISARM); + ASSERT_EQ(rf.state_manager_.state().armed, false); +} + +TEST(state_machine_test, failsafe_check) { + // Build the full firmware, so that the state_manager can do its thing + testBoard board; + ROSflight rf(board); + + // Initialize just a subset of the modules + // (some modules set errors when they initialize) + rf.board_.init_board(); + rf.state_manager_.init(); + rf.params_.init(); + + // Should be in PREFLIGHT MODE + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x00); + ASSERT_EQ(rf.state_manager_.state().error, false); + + //====================================================== + // RC Lost when disarmed - Should not be in failsafe, but in error + //====================================================== + rf.state_manager_.set_event(StateManager::EVENT_RC_LOST); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, StateManager::ERROR_RC_LOST); + ASSERT_EQ(rf.state_manager_.state().error, true); + + // Try to arm + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_ARM); + ASSERT_EQ(rf.state_manager_.state().armed, false); + + // Oh look! we have RC again + rf.state_manager_.set_event(StateManager::EVENT_RC_FOUND); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x00); + ASSERT_EQ(rf.state_manager_.state().error, false); + + //====================================================== + // RC Lost when armed - should enter failsafe + //====================================================== + + // Let's fly! + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_ARM); + ASSERT_EQ(rf.state_manager_.state().armed, true); + + // Oh crap, we lost RC in the air + rf.state_manager_.set_event(StateManager::EVENT_RC_LOST); + ASSERT_EQ(rf.state_manager_.state().armed, true); + ASSERT_EQ(rf.state_manager_.state().failsafe, true); + ASSERT_EQ(rf.state_manager_.state().error_codes, StateManager::ERROR_RC_LOST); + ASSERT_EQ(rf.state_manager_.state().error, true); + + // If by some magic we are able to disarm (perhaps via the computer) + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_DISARM); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, true); + ASSERT_EQ(rf.state_manager_.state().error_codes, StateManager::ERROR_RC_LOST); + ASSERT_EQ(rf.state_manager_.state().error, true); + + // Let's regain RC + rf.state_manager_.set_event(StateManager::EVENT_RC_FOUND); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x00); + ASSERT_EQ(rf.state_manager_.state().error, false); + + // Let's try this again! + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_ARM); + ASSERT_EQ(rf.state_manager_.state().armed, true); + + // This is the worst receiver + rf.state_manager_.set_event(StateManager::EVENT_RC_LOST); + ASSERT_EQ(rf.state_manager_.state().armed, true); + ASSERT_EQ(rf.state_manager_.state().failsafe, true); + + // It's going in and out! + rf.state_manager_.set_event(StateManager::EVENT_RC_FOUND); + ASSERT_EQ(rf.state_manager_.state().armed, true); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x00); + ASSERT_EQ(rf.state_manager_.state().error, false); +} + +TEST(state_machine_test, corner_cases) { + // Build the full firmware, so that the state_manager can do its thing + testBoard board; + ROSflight rf(board); + + // Initialize just a subset of the modules + // (some modules set errors when they initialize) + rf.board_.init_board(); + rf.state_manager_.init(); + rf.params_.init(); + + // Should be in PREFLIGHT MODE + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x00); + ASSERT_EQ(rf.state_manager_.state().error, false); + + //====================================================== + // RC Lost when calibrating + //====================================================== + + // turn preflight calibration on + rf.params_.set_param_int(PARAM_CALIBRATE_GYRO_ON_ARM, true); + + // Try to arm + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_ARM); + ASSERT_EQ(rf.state_manager_.state().armed, false); + + // Lose RC during calibration - error, no failsafe + rf.state_manager_.set_event(StateManager::EVENT_RC_LOST); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, StateManager::ERROR_RC_LOST); + ASSERT_EQ(rf.state_manager_.state().error, true); + + // Regain RC, should be in preflight mode, no error + rf.state_manager_.set_event(StateManager::EVENT_RC_FOUND); + ASSERT_EQ(rf.state_manager_.state().armed, false); + ASSERT_EQ(rf.state_manager_.state().failsafe, false); + ASSERT_EQ(rf.state_manager_.state().error_codes, 0x00); + ASSERT_EQ(rf.state_manager_.state().error, false); + + rf.state_manager_.set_event(StateManager::EVENT_REQUEST_ARM); + ASSERT_EQ(rf.state_manager_.state().armed, false); + rf.state_manager_.set_event(StateManager::EVENT_CALIBRATION_COMPLETE); + ASSERT_EQ(rf.state_manager_.state().armed, true); +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/test_board.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/test_board.cpp new file mode 100644 index 0000000..9053cb8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/test_board.cpp @@ -0,0 +1,144 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include "test_board.h" + +namespace rosflight_firmware +{ + + void testBoard::set_rc(uint16_t *values) + { + for (int i = 0; i < 8; i++) + { + rc_values[i] = values[i]; + } + } + + void testBoard::set_time(uint64_t time_us) + { + time_us_ = time_us; + } + + void testBoard::set_pwm_lost(bool lost) + { + rc_lost_ = lost; + } + + void testBoard::set_imu(float *acc, float *gyro, uint64_t time_us) + { + time_us_ = time_us; + for (int i = 0; i < 3; i++) + { + acc_[i] = acc[i]; + gyro_[i] = gyro[i]; + } + new_imu_ = true; + } + + +// setup + void testBoard::init_board(void){} + void testBoard::board_reset(bool bootloader){} + +// clock + uint32_t testBoard::clock_millis(){ return time_us_/1000; } + uint64_t testBoard::clock_micros(){ return time_us_; } + void testBoard::clock_delay(uint32_t milliseconds){} + +// serial + void testBoard::serial_init(uint32_t baud_rate){} + void testBoard::serial_write(const uint8_t *src, size_t len){} + uint16_t testBoard::serial_bytes_available(void){ return 0; } + uint8_t testBoard::serial_read(void){} + +// sensors + void testBoard::sensors_init(){} + uint16_t testBoard::num_sensor_errors(void) {} + + bool testBoard::new_imu_data() + { + if (new_imu_) + { + new_imu_ = false; + return true; + } + return false; + } + + + bool testBoard::imu_read(float accel[3], float *temperature, float gyro[3], uint64_t* time) + { + for (int i = 0; i < 3; i++) + { + accel[i] = acc_[i]; + gyro[i] = gyro_[i]; + } + *temperature = 25.0; + *time = time_us_; + return true; + } + + void testBoard::imu_not_responding_error(void){} + + bool testBoard::mag_check(void){ return false; } + void testBoard::mag_read(float mag[3]){} + + bool testBoard::baro_check(void){ return false; } + void testBoard::baro_read(float *pressure, float *temperature) {} + + bool testBoard::diff_pressure_check(void){ return false; } + void testBoard::diff_pressure_read(float *diff_pressure, float *temperature) {} + + bool testBoard::sonar_check(void){ return false; } + float testBoard::sonar_read(void){} + +// PWM +// TODO make these deal in normalized (-1 to 1 or 0 to 1) values (not pwm-specific) + void testBoard::pwm_init(bool cppm, uint32_t refresh_rate, uint16_t idle_pwm){} + bool testBoard::pwm_lost(){ return rc_lost_; } + uint16_t testBoard::pwm_read(uint8_t channel){ return rc_values[channel];} + void testBoard::pwm_write(uint8_t channel, uint16_t value){} + +// non-volatile memory + void testBoard::memory_init(void){} + bool testBoard::memory_read(void *dest, size_t len){ return false; } + bool testBoard::memory_write(const void *src, size_t len){ return false; } + +// LEDs + void testBoard::led0_on(void){} + void testBoard::led0_off(void){} + void testBoard::led0_toggle(void){} + + void testBoard::led1_on(void){} + void testBoard::led1_off(void){} + void testBoard::led1_toggle(void){} + +} // namespace rosflight_firmware diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/test_board.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/test_board.h new file mode 100644 index 0000000..c64f274 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/test_board.h @@ -0,0 +1,119 @@ +/* + * Copyright (c) 2017, James Jackson and Daniel Koch, BYU MAGICC Lab + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_FIRMWARE_TEST_BOARD_H +#define ROSFLIGHT_FIRMWARE_TEST_BOARD_H + +#include "board.h" + +namespace rosflight_firmware +{ + +class testBoard : public Board +{ + +private: + uint16_t rc_values[8] = {0, 0, 0, 0, 0, 0, 0, 0}; + uint64_t time_us_ = 0; + bool rc_lost_ = false; + float acc_[3] = {0, 0, 0}; + float gyro_[3] = {0, 0, 0}; + bool new_imu_ = false; + +public: +// setup + void init_board(void); + void board_reset(bool bootloader); + +// clock + uint32_t clock_millis(); + uint64_t clock_micros(); + void clock_delay(uint32_t milliseconds); + +// serial + void serial_init(uint32_t baud_rate); + void serial_write(const uint8_t *src, size_t len); + uint16_t serial_bytes_available(void); + uint8_t serial_read(void); + +// sensors + void sensors_init(); + uint16_t num_sensor_errors(void) ; + + bool new_imu_data(); + bool imu_read(float accel[3], float *temperature, float gyro[3], uint64_t* time); + void imu_not_responding_error(void); + + bool mag_check(void); + void mag_read(float mag[3]); + + bool baro_check(void); + void baro_read(float *pressure, float *temperature); + + bool diff_pressure_check(void); + void diff_pressure_read(float *diff_pressure, float *temperature); + + bool sonar_check(void); + float sonar_read(void); + +// PWM +// TODO make these deal in normalized (-1 to 1 or 0 to 1) values (not pwm-specific) + void pwm_init(bool cppm, uint32_t refresh_rate, uint16_t idle_pwm); + bool pwm_lost(); + uint16_t pwm_read(uint8_t channel); + void pwm_write(uint8_t channel, uint16_t value); + +// non-volatile memory + void memory_init(void); + bool memory_read(void *dest, size_t len); + bool memory_write(const void *src, size_t len); + +// LEDs + void led0_on(void); + void led0_off(void); + void led0_toggle(void); + + void led1_on(void); + void led1_off(void); + void led1_toggle(void); + + + + void set_imu(float* acc, float* gyro, uint64_t time_us); + void set_rc(uint16_t* values); + void set_time(uint64_t time_us); + void set_pwm_lost(bool lost); + +}; + +} // namespace rosflight_firmware + +#endif // ROSLFIGHT_FIRMWARE_TEST_BOARD_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/turbotrig_test.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/turbotrig_test.cpp new file mode 100644 index 0000000..d1f2c0e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/firmware/test/turbotrig_test.cpp @@ -0,0 +1,306 @@ +/* + * + * BSD 3-Clause License + * + * Copyright (c) 2017, James Jackson BYU MAGICC Lab, Provo UT + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#include "math.h" +#include +#include +#include "eigen3/Eigen/Core" +#include "eigen3/Eigen/Dense" +#include "eigen3/Eigen/Geometry" +#include + +vector_t random_vectors[25] = { + { -0.0376278050814 , 0.471775699711 , -0.336572370974 }, + { 0.842139998851 , -0.113277302409 , -0.435361598132 }, + { 0.402876930871 , -0.998517068538 , 0.956603957591 }, + { 0.366004030077 , -0.966554559399 , 0.236455814495 }, + { 0.170963581611 , -0.892193316086 , -0.360102936987 }, + { -0.675191763273 , -0.794118513048 , 0.561367212903 }, + { -0.0299477253533 , 0.0938177650483 , 0.525814272724 }, + { -0.676191678521 , -0.0780862208203 , -0.272955681219 }, + { -0.435749833209 , -0.673810649938 , -0.896559097382 }, + { 0.709083915552 , -0.135067363969 , -0.385492450532 }, + { -0.38728558039 , -0.502219301225 , 0.323557018529 }, + { -0.186870345154 , 0.554827454101 , 0.921567682061 }, + { -0.142106787605 , -0.764876359963 , 0.00303689980819 }, + { -0.677798963582 , -0.664595954482 , 0.339274533414 }, + { -0.700464041114 , 0.325731535871 , -0.621492014391 }, + { -0.604865828708 , 0.270639620454 , 0.188624833185 }, + { 0.464205180183 , -0.461504601245 , -0.578708441515 }, + { 0.498899172115 , -0.582342366402 , -0.694758083436 }, + { 0.0710544604541 , -0.63603887083 , -0.521799692437 }, + { -0.372025413205 , 0.83531212357 , 0.232484576742 }, + { 0.790872496361 , -0.89600683592 , 0.783984438621 }, + { 0.236462609786 , -0.636362560394 , 0.203951290805 }, + { 0.831924307534 , -0.482532468579 , 0.0600026189612 }, + { 0.0562194856302 , -0.605799189029 , -0.556494338297 }, + { -0.85014432598 , 0.0632157037573 , 0.0272188414114 }}; + + +quaternion_t random_quaternions[25] = { + { 0.10377420365 , -0.583993115868 , -0.731526280531 , -0.0530049846003 }, + { -0.00228103177408 , -0.506936771567 , 0.976002181169 , 0.90368722061 }, + { -0.280191704748 , 0.141235897077 , 0.770363502952 , 0.306427689307 }, + { 0.964538929753 , -0.849755381903 , 0.36374459234 , 0.694507794584 }, + { 0.0176390041681 , -0.960155080148 , 0.340078582124 , -0.119639355159 }, + { -0.213139865459 , -0.91618752978 , -0.192746623826 , -0.761937711418 }, + { -0.491440057128 , -0.468120646081 , -0.0682240789086 , -0.779728041272 }, + { 0.00414757516987 , -0.980357614738 , 0.243315557667 , 0.487816606638 }, + { -0.593742280674 , 0.245648066311 , 0.682367014935 , -0.0659175648814 }, + { -0.322464011587 , 0.706588950729 , -0.966024250287 , -0.50354344519 }, + { -0.537023302971 , -0.496355850419 , -0.326843736039 , 0.456606813517 }, + { -0.581585485434 , 0.225766708322 , -0.121402082687 , 0.160333514827 }, + { -0.422711480811 , 0.894994456476 , 0.392582496229 , 0.0035135659771 }, + { 0.326380783544 , 0.551413227108 , 0.89489801397 , 0.87883243747 }, + { 0.83500683695 , -0.263875030319 , -0.1783391105 , 0.453727091163 }, + { -0.30389938019 , -0.0744317276089 , -0.436917072268 , 0.907173926266 }, + { -0.320066655494 , -0.349065285706 , 0.0336903431161 , 0.573906603454 }, + { -0.103624452083 , -0.82874783662 , -0.635967208274 , 0.562138574765 }, + { 0.90735669209 , -0.611711092446 , 0.732474120503 , 0.866697480004 }, + { 0.626137839218 , 0.41320663394 , -0.821473642241 , -0.344696411875 }, + { 0.266650461152 , -0.784707647527 , 0.324347257562 , -0.724904312141 }, + { 0.964177603528 , -0.378173605577 , 0.767349174766 , 0.560290218637 }, + { 0.0812716046369 , 0.745067180353 , -0.476875959113 , -0.245887902551 }, + { -0.177027678376 , 0.214558558928 , -0.992910369554 , 0.592964390132 }, + { 0.0979109306209 , 0.121890109199 , 0.126418158551 , 0.242200145606 }}; + + +#define EXPECT_VEC3_SUPERCLOSE(vec, eig) EXPECT_LE(fabs(vec.x - eig.x()), 0.0001);\ + EXPECT_LE(fabs(vec.y - eig.y()), 0.0001);\ + EXPECT_LE(fabs(vec.z - eig.z()), 0.0001) +#define EXPECT_QUAT_SUPERCLOSE(q, q_eig) { \ + double e1 = quaternion_error(q_eig, q); \ + q_eig.coeffs() *= -1.0; \ + double e2 = quaternion_error(q_eig, q); \ + double error = (e1 < e2) ? e1 : e2; \ + EXPECT_LE(error, 0.0001); \ +} +#define ASSERT_QUAT_SUPERCLOSE(q, q_eig) { \ + double e1 = quaternion_error(q_eig, q); \ + q_eig.coeffs() *= -1.0; \ + double e2 = quaternion_error(q_eig, q); \ + double error = (e1 < e2) ? e1 : e2; \ + ASSERT_LE(error, 0.0001); \ +} + +#define ASSERT_TURBOQUAT_SUPERCLOSE(q, q_eig) { \ + double e1 = quaternion_error(q_eig, q); \ + q_eig.w *= -1.0; \ + q_eig.x *= -1.0; \ + q_eig.y *= -1.0; \ + q_eig.z *= -1.0; \ + double e2 = quaternion_error(q_eig, q); \ + double error = (e1 < e2) ? e1 : e2; \ + ASSERT_LE(error, 0.0001); \ +} + +#define EXPECT_SUPERCLOSE(x, y) EXPECT_LE(fabs(x -y), 0.0001) +#define ASSERT_SUPERCLOSE(x, y) ASSERT_LE(fabs(x -y), 0.0001) +#define EXPECT_CLOSE(x, y) EXPECT_LE(fabs(x -y), 0.01) + +double quaternion_error(Eigen::Quaternionf q_eig, quaternion_t q) +{ + Eigen::Quaternionf est_quat(q.w, q.x, q.y, q.z); + Eigen::Quaternionf q_tilde = q_eig * est_quat.inverse(); + if(q_tilde.vec().norm() < 0.000001) + return 0; + else + { + Eigen::Vector3f v_tilde = atan2(q_tilde.vec().norm(), q_tilde.w())*q_tilde.vec()/q_tilde.vec().norm(); + return v_tilde.norm(); + } +} + +double quaternion_error(quaternion_t q0, quaternion_t q) +{ + Eigen::Quaternionf est_quat(q.w, q.x, q.y, q.z); + Eigen::Quaternionf q_eig(q0.w, q0.x, q0.y, q0.z); + Eigen::Quaternionf q_tilde = q_eig * est_quat.inverse(); + if(q_tilde.vec().norm() < 0.000001) + return 0; + else + { + Eigen::Vector3f v_tilde = atan2(q_tilde.vec().norm(), q_tilde.w())*q_tilde.vec()/q_tilde.vec().norm(); + return v_tilde.norm(); + } +} + +TEST(turbotrig_test, atan_test) { + for (float i = -200.0; i <= 200.0; i += 0.001) + { + EXPECT_LE(fabs(turboatan(i) - atan(i)), 0.0001); + } +} + +TEST(turbotrig_test, atan2_test) { + for (float i = -100.0; i <= 100.0; i += 0.1) + { + for (float j = -1.0; j <= 1.0; j += 0.001) + { + if (fabs(j) > 0.0001) + { + EXPECT_LE(fabs(atan2_approx(i, j) - atan2(i, j)), 0.001); + } + } + } +} + +TEST(turbotrig_test, asin_test) { + for (float i = -1.0; i <= 1.0; i += 0.001) + { + if ( fabs(i) < 0.95 ) + EXPECT_LE(fabs(asin_approx(i) - asin(i)), 0.0001); + else + EXPECT_LE(fabs(asin_approx(i) - asin(i)), 0.05); + } +} + +TEST(turbovec_test, vector_test) { + for (int i = 0; i < 24; i++) + { + vector_t vec1 = random_vectors[i]; + vector_t vec2 = random_vectors[i + 1]; + Eigen::Vector3f eig2, eig1; + eig1 << vec1.x, vec1.y, vec1.z; + eig2 << vec2.x, vec2.y, vec2.z; + EXPECT_VEC3_SUPERCLOSE(vec1, eig1); + EXPECT_VEC3_SUPERCLOSE(vec2, eig2); + + EXPECT_VEC3_SUPERCLOSE(vector_add(vec1, vec2), (eig1 + eig2)); + EXPECT_VEC3_SUPERCLOSE(vector_sub(vec1, vec2), (eig1 - eig2)); + EXPECT_VEC3_SUPERCLOSE(vector_normalize(vec1), eig1.normalized()); + EXPECT_VEC3_SUPERCLOSE(scalar_multiply(5.0, vec1), 5.0*eig1); + + EXPECT_SUPERCLOSE(norm(vec1), eig1.norm()); + EXPECT_SUPERCLOSE(sqrd_norm(vec1), eig1.squaredNorm()); + + // Test Vector Dot Product + EXPECT_SUPERCLOSE(dot(vec1, vec2), (eig1.transpose() * eig2)); + + // Test Vector Cross Product + EXPECT_VEC3_SUPERCLOSE(cross(vec1, vec2), eig1.cross(eig2)); + } +} + + +TEST(turbovec_test, quaternion_test) { + + for (int i = 0; i < 24; i++) + { + quaternion_t quat1 = quaternion_normalize(random_quaternions[i]); + quaternion_t quat2 = quaternion_normalize(random_quaternions[i + 1]); + Eigen::Quaternionf eig1(quat1.w, quat1.x, quat1.y, quat1.z); + Eigen::Quaternionf eig2(quat2.w, quat2.x, quat2.y, quat2.z); + + EXPECT_QUAT_SUPERCLOSE(quat1, eig1); + EXPECT_QUAT_SUPERCLOSE(quat2, eig2); + + // Check normalization + EXPECT_SUPERCLOSE(quat1.x*quat1.x + quat1.y*quat1.y + quat1.z*quat1.z + quat1.w*quat1.w, 1.0f); + EXPECT_SUPERCLOSE(quat2.x*quat2.x + quat2.y*quat2.y + quat2.z*quat2.z + quat2.w*quat2.w, 1.0f); + + // Test Quaternion Operators + ASSERT_QUAT_SUPERCLOSE(quaternion_multiply(quat1, quat2), (eig2*eig1)); + ASSERT_QUAT_SUPERCLOSE(quaternion_inverse(quat2), eig2.inverse()); + + + // Test Quaternion Rotate + vector_t vec1 = random_vectors[i]; + Eigen::Vector3f veig1; + veig1 << vec1.x, vec1.y, vec1.z; + + + // Test rotate_vector + vector_t vec2 = rotate_vector(quat1, vec1); + Eigen::Vector3f veig2 = veig1.transpose()*eig1.toRotationMatrix(); + EXPECT_VEC3_SUPERCLOSE(vec2, veig2); + + vector_t vec3 = rotate_vector(quat1, vec1); + Eigen::Vector3f veig3 = veig1.transpose()*eig1.toRotationMatrix(); + EXPECT_VEC3_SUPERCLOSE(vec3, veig3); + } +} + +TEST(turbovec_test, quat_from_two_vectors_test){ + // Test the "quat_from_two_vectors" + vector_t vec1 = {1, 0, 0}; + quaternion_t quat1 = {1.0/sqrt(2.0), 0, 0, 1.0/sqrt(2.0)}; + vector_t vec2 = rotate_vector(quat1, vec1); + quaternion_t quat_test = quat_from_two_unit_vectors(vec2, vec1); + + ASSERT_TURBOQUAT_SUPERCLOSE(quat1, quat_test); + + + // A bunch of random (off-axes tests) + for (int i = 0; i < 25; i++) + { + vector_t vec3 = vector_normalize(random_vectors[i]); + quaternion_t quat2 = quaternion_normalize(random_quaternions[i]); + + // Manually rotate this vector with the quaternion + vector_t vec4 = rotate_vector(quat2, vec3); + + // Extract the "shortest-arc" rotation + quat_test = quat_from_two_unit_vectors(vec4, vec3); + + // Try rotating that same vector with this new quaternion + vector_t vec5 = rotate_vector(quat_test, vec3); + + // Make sure that the vectors are the same + ASSERT_SUPERCLOSE(vec5.x, vec4.x); + ASSERT_SUPERCLOSE(vec5.y, vec4.y); + ASSERT_SUPERCLOSE(vec5.z, vec4.z); + } +} + +TEST(turbotrig_test, fast_alt_test) { + + //out of bounds + EXPECT_EQ(fast_alt(69681), 0.0); + EXPECT_EQ(fast_alt(106598), 0.0); + + //all valid int values + float trueResult = 0.0; + for (int i = 69682; i < 106597; i++) { + trueResult = (float)((1.0 - pow((float)i/101325, 0.190284)) * 145366.45) * (float)0.3048; + EXPECT_LE(fabs(fast_alt(i) - trueResult), .15); + //arbitrarily chose <= .15m since fast_alt isn't accurate enough for EXPECT_CLOSE, + //but being within .15 meters of the correct result seems pretty good to me + } +} + + +int main(int argc, char **argv) { + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/include/rosflight_firmware/udp_board.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/include/rosflight_firmware/udp_board.h new file mode 100644 index 0000000..28a54e6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/include/rosflight_firmware/udp_board.h @@ -0,0 +1,125 @@ +/* + * Copyright (c) 2017 Daniel Koch, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file udp_board.h + * \author Daniel Koch + */ + +#ifndef ROSFLIGHT_FIRMWARE_UDP_BOARD_H +#define ROSFLIGHT_FIRMWARE_UDP_BOARD_H + +#include +#include + +#include +#include + +#include "board.h" +#include "mavlink.h" + +namespace rosflight_firmware +{ + +class UDPBoard : public Board +{ +public: + UDPBoard(std::string bind_host = "localhost", + uint16_t bind_port = 14525, + std::string remote_host = "localhost", + uint16_t remote_port = 14520); + ~UDPBoard(); + + void serial_init(uint32_t baud_rate) override; + void serial_write(const uint8_t *src, size_t len) override; + uint16_t serial_bytes_available(void) override; + uint8_t serial_read(void) override; + + void set_ports(std::string bind_host, uint16_t bind_port, std::string remote_host, uint16_t remote_port); +private: + + struct Buffer + { + uint8_t data[MAVLINK_MAX_PACKET_LEN]; + size_t len; + size_t pos; + + Buffer() : len(0), pos(0) {} + + Buffer(const uint8_t *src, size_t len) : len(len), pos(0) + { + assert(len <= MAVLINK_MAX_PACKET_LEN); //! \todo Do something less catastrophic here + memcpy(data, src, len); + } + + const uint8_t * dpos() const { return data + pos; } + size_t nbytes() const { return len - pos; } + void add_byte(uint8_t byte) { data[len++] = byte; } + uint8_t consume_byte() { return data[pos++]; } + bool empty() const { return pos >= len; } + bool full() const { return len >= MAVLINK_MAX_PACKET_LEN; } + }; + + typedef boost::lock_guard MutexLock; + + void async_read(); + void async_read_end(const boost::system::error_code& error, size_t bytes_transferred); + + void async_write(bool check_write_state); + void async_write_end(const boost::system::error_code& error, size_t bytes_transferred); + + std::string bind_host_; + uint16_t bind_port_; + + std::string remote_host_; + uint16_t remote_port_; + + boost::thread io_thread_; + boost::recursive_mutex write_mutex_; + boost::recursive_mutex read_mutex_; + + boost::asio::io_service io_service_; + + boost::asio::ip::udp::socket socket_; + boost::asio::ip::udp::endpoint bind_endpoint_; + boost::asio::ip::udp::endpoint remote_endpoint_; + + uint8_t read_buffer_[MAVLINK_MAX_PACKET_LEN]; + std::list read_queue_; + + Buffer * current_write_buffer_; + std::list write_queue_; + bool write_in_progress_; +}; + +} // namespace rosflight_firmware + +#endif // ROSFLIGHT_FIRMWARE_UDP_BOARD_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/package.xml new file mode 100644 index 0000000..e7b3fd4 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/package.xml @@ -0,0 +1,24 @@ + + + rosflight_firmware + 0.1.3 + Firmware library for software-in-the-loop of the ROSflight ROS stack + + Daniel Koch + + Daniel Koch + James Jackson + + BSD + + http://rosflight.org + https://github.com/rosflight/rosflight + https://github.com/rosflight/rosflight/issues + + catkin + + roscpp + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/src/udp_board.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/src/udp_board.cpp new file mode 100644 index 0000000..38154bc --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_firmware/src/udp_board.cpp @@ -0,0 +1,205 @@ +/* + * Copyright (c) 2017 Daniel Koch, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** + * \file udp_board.cpp + * \author Daniel Koch + */ + +#include +#include + +using boost::asio::ip::udp; + +namespace rosflight_firmware +{ + +UDPBoard::UDPBoard(std::string bind_host, uint16_t bind_port, std::string remote_host, uint16_t remote_port) : + bind_host_(bind_host), + bind_port_(bind_port), + remote_host_(remote_host), + remote_port_(remote_port), + io_service_(), + socket_(io_service_), + current_write_buffer_(new Buffer), + write_in_progress_(false) +{ +} + +UDPBoard::~UDPBoard() +{ + MutexLock read_lock(read_mutex_); + MutexLock write_lock(write_mutex_); + + io_service_.stop(); + socket_.close(); + + if (io_thread_.joinable()) + io_thread_.join(); +} + +void UDPBoard::set_ports(std::string bind_host, uint16_t bind_port, std::string remote_host, uint16_t remote_port) +{ + bind_host_ = bind_host; + bind_port_ = bind_port; + remote_host_ = remote_host; + remote_port_ = remote_port; +} + +void UDPBoard::serial_init(uint32_t baud_rate) +{ + // can throw an uncaught boost::system::system_error exception + + udp::resolver resolver(io_service_); + + bind_endpoint_ = *resolver.resolve({udp::v4(), bind_host_, ""}); + bind_endpoint_.port(bind_port_); + + remote_endpoint_ = *resolver.resolve({udp::v4(), remote_host_, ""}); + remote_endpoint_.port(remote_port_); + + socket_.open(udp::v4()); + socket_.bind(bind_endpoint_); + + socket_.set_option(udp::socket::reuse_address(true)); + socket_.set_option(udp::socket::send_buffer_size(1000*MAVLINK_MAX_PACKET_LEN)); + socket_.set_option(udp::socket::receive_buffer_size(1000*MAVLINK_MAX_PACKET_LEN)); + + async_read(); + io_thread_ = boost::thread(boost::bind(&boost::asio::io_service::run, &io_service_)); +} + +void UDPBoard::serial_write(const uint8_t *src, size_t len) +{ + Buffer *buffer = new Buffer(src, len); + + { + MutexLock lock(write_mutex_); + write_queue_.push_back(buffer); + } + + async_write(true); +} + +uint16_t UDPBoard::serial_bytes_available() +{ + MutexLock lock(read_mutex_); + return !read_queue_.empty(); //! \todo This should return a number, not a bool +} + +uint8_t UDPBoard::serial_read() +{ + MutexLock lock(read_mutex_); + + if (read_queue_.empty()) + return 0; + + Buffer *buffer = read_queue_.front(); + uint8_t byte = buffer->consume_byte(); + + if (buffer->empty()) + { + read_queue_.pop_front(); + delete buffer; + } + return byte; +} + +void UDPBoard::async_read() +{ + if (!socket_.is_open()) return; + + MutexLock lock(read_mutex_); + socket_.async_receive_from(boost::asio::buffer(read_buffer_, MAVLINK_MAX_PACKET_LEN), + remote_endpoint_, + boost::bind(&UDPBoard::async_read_end, + this, + boost::asio::placeholders::error, + boost::asio::placeholders::bytes_transferred)); +} + +void UDPBoard::async_read_end(const boost::system::error_code &error, size_t bytes_transferred) +{ + if (!error) + { + MutexLock lock(read_mutex_); + read_queue_.push_back(new Buffer(read_buffer_, bytes_transferred)); + } + async_read(); +} + +void UDPBoard::async_write(bool check_write_state) +{ + if (check_write_state && write_in_progress_) + return; + + MutexLock lock(write_mutex_); + if (write_queue_.empty()) + return; + + write_in_progress_ = true; + Buffer *buffer = write_queue_.front(); + socket_.async_send_to(boost::asio::buffer(buffer->dpos(), buffer->nbytes()), + remote_endpoint_, + boost::bind(&UDPBoard::async_write_end, + this, + boost::asio::placeholders::error, + boost::asio::placeholders::bytes_transferred)); +} + +void UDPBoard::async_write_end(const boost::system::error_code &error, size_t bytes_transferred) +{ + if (!error) + { + MutexLock lock(write_mutex_); + + if (write_queue_.empty()) + { + write_in_progress_ = false; + return; + } + + Buffer *buffer = write_queue_.front(); + buffer->pos += bytes_transferred; + if (buffer->empty()) + { + write_queue_.pop_front(); + delete buffer; + } + + if (write_queue_.empty()) + write_in_progress_ = false; + else + async_write(false); + } +} + +} // namespace rosflight_firmware diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/CHANGELOG.rst b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/CHANGELOG.rst new file mode 100644 index 0000000..846f5bc --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/CHANGELOG.rst @@ -0,0 +1,19 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package rosflight_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.1.3 (2017-06-02) +------------------ +* Updated package.xml files +* Contributors: Daniel Koch + +0.1.2 (2017-05-24) +------------------ + +0.1.1 (2017-05-24) +------------------ + +0.1.0 (2017-05-22) +------------------ +* Created the rosflight_msgs package and updated dependencies +* Contributors: Daniel Koch diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/CMakeLists.txt new file mode 100644 index 0000000..eb6d8ae --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/CMakeLists.txt @@ -0,0 +1,39 @@ +cmake_minimum_required(VERSION 2.8.3) +project(rosflight_msgs) + +find_package(catkin REQUIRED COMPONENTS + geometry_msgs + std_msgs + message_generation +) + +add_message_files( + DIRECTORY msg + FILES + GPS.msg + OutputRaw.msg + RCRaw.msg + Command.msg + Barometer.msg + Airspeed.msg + Attitude.msg + Status.msg +) + +add_service_files( + DIRECTORY srv + FILES + ParamFile.srv + ParamGet.srv + ParamSet.srv +) + +generate_messages( + DEPENDENCIES + geometry_msgs + std_msgs +) + +catkin_package( + CATKIN_DEPENDS geometry_msgs std_msgs +) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/Airspeed.msg b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/Airspeed.msg new file mode 100644 index 0000000..6f34152 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/Airspeed.msg @@ -0,0 +1,4 @@ +Header header +float32 velocity # m/s +float32 differential_pressure # Pa +float32 temperature # K diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/Attitude.msg b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/Attitude.msg new file mode 100644 index 0000000..e291daa --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/Attitude.msg @@ -0,0 +1,5 @@ +# Defines an Euler-Angle Based Attitude Message + +Header header +geometry_msgs/Quaternion attitude +geometry_msgs/Vector3 angular_velocity diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/Barometer.msg b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/Barometer.msg new file mode 100644 index 0000000..0dce052 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/Barometer.msg @@ -0,0 +1,4 @@ +Header header +float32 altitude +float32 pressure +float32 temperature diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/Command.msg b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/Command.msg new file mode 100644 index 0000000..8e3f3c0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/Command.msg @@ -0,0 +1,25 @@ +# Offboard control command message + +# control mode flags +uint8 MODE_PASS_THROUGH = 0 +uint8 MODE_ROLLRATE_PITCHRATE_YAWRATE_THROTTLE = 1 +uint8 MODE_ROLL_PITCH_YAWRATE_THROTTLE = 2 +uint8 MODE_ROLL_PITCH_YAWRATE_ALTITUDE = 3 +uint8 MODE_XPOS_YPOS_YAW_ALTITUDE = 4 +uint8 MODE_XVEL_YVEL_YAWRATE_ALTITUDE = 5 +uint8 MODE_XACC_YACC_YAWRATE_AZ = 6 + +# ignore field bitmasks +uint8 IGNORE_NONE = 0 +uint8 IGNORE_X = 1 +uint8 IGNORE_Y = 2 +uint8 IGNORE_Z = 4 +uint8 IGNORE_F = 8 + +Header header +uint8 mode # offboard control mode for interpreting value fields +uint8 ignore # bitmask for ignore specific setpoint values +float32 x +float32 y +float32 z +float32 F diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/GPS.msg b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/GPS.msg new file mode 100644 index 0000000..ca2c738 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/GPS.msg @@ -0,0 +1,9 @@ +Header header +bool fix +int16 NumSat +float64 latitude # Deg +float64 longitude # Deg +float64 altitude # m +float64 speed # m/s +float64 ground_course # rad +float64 covariance # m diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/OutputRaw.msg b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/OutputRaw.msg new file mode 100644 index 0000000..65e5ca0 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/OutputRaw.msg @@ -0,0 +1,4 @@ +# raw servo outputs + +Header header +float32[16] values diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/RCRaw.msg b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/RCRaw.msg new file mode 100644 index 0000000..6729ff2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/RCRaw.msg @@ -0,0 +1,4 @@ +# raw servo outputs + +Header header +uint16[8] values diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/Status.msg b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/Status.msg new file mode 100644 index 0000000..8612fb8 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/msg/Status.msg @@ -0,0 +1,12 @@ +# Flight controller status message + +Header header + +bool armed # True if armed +bool failsafe # True if in failsafe +bool rc_override # True if RC is in control +bool offboard # True if offboard control is active +int8 control_mode # Onboard control mode +int8 error_code # Onboard error code +int16 num_errors # Number of errors +int16 loop_time_us # Loop time in microseconds diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/package.xml new file mode 100644 index 0000000..ed14042 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/package.xml @@ -0,0 +1,28 @@ + + + rosflight_msgs + 0.1.3 + Message and service definitions for the ROSflight ROS stack + + Daniel Koch + + Daniel Koch + James Jackson + + BSD + + http://rosflight.org + https://github.com/rosflight/rosflight + https://github.com/rosflight/rosflight/issues + + catkin + + geometry_msgs + std_msgs + + message_generation + message_runtime + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/srv/ParamFile.srv b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/srv/ParamFile.srv new file mode 100644 index 0000000..536602a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/srv/ParamFile.srv @@ -0,0 +1,3 @@ +string filename +--- +bool success diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/srv/ParamGet.srv b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/srv/ParamGet.srv new file mode 100644 index 0000000..323cc4a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/srv/ParamGet.srv @@ -0,0 +1,6 @@ +# Request a parameter value + +string name # the name of the parameter value to retrieve +--- +bool exists # whether the request parameter exists +float64 value # the value of the requested parameter diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/srv/ParamSet.srv b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/srv/ParamSet.srv new file mode 100644 index 0000000..1f80f8e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_msgs/srv/ParamSet.srv @@ -0,0 +1,6 @@ +# Set a parameter value + +string name # the name of the parameter to set +float64 value # the value to set the parameter to +--- +bool exists # whether the requested parameter exists diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_pkgs/CHANGELOG.rst b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_pkgs/CHANGELOG.rst new file mode 100644 index 0000000..7705812 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_pkgs/CHANGELOG.rst @@ -0,0 +1,19 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package rosflight_pkgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.1.3 (2017-06-02) +------------------ +* Updated package.xml files +* Contributors: Daniel Koch + +0.1.2 (2017-05-24) +------------------ + +0.1.1 (2017-05-24) +------------------ + +0.1.0 (2017-05-22) +------------------ +* Added rosflight_pkgs metapackage +* Contributors: Daniel Koch diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_pkgs/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_pkgs/CMakeLists.txt new file mode 100644 index 0000000..60098ca --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_pkgs/CMakeLists.txt @@ -0,0 +1,4 @@ +cmake_minimum_required(VERSION 2.8.3) +project(rosflight_pkgs) +find_package(catkin REQUIRED) +catkin_metapackage() diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_pkgs/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_pkgs/package.xml new file mode 100644 index 0000000..53c0dd9 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_pkgs/package.xml @@ -0,0 +1,27 @@ + + + rosflight_pkgs + 0.1.3 + ROS interface for the ROSflight autpilot stack + + Daniel Koch + + Daniel Koch + James Jackson + + BSD + + http://rosflight.org + https://github.com/rosflight/rosflight + https://github.com/rosflight/rosflight/issues + + catkin + + rosflight + rosflight_msgs + rosflight_utils + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/CMakeLists.txt new file mode 100644 index 0000000..5433c99 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/CMakeLists.txt @@ -0,0 +1,59 @@ +cmake_minimum_required(VERSION 2.8.3) +project(rosflight_sim) + +SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") + +# To enable assertions when compiled in release mode. +add_definitions(-DROS_ASSERT_ENABLED) + +find_package(catkin REQUIRED COMPONENTS + roscpp + gazebo_plugins + gazebo_ros + geometry_msgs + rosflight_firmware + rosflight_msgs +) + +find_package(Eigen3 REQUIRED) +find_package(gazebo REQUIRED) + +catkin_package( + INCLUDE_DIRS include + CATKIN_DEPENDS roscpp gazebo_plugins gazebo_ros geometry_msgs rosflight_firmware rosflight_msgs + DEPENDS EIGEN3 GAZEBO +) + +include_directories(include) +include_directories( + ${catkin_INCLUDE_DIRS} + ${Eigen_INCLUDE_DIRS} + ${GAZEBO_INCLUDE_DIRS} + ${SDFormat_INCLUDE_DIRS} +) +link_directories(${GAZEBO_LIBRARY_DIRS}) + +add_library(rosflight_sil_plugin SHARED + src/rosflight_sil.cpp + src/sil_board.cpp + src/multirotor_forces_and_moments.cpp + src/fixedwing_forces_and_moments.cpp +) +target_link_libraries(rosflight_sil_plugin + ${catkin_LIBRARIES} + ${GAZEBO_LIBRARIES} +) +add_dependencies(rosflight_sil_plugin ${catkin_EXPORTED_TARGETS}) + +install( + TARGETS rosflight_sil_plugin + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install( + DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" +) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/include/rosflight_sim/fixedwing_forces_and_moments.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/include/rosflight_sim/fixedwing_forces_and_moments.h new file mode 100644 index 0000000..7349b4c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/include/rosflight_sim/fixedwing_forces_and_moments.h @@ -0,0 +1,118 @@ +/* + * Copyright (c) 2017 Daniel Koch, James Jackson and Gary Ellingson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_SIM_FIXEDWING_FORCES_AND_MOMENTS_H +#define ROSFLIGHT_SIM_FIXEDWING_FORCES_AND_MOMENTS_H + + +#include +#include +#include + +namespace rosflight_sim +{ + +class Fixedwing : public MAVForcesAndMoments +{ +private: + ros::NodeHandle* nh_; + + // physical parameters + double mass_; + double Jx_; + double Jy_; + double Jz_; + double Jxz_; + double rho_; + + // aerodynamic coefficients + struct WingCoeff{ + double S; + double b; + double c; + double M; + double epsilon; + double alpha0; + } wing_; + + // Propeller Coefficients + struct PropCoeff{ + double k_motor; + double k_T_P; + double k_Omega; + double e; + double S; + double C; + } prop_; + + // Lift Coefficients + struct LiftCoeff{ + double O; + double alpha; + double beta; + double p; + double q; + double r; + double delta_a; + double delta_e; + double delta_r; + }; + + LiftCoeff CL_; + LiftCoeff CD_; + LiftCoeff Cm_; + LiftCoeff CY_; + LiftCoeff Cell_; + LiftCoeff Cn_; + + // not constants + // actuators + struct Actuators{ + double e; + double a; + double r; + double t; + } delta_; + + // wind + Eigen::Vector3d wind_; + +public: + Fixedwing(ros::NodeHandle* nh); + ~Fixedwing(); + + Eigen::Matrix updateForcesAndTorques(Current_State x, const int act_cmds[]); + void set_wind(Eigen::Vector3d wind); +}; + +} // namespace rosflight_sim + +#endif // ROSFLIGHT_SIM_FIXEDWING_FORCES_AND_MOMENTS_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/include/rosflight_sim/mav_forces_and_moments.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/include/rosflight_sim/mav_forces_and_moments.h new file mode 100644 index 0000000..457ba84 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/include/rosflight_sim/mav_forces_and_moments.h @@ -0,0 +1,73 @@ +/* + * Copyright (c) 2017 Daniel Koch, James Jackson and Gary Ellingson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_SIM_MAV_FORCES_AND_MOMENTS_H +#define ROSFLIGHT_SIM_MAV_FORCES_AND_MOMENTS_H + +#include + +namespace rosflight_sim +{ + +class MAVForcesAndMoments { +protected: + double sat(double x, double max, double min) + { + if(x > max) + return max; + else if(x < min) + return min; + else + return x; + } + + double max(double x, double y) + { + return (x > y) ? x : y; + } + +public: + + struct Current_State{ + Eigen::Vector3d pos; // Position of MAV in NED wrt initial position + Eigen::Matrix3d rot; // Rotation of MAV in NED wrt initial position + Eigen::Vector3d vel; // Body-fixed velocity of MAV wrt initial position (NED) + Eigen::Vector3d omega; // Body-fixed angular velocity of MAV (NED) + double t; // current time + }; + + virtual Eigen::Matrix updateForcesAndTorques(Current_State x, const int act_cmds[]) = 0; + virtual void set_wind(Eigen::Vector3d wind) = 0; +}; + +} // namespace rosflight_sim + +#endif // ROSFLIGHT_SIM_MAV_FORCES_AND_MOMENTS_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/include/rosflight_sim/multirotor_forces_and_moments.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/include/rosflight_sim/multirotor_forces_and_moments.h new file mode 100644 index 0000000..9a6bc6d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/include/rosflight_sim/multirotor_forces_and_moments.h @@ -0,0 +1,111 @@ +/* + * Copyright (c) 2017 Daniel Koch, James Jackson and Gary Ellingson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_SIM_MULTIROTOR_FORCES_AND_MOMENTS_H +#define ROSFLIGHT_SIM_MULTIROTOR_FORCES_AND_MOMENTS_H + +#include +#include + +#include + +namespace rosflight_sim +{ + +class Multirotor : public MAVForcesAndMoments { +private: + ros::NodeHandle* nh_; + Eigen::Vector3d wind_; + + double prev_time_; + + struct Rotor{ + double max; + std::vector F_poly; + std::vector T_poly; + double tau_up; // time constants for response + double tau_down; + }; + + struct Motor{ + Rotor rotor; + Eigen::Vector3d position; + Eigen::Vector3d normal; + int direction; // 1 for CW -1 for CCW + }; + + int num_rotors_; + std::vector motors_; + + double linear_mu_; + double angular_mu_; + std::vector ground_effect_; + + double mass_; + + // Container for an Actuator + struct Actuator{ + double max; + double tau_up; + double tau_down; + }; + + // Struct of Actuators + // This organizes the physical limitations of the abstract torques and Force + struct Actuators{ + Actuator l; + Actuator m; + Actuator n; + Actuator F; + } actuators_; + + Eigen::MatrixXd rotor_position_; + Eigen::MatrixXd rotor_plane_normal_; + Eigen::VectorXd rotor_rotation_direction_; + + Eigen::MatrixXd force_allocation_matrix_; + Eigen::MatrixXd torque_allocation_matrix_; + Eigen::VectorXd desired_forces_; + Eigen::VectorXd desired_torques_; + Eigen::VectorXd actual_forces_; + Eigen::VectorXd actual_torques_; + +public: + Multirotor(ros::NodeHandle* nh); + ~Multirotor(); + + Eigen::Matrix updateForcesAndTorques(Current_State x, const int act_cmds[]); + void set_wind(Eigen::Vector3d wind); +}; + +} // namespace rosflight_sim + +#endif // ROSFLIGHT_SIM_MULTIROTOR_FORCES_AND_MOMENTS_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/include/rosflight_sim/rosflight_sil.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/include/rosflight_sim/rosflight_sil.h new file mode 100644 index 0000000..24c8507 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/include/rosflight_sim/rosflight_sil.h @@ -0,0 +1,108 @@ +/* + * Copyright (c) 2017 Daniel Koch, James Jackson and Gary Ellingson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_SIM_ROSFLIGHT_SIL_H +#define ROSFLIGHT_SIM_ROSFLIGHT_SIL_H + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +namespace rosflight_sim +{ + +class ROSflightSIL : public gazebo::ModelPlugin +{ +public: + ROSflightSIL(); + ~ROSflightSIL(); + +protected: + void Reset() override; + void Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf) override; + void OnUpdate(const gazebo::common::UpdateInfo &_info); + +private: + void windCallback(const geometry_msgs::Vector3 &msg); + void publishTruth(); + + SIL_Board board_; + rosflight_firmware::ROSflight firmware_; + + std::string mav_type_; + std::string namespace_; + std::string link_name_; + + gazebo::physics::WorldPtr world_; + gazebo::physics::ModelPtr model_; + gazebo::physics::LinkPtr link_; + gazebo::physics::JointPtr joint_; + gazebo::physics::EntityPtr parent_link_; + gazebo::event::ConnectionPtr updateConnection_; // Pointer to the update event connection. + + ros::Subscriber wind_sub_; + ros::Publisher truth_NED_pub_; + ros::Publisher truth_NWU_pub_; + + MAVForcesAndMoments* mav_dynamics_; + + // container for forces + Eigen::Matrix forces_, applied_forces_; + + // Time Counters + uint64_t start_time_us_; + + ros::NodeHandle* nh_; + + // For reset handlin + gazebo::math::Pose initial_pose_; + + // helper functions for converting to and from eigen + Eigen::Vector3d vec3_to_eigen_from_gazebo(gazebo::math::Vector3 vec); + gazebo::math::Vector3 vec3_to_gazebo_from_eigen(Eigen::Vector3d vec); + Eigen::Matrix3d rotation_to_eigen_from_gazebo(gazebo::math::Quaternion vec); + +}; + +} // namespace rosflight_sim + +#endif // ROSFLIGHT_SIM_ROSFLIGHT_SIL_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/include/rosflight_sim/sil_board.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/include/rosflight_sim/sil_board.h new file mode 100644 index 0000000..4372ed6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/include/rosflight_sim/sil_board.h @@ -0,0 +1,183 @@ +/* + * Copyright (c) 2017 Daniel Koch, James Jackson and Gary Ellingson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_SIM_SIL_BOARD_H +#define ROSFLIGHT_SIM_SIL_BOARD_H + +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include + +namespace rosflight_sim +{ + +class SIL_Board : public rosflight_firmware::UDPBoard +{ +private: + gazebo::math::Vector3 inertial_magnetic_field_; + + double imu_update_rate_; + + double gyro_stdev_; + double gyro_bias_walk_stdev_; + double gyro_bias_range_; + + double acc_stdev_; + double acc_bias_range_; + double acc_bias_walk_stdev_; + + double baro_bias_walk_stdev_; + double baro_stdev_; + double baro_bias_range_; + + double mag_bias_walk_stdev_; + double mag_stdev_; + double mag_bias_range_; + + double airspeed_bias_walk_stdev_; + double airspeed_stdev_; + double airspeed_bias_range_; + + double sonar_stdev_; + double sonar_max_range_; + double sonar_min_range_; + + gazebo::math::Vector3 gyro_bias_; + gazebo::math::Vector3 acc_bias_; + gazebo::math::Vector3 mag_bias_; + double baro_bias_; + double airspeed_bias_; + + std::default_random_engine random_generator_; + std::normal_distribution normal_distribution_; + std::uniform_real_distribution uniform_distribution_; + + gazebo::math::Vector3 gravity_; + double ground_altitude_; + + gazebo::physics::WorldPtr world_; + gazebo::physics::ModelPtr model_; + gazebo::physics::LinkPtr link_; + + ros::NodeHandle* nh_; + ros::Subscriber rc_sub_; + rosflight_msgs::RCRaw latestRC_; + bool rc_received_; + + std::string mav_type_; + int pwm_outputs_[14]; //assumes maximum of 14 channels + + // Time variables + double boot_time_; + uint64_t next_imu_update_time_us_; + uint64_t imu_update_period_us_; + + void RCCallback(const rosflight_msgs::RCRaw& msg); + bool motors_spinning(); + + gazebo::math::Vector3 prev_vel_1_; + gazebo::math::Vector3 prev_vel_2_; + gazebo::math::Vector3 prev_vel_3_; + gazebo::common::Time last_time_; + +public: + SIL_Board(); + + // setup + void init_board(void); + void board_reset(bool bootloader); + + // clock + uint32_t clock_millis(); + uint64_t clock_micros(); + void clock_delay(uint32_t milliseconds); + + // sensors + void sensors_init(); + uint16_t num_sensor_errors(void); + + bool new_imu_data(); + bool imu_read(float accel[3], float* temperature, float gyro[3], uint64_t* time_us); + void imu_not_responding_error(); + + bool mag_check(void); + void mag_read(float mag[3]); + + bool baro_check(void); + void baro_read(float *pressure, float *temperature); + + bool diff_pressure_check(void); + void diff_pressure_read(float *diff_pressure, float *temperature); + + bool sonar_check(void); + float sonar_read(void); + + // PWM + // TODO make these deal in normalized (-1 to 1 or 0 to 1) values (not pwm-specific) + void pwm_init(bool cppm, uint32_t refresh_rate, uint16_t idle_pwm); + bool pwm_lost(); + uint16_t pwm_read(uint8_t channel); + void pwm_write(uint8_t channel, uint16_t value); + + // non-volatile memory + void memory_init(void); + bool memory_read(void * dest, size_t len); + bool memory_write(const void * src, size_t len); + + // LEDs + void led0_on(void); + void led0_off(void); + void led0_toggle(void); + + void led1_on(void); + void led1_off(void); + void led1_toggle(void); + + // Gazebo stuff + void gazebo_setup(gazebo::physics::LinkPtr link, gazebo::physics::WorldPtr world, gazebo::physics::ModelPtr model, ros::NodeHandle* nh, std::string mav_type); + inline const int* get_outputs() const { return pwm_outputs_; } + +}; + +} // namespace rosflight_sim + +#endif // ROSFLIGHT_SIM_SIL_BOARD_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/launch/base.launch b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/launch/base.launch new file mode 100644 index 0000000..65e6a67 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/launch/base.launch @@ -0,0 +1,44 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/launch/fixedwing.launch b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/launch/fixedwing.launch new file mode 100644 index 0000000..852f381 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/launch/fixedwing.launch @@ -0,0 +1,29 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/launch/multirotor.launch b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/launch/multirotor.launch new file mode 100644 index 0000000..057894c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/launch/multirotor.launch @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/launch/spawn_mav.launch b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/launch/spawn_mav.launch new file mode 100644 index 0000000..7d5046e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/launch/spawn_mav.launch @@ -0,0 +1,43 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/package.xml new file mode 100644 index 0000000..5e59d30 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/package.xml @@ -0,0 +1,35 @@ + + + rosflight_sim + 0.1.3 + Software-in-the-loop (SIL) simulator for the ROSflight firmware + + James Jackson + + James Jackson + Gary Ellingson + Daniel Koch + + BSD + + http://rosflight.org + https://github.com/rosflight/rosflight + https://github.com/rosflight/rosflight/issues + + catkin + + gazebo_plugins + gazebo_ros + geometry_msgs + roscpp + rosflight_firmware + rosflight_msgs + + eigen + gazebo + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/params/fixedwing.yaml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/params/fixedwing.yaml new file mode 100644 index 0000000..3d8c02d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/params/fixedwing.yaml @@ -0,0 +1,91 @@ +# Based on My Twin Dream parameters +mass: 3.92 + +Jx: 0.213 +Jy: 0.171 +Jz: 0.350 +Jxz: 0.04 + +rho: 1.2682 +wing_s: 0.468 +wing_b: 1.8 +wing_c: 0.26 +wing_M: 50 +wing_epsilon: 0.1592 +wing_alpha0: 0.3040363557 + +k_motor: 40.0 +k_T_P: 0.0 +k_Omega: 0.0 + +prop_e: 0.8 +prop_S: 0.0314 +prop_C: 1.0 + +C_L_O: 0.2869 +C_L_alpha: 5.1378 +C_L_beta: 0.0 +C_L_p: 0.0 +C_L_q: 1.7102 +C_L_r: 0.0 +C_L_delta_a: 0.0 +C_L_delta_e: 0.5202 +C_L_delta_r: 0.0 + +C_D_O: 0.03087 +C_D_alpha: 0.0043021 +C_D_beta: 0.0 +C_D_p: 0.02815 +C_D_q: 0.2514 +C_D_r: 0.0 +C_D_delta_a: 0.0 +C_D_delta_e: 0.01879 +C_D_delta_r: 0.0 + +C_ell_O: 0.0 +C_ell_alpha: 0.00 +C_ell_beta: 0.0193 +C_ell_p: -0.5406 +C_ell_q: 0.0 +C_ell_r: 0.1929 +C_ell_delta_a: 0.2818 +C_ell_delta_e: 0.0 +C_ell_delta_r: 0.00096 + +C_m_O: 0.0362 +C_m_alpha: -0.2627 +C_m_beta: 0.0 +C_m_p: 0.0 +C_m_q: -9.7213 +C_m_r: 0.0 +C_m_delta_a: 0.0 +C_m_delta_e: -1.2392 +C_m_delta_r: 0.0 + +C_n_O: 0.0 +C_n_alpha: 0.0 +C_n_beta: 0.08557 +C_n_p: -0.0498 +C_n_q: 0.0 +C_n_r: -0.0572 +C_n_delta_a: 0.0095 +C_n_delta_e: 0.0 +C_n_delta_r: -0.06 + +C_Y_O: 0.0 +C_Y_alpha: 0.00 +C_Y_beta: -0.2471 +C_Y_p: -0.07278 +C_Y_q: 0.0 +C_Y_r: 0.1849 +C_Y_delta_a: -0.02344 +C_Y_delta_e: 0.0 +C_Y_delta_r: 0.1591 + +# trim conditions +phi0: 0 +theta0: 0.0349 # 2 degrees +psi0: 0 +Va0: 16.38 +delta_e0: 0.02967 # 1.7 degrees +delta_t0: 0.4 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/params/multirotor.yaml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/params/multirotor.yaml new file mode 100644 index 0000000..8979382 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/params/multirotor.yaml @@ -0,0 +1,65 @@ +# Parameters for ROSflight software-in-the-loop simulation + +# Common Global Physical Parameters + +mass: 2.0 +linear_mu: 0.05 +angular_mu: 0.0005 +ground_effect: [-55.3516, 181.8265, -203.9874, 85.3735, -7.6619] + +# Dynamics +num_rotors: 4 +rotor_positions: [ 0.1926, 0.230, -0.0762, + -0.1907, 0.205, -0.0762, + -0.1907, -0.205, -0.0762, + 0.1926, -0.230, -0.0762] + +rotor_vector_normal: [-0.02674078, 0.0223925, -0.99939157, + 0.02553726, 0.02375588, -0.99939157, + 0.02553726, -0.02375588, -0.99939157, + -0.02674078, -0.0223925, -0.99939157] + +rotor_rotation_directions: [-1, 1, -1, 1] +rotor_max_thrust: 14.961 +rotor_F: [1.5e-5, -0.024451, 9.00225] +rotor_T: [2.22e-7,-3.51e-4, 0.12531] +rotor_tau_up: 0.2164 +rotor_tau_down: 0.1644 + +ground_altitude: 1387 #Default in Provo, UT (4551 ft) + +# Sensor Noise Parameters (These are empirically-determined) +# gyro_stdev: 0.25 +# gyro_bias_range: 0.25 +# gyro_bias_walk_stdev: 0.00001 +gyro_stdev: 0.0 +gyro_bias_range: 0.0 +gyro_bias_walk_stdev: 0.00000 + +# acc_stdev: 0.561 +# acc_bias_range: 0.6 +# acc_bias_walk_stdev: 0.00001 + +acc_stdev: 0.0 +acc_bias_range: 0.0 +acc_bias_walk_stdev: 0.00000 + +baro_stdev: 4.0 +baro_bias_range: 500 +baro_bias_walk_stdev: 0.1 + +sonar_stdev: 0.03 +sonar_min_range: 0.25 +sonar_max_range: 8.0 + +# TODO: update these with empirically-derived values +airspeed_stdev: 1.15 +airspeed_bias_range: 0.15 +airspeed_bias_walk_stdev: 0.001 + +mag_stdev: 1.15 +mag_bias_range: 0.15 +mag_bias_walk_stdev: 0.001 + +inclination: 1.14316156541 +declination: 0.198584539676 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/src/fixedwing_forces_and_moments.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/src/fixedwing_forces_and_moments.cpp new file mode 100644 index 0000000..dd4ee3d --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/src/fixedwing_forces_and_moments.cpp @@ -0,0 +1,210 @@ +/* + * Copyright (c) 2017 Daniel Koch, James Jackson and Gary Ellingson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +namespace rosflight_sim +{ + +Fixedwing::Fixedwing(ros::NodeHandle* nh) +{ + nh_ = nh; + + // physical parameters + mass_ = nh_->param("mass", 13.5); + Jx_ = nh_->param("Jx", 0.8244); + Jy_ = nh_->param("Jy", 1.135); + Jz_ = nh_->param("Jz", 1.759); + Jxz_ = nh_->param("Jxz", .1204); + rho_ = nh_->param("rho", 1.2682); + + // Wing Geometry + wing_.S = nh_->param("wing_s", 0.55); + wing_.b = nh_->param("wing_b", 2.8956); + wing_.c = nh_->param("wing_c", 0.18994); + wing_.M = nh_->param("wing_M", 0.55); + wing_.epsilon = nh_->param("wing_epsilon", 2.8956); + wing_.alpha0 = nh_->param("wing_alpha0", 0.18994); + + // Propeller Coefficients + prop_.k_motor = nh_->param("k_motor", 80.0); + prop_.k_T_P = nh_->param("k_T_P", 0.0); + prop_.k_Omega = nh_->param("k_Omega", 0.0); + prop_.e = nh_->param("prop_e", 0.9); + prop_.S = nh_->param("prop_S", 0.202); + prop_.C = nh_->param("prop_C", 1.0); + + // Lift Params + CL_.O = nh_->param("C_L_O", 0.28); + CL_.alpha = nh_->param("C_L_alpha", 3.45); + CL_.beta = nh_->param("C_L_beta", 0.0); + CL_.p = nh_->param("C_L_p", 0.0); + CL_.q = nh_->param("C_L_q", 0.0); + CL_.r = nh_->param("C_L_r", 0.0); + CL_.delta_a = nh_->param("C_L_delta_a", 0.0); + CL_.delta_e = nh_->param("C_L_delta_e", -0.36); + CL_.delta_r = nh_->param("C_L_delta_r", 0.0); + + // Drag Params + CD_.O = nh_->param("C_D_O", 0.03); + CD_.alpha = nh_->param("C_D_alpha", 0.30); + CD_.beta = nh_->param("C_D_beta", 0.0); + CD_.p = nh_->param("C_D_p", 0.0437); + CD_.q = nh_->param("C_D_q", 0.0); + CD_.r = nh_->param("C_D_r", 0.0); + CD_.delta_a = nh_->param("C_D_delta_a", 0.0); + CD_.delta_e = nh_->param("C_D_delta_e", 0.0); + CD_.delta_r = nh_->param("C_D_delta_r", 0.0); + + // ell Params (x axis moment) + Cell_.O = nh_->param("C_ell_O", 0.0); + Cell_.alpha = nh_->param("C_ell_alpha", 0.00); + Cell_.beta = nh_->param("C_ell_beta", -0.12); + Cell_.p = nh_->param("C_ell_p", -0.26); + Cell_.q = nh_->param("C_ell_q", 0.0); + Cell_.r = nh_->param("C_ell_r", 0.14); + Cell_.delta_a = nh_->param("C_ell_delta_a", 0.08); + Cell_.delta_e = nh_->param("C_ell_delta_e", 0.0); + Cell_.delta_r = nh_->param("C_ell_delta_r", 0.105); + + // m Params (y axis moment) + Cm_.O = nh_->param("C_m_O", -0.02338); + Cm_.alpha = nh_->param("C_m_alpha", -0.38); + Cm_.beta = nh_->param("C_m_beta", 0.0); + Cm_.p = nh_->param("C_m_p", 0.0); + Cm_.q = nh_->param("C_m_q", -3.6); + Cm_.r = nh_->param("C_m_r", 0.0); + Cm_.delta_a = nh_->param("C_m_delta_a", 0.0); + Cm_.delta_e = nh_->param("C_m_delta_e", -0.5); + Cm_.delta_r = nh_->param("C_m_delta_r", 0.0); + + // n Params (z axis moment) + Cn_.O = nh_->param("C_n_O", 0.0); + Cn_.alpha = nh_->param("C_n_alpha", 0.0); + Cn_.beta = nh_->param("C_n_beta", 0.25); + Cn_.p = nh_->param("C_n_p", 0.022); + Cn_.q = nh_->param("C_n_q", 0.0); + Cn_.r = nh_->param("C_n_r", -0.35); + Cn_.delta_a = nh_->param("C_n_delta_a", 0.06); + Cn_.delta_e = nh_->param("C_n_delta_e", 0.0); + Cn_.delta_r = nh_->param("C_n_delta_r", -0.032); + + // Y Params (Sideslip Forces) + CY_.O = nh_->param("C_Y_O", 0.0); + CY_.alpha = nh_->param("C_Y_alpha", 0.00); + CY_.beta = nh_->param("C_Y_beta", -0.98); + CY_.p = nh_->param("C_Y_p", 0.0); + CY_.q = nh_->param("C_Y_q", 0.0); + CY_.r = nh_->param("C_Y_r", 0.0); + CY_.delta_a = nh_->param("C_Y_delta_a", 0.0); + CY_.delta_e = nh_->param("C_Y_delta_e", 0.0); + CY_.delta_r = nh_->param("C_Y_delta_r", -0.017); + + wind_ = Eigen::Vector3d::Zero(); +} + +Eigen::Matrix Fixedwing::updateForcesAndTorques(Current_State x, const int act_cmds[]) +{ + delta_.a = (act_cmds[0] - 1500.0)/500.0; + delta_.e = -(act_cmds[1] - 1500.0)/500.0; + delta_.t = (act_cmds[2] - 1000.0)/1000.0; + delta_.r = -(act_cmds[3] - 1500.0)/500.0; + + double p = x.omega(0); + double q = x.omega(1); + double r = x.omega(2); + + // Calculate airspeed + Eigen::Vector3d V_airspeed = x.vel + x.rot.inverse()*wind_; + double ur = V_airspeed(0); + double vr = V_airspeed(1); + double wr = V_airspeed(2); + + double Va = V_airspeed.norm(); + + Eigen::Matrix forces; + + // Be sure that we have some significant airspeed before we run aerodynamics, and don't let NaNs get through + if(Va > 1.0 && std::isfinite(Va)) + { + /* + * The following math follows the method described in chapter 4 of + * Small Unmanned Aircraft: Theory and Practice + * By Randy Beard and Tim McLain. + * Look there for a detailed explanation of each line in the rest of this function + */ + double alpha = atan2(wr , ur); + double beta = asin(vr/Va); + + double ca = cos(alpha); + double sa = sin(alpha); + + double sign = (alpha >= 0? 1: -1);//Sigmoid function + double sigma_a = (1 + exp(-(wing_.M*(alpha - wing_.alpha0))) + exp((wing_.M*(alpha + wing_.alpha0))))/((1 + exp(-(wing_.M*(alpha - wing_.alpha0))))*(1 + exp((wing_.M*(alpha + wing_.alpha0))))); + double CL_a = (1 - sigma_a)*(CL_.O + CL_.alpha*alpha) + sigma_a*(2*sign*sa*sa*ca); + double AR = (pow(wing_.b, 2.0))/wing_.S; + double CD_a = CD_.p + ((pow((CL_.O + CL_.alpha*(alpha)),2.0))/(3.14159*0.9*AR));//the const 0.9 in this equation replaces the e (Oswald Factor) variable and may be inaccurate + + double CX_a = -CD_a*ca + CL_a*sa; + double CX_q_a = -CD_.q*ca + CL_.q*sa; + double CX_deltaE_a = -CD_.delta_e*ca + CL_.delta_e*sa; + + double CZ_a = -CD_a*sa - CL_a*ca; + double CZ_q_a = -CD_.q*sa - CL_.q*ca; + double CZ_deltaE_a = -CD_.delta_e*sa - CL_.delta_e*ca; + + forces(0) = 0.5*(rho_)*Va*Va*wing_.S*(CX_a + (CX_q_a*wing_.c*q)/(2.0*Va) + CX_deltaE_a * delta_.e) + 0.5*rho_*prop_.S*prop_.C*(pow((prop_.k_motor*delta_.t),2.0) - Va*Va); + forces(1) = 0.5*(rho_)*Va*Va*wing_.S*(CY_.O + CY_.beta*beta + ((CY_.p*wing_.b*p)/(2.0*Va)) + ((CY_.r*wing_.b*r)/(2.0*Va)) + CY_.delta_a*delta_.a + CY_.delta_r*delta_.r); + forces(2) = 0.5*(rho_)*Va*Va*wing_.S*(CZ_a + (CZ_q_a*wing_.c*q)/(2.0*Va) + CZ_deltaE_a * delta_.e); + + forces(3) = 0.5*(rho_)*Va*Va*wing_.S*wing_.b*(Cell_.O + Cell_.beta*beta + (Cell_.p*wing_.b*p)/(2.0*Va) + (Cell_.r*wing_.b*r)/(2.0*Va) + Cell_.delta_a*delta_.a + Cell_.delta_r*delta_.r) - prop_.k_T_P*pow((prop_.k_Omega*delta_.t),2.0); + forces(4) = 0.5*(rho_)*Va*Va*wing_.S*wing_.c*(Cm_.O + Cm_.alpha*alpha + (Cm_.q*wing_.c*q)/(2.0*Va) + Cm_.delta_e*delta_.e); + forces(5) = 0.5*(rho_)*Va*Va*wing_.S*wing_.b*(Cn_.O + Cn_.beta*beta + (Cn_.p*wing_.b*p)/(2.0*Va) + (Cn_.r*wing_.b*r)/(2.0*Va) + Cn_.delta_a*delta_.a + Cn_.delta_r*delta_.r); + } + else + { + forces(0) = 0.5*rho_*prop_.S*prop_.C*((prop_.k_motor*delta_.t*prop_.k_motor*delta_.t)); + forces(1) = 0.0; + forces(2) = 0.0; + forces(3) = 0.0; + forces(4) = 0.0; + forces(5) = 0.0; + } + + return forces; +} + +void Fixedwing::set_wind(Eigen::Vector3d wind) +{ + wind_ = wind; +} + +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/src/multirotor_forces_and_moments.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/src/multirotor_forces_and_moments.cpp new file mode 100644 index 0000000..77839e6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/src/multirotor_forces_and_moments.cpp @@ -0,0 +1,173 @@ +/* + * Copyright (c) 2017 Daniel Koch, James Jackson and Gary Ellingson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +namespace rosflight_sim +{ + +Multirotor::Multirotor(ros::NodeHandle *nh) +{ + nh_ = nh; + + // Pull Parameters off of rosparam server + num_rotors_ = 0; + ROS_ASSERT_MSG(nh_->getParam("ground_effect", ground_effect_), "missing parameters in %s namespace", nh_->getNamespace().c_str()); + ROS_ASSERT(nh_->getParam("mass", mass_)); + ROS_ASSERT(nh_->getParam("linear_mu", linear_mu_)); + ROS_ASSERT(nh_->getParam("angular_mu", angular_mu_)); + ROS_ASSERT(nh_->getParam("num_rotors", num_rotors_)); + + std::vector rotor_positions(3 * num_rotors_); + std::vector rotor_vector_normal(3 * num_rotors_); + std::vector rotor_rotation_directions(num_rotors_); + + // For now, just assume all rotors are the same + Rotor rotor; + + ROS_ASSERT(nh_->getParam("rotor_positions", rotor_positions)); + ROS_ASSERT(nh_->getParam("rotor_vector_normal", rotor_vector_normal)); + ROS_ASSERT(nh_->getParam("rotor_rotation_directions", rotor_rotation_directions)); + ROS_ASSERT(nh_->getParam("rotor_max_thrust", rotor.max)); + ROS_ASSERT(nh_->getParam("rotor_F", rotor.F_poly)); + ROS_ASSERT(nh_->getParam("rotor_T", rotor.T_poly)); + ROS_ASSERT(nh_->getParam("rotor_tau_up", rotor.tau_up)); + ROS_ASSERT(nh_->getParam("rotor_tau_down", rotor.tau_down)); + + /* Load Rotor Configuration */ + motors_.resize(num_rotors_); + + force_allocation_matrix_.resize(4,num_rotors_); + torque_allocation_matrix_.resize(4,num_rotors_); + for(int i = 0; i < num_rotors_; i++) + { + motors_[i].rotor = rotor; + motors_[i].position.resize(3); + motors_[i].normal.resize(3); + for (int j = 0; j < 3; j++) + { + motors_[i].position(j) = rotor_positions[3*i + j]; + motors_[i].normal(j) = rotor_vector_normal[3*i + j]; + } + motors_[i].normal.normalize(); + motors_[i].direction = rotor_rotation_directions[i]; + + Eigen::Vector3d moment_from_thrust = motors_[i].position.cross(motors_[i].normal); + Eigen::Vector3d moment_from_torque = motors_[i].direction * motors_[i].normal; + + // build allocation_matrices + force_allocation_matrix_(0,i) = moment_from_thrust(0); // l + force_allocation_matrix_(1,i) = moment_from_thrust(1); // m + force_allocation_matrix_(2,i) = moment_from_thrust(2); // n + force_allocation_matrix_(3,i) = motors_[i].normal(2); // F + + torque_allocation_matrix_(0,i) = moment_from_torque(0); // l + torque_allocation_matrix_(1,i) = moment_from_torque(1); // m + torque_allocation_matrix_(2,i) = moment_from_torque(2); // n + torque_allocation_matrix_(3,i) = 0.0; // F + } + + ROS_INFO_STREAM("allocation matrices:\nFORCE \n" << force_allocation_matrix_ << "\nTORQUE\n" << torque_allocation_matrix_ << "\n"); + + // Initialize size of dynamic force and torque matrices + desired_forces_.resize(num_rotors_); + desired_torques_.resize(num_rotors_); + actual_forces_.resize(num_rotors_); + actual_torques_.resize(num_rotors_); + + for (int i = 0; i < num_rotors_; i++) + { + desired_forces_(i)=0.0; + desired_torques_(i)=0.0; + actual_forces_(i)=0.0; + actual_torques_(i)=0.0; + } + + wind_ = Eigen::Vector3d::Zero(); + prev_time_ = -1; +} + +Eigen::Matrix Multirotor::updateForcesAndTorques(Current_State x, const int act_cmds[]) +{ + if (prev_time_ < 0) + { + prev_time_ = x.t; + return Eigen::Matrix::Zero(); + } + + double dt = x.t - prev_time_; + double pd = x.pos[2]; + + // Get airspeed vector for drag force calculation (rotate wind into body frame and add to inertial velocity) + Eigen::Vector3d Va = x.vel + x.rot.inverse()*wind_; + + // Calculate Forces + for (int i = 0; i actual_forces_(i,0)) ? motors_[i].rotor.tau_up : motors_[i].rotor.tau_down; + double alpha = dt/(tau + dt); + actual_forces_(i,0) = sat((1-alpha)*actual_forces_(i) + alpha*desired_forces_(i), motors_[i].rotor.max, 0.0); + actual_torques_(i,0) = sat((1-alpha)*actual_torques_(i) + alpha*desired_torques_(i), motors_[i].rotor.max, 0.0); + } + + // Use the allocation matrix to calculate the body-fixed force and torques + Eigen::Vector4d output_forces = force_allocation_matrix_*actual_forces_; + Eigen::Vector4d output_torques = torque_allocation_matrix_*actual_torques_; + Eigen::Vector4d output_forces_and_torques = output_forces + output_torques; + + // Calculate Ground Effect + double z = -pd; + double ground_effect = max(ground_effect_[0]*z*z*z*z + ground_effect_[1]*z*z*z + ground_effect_[2]*z*z + ground_effect_[3]*z + ground_effect_[4], 0); + + Eigen::Matrix forces; + // Apply other forces (drag) <- follows "Quadrotors and Accelerometers - State Estimation With an Improved Dynamic Model" + // By Rob Leishman et al. + forces.block<3,1>(3,0) = -linear_mu_ * Va; + forces.block<3,1>(3,0) = -angular_mu_ * x.omega + output_forces_and_torques.block<3,1>(0,0); + + // Apply ground effect and thrust + forces(2) += output_forces_and_torques(3) - ground_effect; + + return forces; +} + +void Multirotor::set_wind(Eigen::Vector3d wind) +{ + wind_ = wind; +} + +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/src/rosflight_sil.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/src/rosflight_sil.cpp new file mode 100644 index 0000000..1815597 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/src/rosflight_sil.cpp @@ -0,0 +1,232 @@ +/* + * Copyright (c) 2017 Daniel Koch, James Jackson and Gary Ellingson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#pragma GCC diagnostic ignored "-Wwrite-strings" + +#include +#include +#include + +#include + +#include +#include + + +namespace rosflight_sim +{ + +ROSflightSIL::ROSflightSIL() : + gazebo::ModelPlugin(), + nh_(nullptr), + firmware_(board_) +{} + +ROSflightSIL::~ROSflightSIL() +{ + gazebo::event::Events::DisconnectWorldUpdateBegin(updateConnection_); + if (nh_) { + nh_->shutdown(); + delete nh_; + } +} + +void ROSflightSIL::Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf) +{ + if (!ros::isInitialized()) + { + ROS_FATAL("A ROS node for Gazebo has not been initialized, unable to load plugin"); + return; + } + ROS_INFO("Loaded the ROSflight SIL plugin"); + + model_ = _model; + world_ = model_->GetWorld(); + + namespace_.clear(); + + /* + * Connect the Plugin to the Robot and Save pointers to the various elements in the simulation + */ + if (_sdf->HasElement("namespace")) + namespace_ = _sdf->GetElement("namespace")->Get(); + else + gzerr << "[ROSflight_SIL] Please specify a namespace.\n"; + nh_ = new ros::NodeHandle(namespace_); + + gzmsg << "loading parameters from " << namespace_ << " ns\n"; + + if (_sdf->HasElement("linkName")) + link_name_ = _sdf->GetElement("linkName")->Get(); + else + gzerr << "[ROSflight_SIL] Please specify a linkName of the forces and moments plugin.\n"; + link_ = model_->GetLink(link_name_); + if (link_ == NULL) + gzthrow("[ROSflight_SIL] Couldn't find specified link \"" << link_name_ << "\"."); + + /* Load Params from Gazebo Server */ + if (_sdf->HasElement("mavType")) { + mav_type_ = _sdf->GetElement("mavType")->Get(); + } + else { + mav_type_ = "multirotor"; + gzerr << "[rosflight_sim] Please specify a value for parameter \"mavType\".\n"; + } + + if(mav_type_ == "multirotor") + mav_dynamics_ = new Multirotor(nh_); + else if(mav_type_ == "fixedwing") + mav_dynamics_ = new Fixedwing(nh_); + else + gzthrow("unknown or unsupported mav type\n"); + + // Initialize the Firmware + board_.gazebo_setup(link_, world_, model_, nh_, mav_type_); + firmware_.init(); + + // Connect the update function to the simulation + updateConnection_ = gazebo::event::Events::ConnectWorldUpdateBegin(boost::bind(&ROSflightSIL::OnUpdate, this, _1)); + + initial_pose_ = link_->GetWorldCoGPose(); + + truth_NED_pub_ = nh_->advertise("truth/NED", 1); + truth_NWU_pub_ = nh_->advertise("truth/NWU", 1); +} + + +// This gets called by the world update event. +void ROSflightSIL::OnUpdate(const gazebo::common::UpdateInfo& _info) +{ + // We run twice so that that functions that take place when we don't have new IMU data get run + firmware_.run(); + firmware_.run(); + Eigen::Matrix3d NWU_to_NED; + NWU_to_NED << 1, 0, 0, 0, -1, 0, 0, 0, -1; + + MAVForcesAndMoments::Current_State state; + gazebo::math::Pose pose = link_->GetWorldCoGPose(); + gazebo::math::Vector3 vel = link_->GetRelativeLinearVel(); + gazebo::math::Vector3 omega = link_->GetRelativeAngularVel(); + + // Convert gazebo types to Eigen and switch to NED frame + state.pos = NWU_to_NED * vec3_to_eigen_from_gazebo(pose.pos) ; + state.rot = NWU_to_NED * rotation_to_eigen_from_gazebo(pose.rot); + state.vel = NWU_to_NED * vec3_to_eigen_from_gazebo(vel); + state.omega = NWU_to_NED * vec3_to_eigen_from_gazebo(omega); + state.t = _info.simTime.Double(); + + forces_ = mav_dynamics_->updateForcesAndTorques(state, board_.get_outputs()); + + // apply the forces and torques to the joint (apply in NWU) + gazebo::math::Vector3 force = vec3_to_gazebo_from_eigen(NWU_to_NED * forces_.block<3,1>(0,0)); + gazebo::math::Vector3 torque = vec3_to_gazebo_from_eigen(NWU_to_NED * forces_.block<3,1>(3,0)); + link_->AddRelativeForce(force); + link_->AddRelativeTorque(torque); + + publishTruth(); + +} + +void ROSflightSIL::Reset() +{ + link_->SetWorldPose(initial_pose_); + link_->ResetPhysicsStates(); +// start_time_us_ = (uint64_t)(world_->GetSimTime().Double() * 1e3); +// rosflight_init(); +} + +void ROSflightSIL::windCallback(const geometry_msgs::Vector3 &msg) +{ + Eigen::Vector3d wind; + wind << msg.x, msg.y, msg.z; + mav_dynamics_->set_wind(wind); +} + +void ROSflightSIL::publishTruth() +{ + gazebo::math::Pose pose = link_->GetWorldCoGPose(); + gazebo::math::Vector3 vel = link_->GetRelativeLinearVel(); + gazebo::math::Vector3 omega = link_->GetRelativeAngularVel(); + + // Publish truth + nav_msgs::Odometry truth; + truth.header.stamp.sec = world_->GetSimTime().sec; + truth.header.stamp.nsec = world_->GetSimTime().nsec; + truth.header.frame_id = link_name_ + "_NWU"; + truth.pose.pose.orientation.w = pose.rot.w; + truth.pose.pose.orientation.x = pose.rot.x; + truth.pose.pose.orientation.y = pose.rot.y; + truth.pose.pose.orientation.z = pose.rot.z; + truth.pose.pose.position.x = pose.pos.x; + truth.pose.pose.position.y = pose.pos.y; + truth.pose.pose.position.z = pose.pos.z; + truth.twist.twist.linear.x = vel.x; + truth.twist.twist.linear.y = vel.y; + truth.twist.twist.linear.z = vel.z; + truth.twist.twist.angular.x = omega.x; + truth.twist.twist.angular.y = omega.y; + truth.twist.twist.angular.z = omega.z; + truth_NWU_pub_.publish(truth); + + // Convert to NED + truth.header.frame_id = link_name_ + "_NED"; + truth.pose.pose.orientation.y *= -1.0; + truth.pose.pose.orientation.z *= -1.0; + truth.pose.pose.position.y *= -1.0; + truth.pose.pose.position.z *= -1.0; + truth.twist.twist.linear.y *= -1.0; + truth.twist.twist.linear.z *= -1.0; + truth.twist.twist.angular.y *= -1.0; + truth.twist.twist.angular.z *= -1.0; + truth_NED_pub_.publish(truth); +} + +Eigen::Vector3d ROSflightSIL::vec3_to_eigen_from_gazebo(gazebo::math::Vector3 vec) +{ + Eigen::Vector3d out; + out << vec.x, vec.y, vec.z; + return out; +} + +gazebo::math::Vector3 ROSflightSIL::vec3_to_gazebo_from_eigen(Eigen::Vector3d vec) +{ + gazebo::math::Vector3 out(vec(0), vec(1), vec(2)); + return out; +} + +Eigen::Matrix3d ROSflightSIL::rotation_to_eigen_from_gazebo(gazebo::math::Quaternion quat) +{ + Eigen::Quaterniond eig_quat(quat.w, quat.x, quat.y, quat.z); + return eig_quat.toRotationMatrix(); +} + +GZ_REGISTER_MODEL_PLUGIN(ROSflightSIL) +} // namespace rosflight_sim diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/src/sil_board.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/src/sil_board.cpp new file mode 100644 index 0000000..053156b --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/src/sil_board.cpp @@ -0,0 +1,471 @@ +/* + * Copyright (c) 2017 Daniel Koch, James Jackson and Gary Ellingson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +#include + +namespace rosflight_sim { + +SIL_Board::SIL_Board() : + rosflight_firmware::UDPBoard() +{ } + +void SIL_Board::init_board(void) +{ + boot_time_ = world_->GetSimTime().Double(); +} + +void SIL_Board::gazebo_setup(gazebo::physics::LinkPtr link, gazebo::physics::WorldPtr world, + gazebo::physics::ModelPtr model, ros::NodeHandle* nh, std::string mav_type) +{ + link_ = link; + world_ = world; + model_ = model; + nh_ = nh; + mav_type_ = mav_type; + + + std::string bind_host = nh->param("gazebo_host", "localhost"); + int bind_port = nh->param("gazebo_port", 14525); + std::string remote_host = nh->param("ROS_host", "localhost"); + int remote_port = nh->param("ROS_port", 14520); + + set_ports(bind_host, bind_port, remote_host, remote_port); + + // Get Sensor Parameters + gyro_stdev_ = nh->param("gyro_stdev", 0.13); + gyro_bias_range_ = nh->param("gyro_bias_range", 0.15); + gyro_bias_walk_stdev_ = nh->param("gyro_bias_walk_stdev", 0.001); + + acc_stdev_ = nh->param("acc_stdev", 1.15); + acc_bias_range_ = nh->param("acc_bias_range", 0.15); + acc_bias_walk_stdev_ = nh->param("acc_bias_walk_stdev", 0.001); + + mag_stdev_ = nh->param("mag_stdev", 1.15); + mag_bias_range_ = nh->param("mag_bias_range", 0.15); + mag_bias_walk_stdev_ = nh->param("mag_bias_walk_stdev", 0.001); + + baro_stdev_ = nh->param("baro_stdev", 1.15); + baro_bias_range_ = nh->param("baro_bias_range", 0.15); + baro_bias_walk_stdev_ = nh->param("baro_bias_walk_stdev", 0.001); + + airspeed_stdev_ = nh_->param("airspeed_stdev", 1.15); + airspeed_bias_range_ = nh_->param("airspeed_bias_range", 0.15); + airspeed_bias_walk_stdev_ = nh_->param("airspeed_bias_walk_stdev", 0.001); + + sonar_stdev_ = nh_->param("sonar_stdev", 1.15); + sonar_min_range_ = nh_->param("sonar_min_range", 0.25); + sonar_max_range_ = nh_->param("sonar_max_range", 8.0); + + imu_update_rate_ = nh_->param("imu_update_rate", 1000.0); + imu_update_period_us_ = (uint64_t)(1e6/imu_update_rate_); + + // Calculate Magnetic Field Vector (for mag simulation) + double inclination = nh_->param("inclination", 1.14316156541); + double declination = nh_->param("declination", 0.198584539676); + inertial_magnetic_field_.z = sin(-inclination); + inertial_magnetic_field_.x = cos(-inclination)*cos(-declination); + inertial_magnetic_field_.y = cos(-inclination)*sin(-declination); + + // Get the desired altitude at the ground (for baro simulation) + ground_altitude_ = nh->param("ground_altitude", 1387.0); + + // Configure Noise + random_generator_= std::default_random_engine(std::chrono::system_clock::now().time_since_epoch().count()); + normal_distribution_ = std::normal_distribution(0.0, 1.0); + uniform_distribution_ = std::uniform_real_distribution(-1.0, 1.0); + + gravity_ = world_->GetPhysicsEngine()->GetGravity(); + + // Initialize the Sensor Biases + gyro_bias_.x = gyro_bias_range_*uniform_distribution_(random_generator_); + gyro_bias_.y = gyro_bias_range_*uniform_distribution_(random_generator_); + gyro_bias_.z = gyro_bias_range_*uniform_distribution_(random_generator_); + acc_bias_.x = acc_bias_range_*uniform_distribution_(random_generator_); + acc_bias_.y = acc_bias_range_*uniform_distribution_(random_generator_); + acc_bias_.z = acc_bias_range_*uniform_distribution_(random_generator_); + mag_bias_.x = mag_bias_range_*uniform_distribution_(random_generator_); + mag_bias_.y = mag_bias_range_*uniform_distribution_(random_generator_); + mag_bias_.z = mag_bias_range_*uniform_distribution_(random_generator_); + baro_bias_ = baro_bias_range_*uniform_distribution_(random_generator_); + airspeed_bias_ = airspeed_bias_range_*uniform_distribution_(random_generator_); + + prev_vel_1_ = link_->GetRelativeLinearVel(); + prev_vel_2_ = link_->GetRelativeLinearVel(); + prev_vel_3_ = link_->GetRelativeLinearVel(); + last_time_ = world_->GetSimTime(); + next_imu_update_time_us_ = 0; +} + +void SIL_Board::board_reset(bool bootloader) +{ +} + +// clock + +uint32_t SIL_Board::clock_millis() +{ + return (uint32_t)((world_->GetSimTime().Double() - boot_time_)*1e3); +} + +uint64_t SIL_Board::clock_micros() +{ + return (uint64_t)((world_->GetSimTime().Double() - boot_time_)*1e6); +} + +void SIL_Board::clock_delay(uint32_t milliseconds) +{ +} + +// sensors +/// TODO these sensors have noise, no bias +/// noise params are hard coded +void SIL_Board::sensors_init() +{ + // Initialize the Biases + gyro_bias_.x = gyro_bias_range_*uniform_distribution_(random_generator_); + gyro_bias_.y = gyro_bias_range_*uniform_distribution_(random_generator_); + gyro_bias_.z = gyro_bias_range_*uniform_distribution_(random_generator_); + acc_bias_.x = acc_bias_range_*uniform_distribution_(random_generator_); + acc_bias_.y = acc_bias_range_*uniform_distribution_(random_generator_); + acc_bias_.z = acc_bias_range_*uniform_distribution_(random_generator_); + + // Gazebo coordinates is NWU and Earth's magnetic field is defined in NED, hence the negative signs + double inclination_ = 1.14316156541; + double declination_ = 0.198584539676; + inertial_magnetic_field_.z = sin(-inclination_); + inertial_magnetic_field_.x = cos(-inclination_)*cos(-declination_); + inertial_magnetic_field_.y = cos(-inclination_)*sin(-declination_); +} + +uint16_t SIL_Board::num_sensor_errors(void) +{ + return 0; +} + +bool SIL_Board::new_imu_data() +{ + uint64_t now_us = clock_micros(); + if (now_us >= next_imu_update_time_us_) + { + next_imu_update_time_us_ = now_us + imu_update_period_us_; + return true; + } + else + { + return false; + } +} + +bool SIL_Board::imu_read(float accel[3], float* temperature, float gyro[3], uint64_t* time_us) +{ + gazebo::math::Quaternion q_I_NWU = link_->GetWorldPose().rot; + gazebo::math::Vector3 current_vel = link_->GetRelativeLinearVel(); + gazebo::math::Vector3 y_acc; + + // this is James' egregious hack to overcome wild imu while sitting on the ground + if (current_vel.GetLength() < 0.05) + y_acc = q_I_NWU.RotateVectorReverse(-gravity_); + else + y_acc = q_I_NWU.RotateVectorReverse(link_->GetWorldLinearAccel() - gravity_); + + // Apply normal noise (only if armed, because most of the noise comes from motors + if (motors_spinning()) + { + y_acc.x += acc_stdev_*normal_distribution_(random_generator_); + y_acc.y += acc_stdev_*normal_distribution_(random_generator_); + y_acc.z += acc_stdev_*normal_distribution_(random_generator_); + } + + // Perform Random Walk for biases + acc_bias_.x += acc_bias_walk_stdev_*normal_distribution_(random_generator_); + acc_bias_.y += acc_bias_walk_stdev_*normal_distribution_(random_generator_); + acc_bias_.z += acc_bias_walk_stdev_*normal_distribution_(random_generator_); + + // Add constant Bias to measurement + y_acc.x += acc_bias_.x; + y_acc.y += acc_bias_.y; + y_acc.z += acc_bias_.z; + + // Convert to NED for output + accel[0] = y_acc.x; + accel[1] = -y_acc.y; + accel[2] = -y_acc.z; + + gazebo::math::Vector3 y_gyro = link_->GetRelativeAngularVel(); + + // Normal Noise from motors + if (motors_spinning()) + { + y_gyro.x += gyro_stdev_*normal_distribution_(random_generator_); + y_gyro.y += gyro_stdev_*normal_distribution_(random_generator_); + y_gyro.z += gyro_stdev_*normal_distribution_(random_generator_); + } + + // Random Walk for bias + gyro_bias_.x += gyro_bias_walk_stdev_*normal_distribution_(random_generator_); + gyro_bias_.y += gyro_bias_walk_stdev_*normal_distribution_(random_generator_); + gyro_bias_.z += gyro_bias_walk_stdev_*normal_distribution_(random_generator_); + + // Apply Constant Bias + y_gyro.x += gyro_bias_.x; + y_gyro.y += gyro_bias_.y; + y_gyro.z += gyro_bias_.z; + + // Convert to NED for output + gyro[0] = y_gyro.x; + gyro[1] = -y_gyro.y; + gyro[2] = -y_gyro.z; + + (*temperature) = 27.0; + (*time_us) = clock_micros(); + return true; +} + +void SIL_Board::imu_not_responding_error(void) +{ + ROS_ERROR("[gazebo_rosflight_sil] imu not responding"); +} + +void SIL_Board::mag_read(float mag[3]) +{ + gazebo::math::Pose I_to_B = link_->GetWorldPose(); + gazebo::math::Vector3 noise; + noise.x = mag_stdev_*normal_distribution_(random_generator_); + noise.y = mag_stdev_*normal_distribution_(random_generator_); + noise.z = mag_stdev_*normal_distribution_(random_generator_); + + // Random Walk for bias + mag_bias_.x += mag_bias_walk_stdev_*normal_distribution_(random_generator_); + mag_bias_.y += mag_bias_walk_stdev_*normal_distribution_(random_generator_); + mag_bias_.z += mag_bias_walk_stdev_*normal_distribution_(random_generator_); + + // combine parts to create a measurement + gazebo::math::Vector3 y_mag = I_to_B.rot.RotateVectorReverse(inertial_magnetic_field_) + mag_bias_ + noise; + + // Convert measurement to NED + mag[0] = y_mag.x; + mag[1] = -y_mag.y; + mag[2] = -y_mag.z;; +} + +bool SIL_Board::mag_check(void) +{ + return true; +} + +bool SIL_Board::baro_check() +{ + return true; +} + +void SIL_Board::baro_read(float *pressure, float *temperature) +{ + // pull z measurement out of Gazebo + gazebo::math::Pose current_state_NWU = link_->GetWorldPose(); + + // Invert measurement model for pressure and temperature + double alt = current_state_NWU.pos.z + ground_altitude_; + + // Convert to the true pressure reading + double y_baro = 101325.0f*(float)pow((1-2.25694e-5 * alt), 5.2553); + + // Add noise + y_baro += baro_stdev_*normal_distribution_(random_generator_); + + // Perform random walk + baro_bias_ += baro_bias_walk_stdev_*normal_distribution_(random_generator_); + + // Add random walk + y_baro += baro_bias_; + + (*pressure) = (float)y_baro; + (*temperature) = 27.0f; +} + +bool SIL_Board::diff_pressure_check(void) +{ + if(mav_type_ == "fixedwing") + return true; + else + return false; +} + +void SIL_Board::diff_pressure_read(float *diff_pressure, float *temperature) +{ + static double rho_ = 1.225; + // Calculate Airspeed + gazebo::math::Vector3 vel = link_->GetRelativeLinearVel(); + + double Va = vel.GetLength(); + + // Invert Airpseed to get sensor measurement + double y_as = rho_*Va*Va/2.0; // Page 130 in the UAV Book + + // Add noise + y_as += airspeed_stdev_*normal_distribution_(random_generator_); + airspeed_bias_ += airspeed_bias_walk_stdev_*normal_distribution_(random_generator_); + y_as += airspeed_bias_; + + *diff_pressure = y_as; + *temperature = 27.0; +} + +bool SIL_Board::sonar_check(void) +{ + return true; +} + +float SIL_Board::sonar_read(void) +{ + gazebo::math::Pose current_state_NWU = link_->GetWorldPose(); + double alt = current_state_NWU.pos.z; + + if (alt < sonar_min_range_) + { + return sonar_min_range_; + } + else if (alt > sonar_max_range_) + { + return sonar_max_range_; + } + else + return alt + sonar_stdev_*normal_distribution_(random_generator_); +} + +// PWM +void SIL_Board::pwm_init(bool cppm, uint32_t refresh_rate, uint16_t idle_pwm) +{ + rc_received_ = false; + latestRC_.values[0] = 1500; // x + latestRC_.values[1] = 1500; // y + latestRC_.values[3] = 1500; // z + latestRC_.values[2] = 1000; // F + latestRC_.values[4] = 1000; // attitude override + latestRC_.values[5] = 1000; // arm + + for (size_t i = 0; i < 14; i++) + pwm_outputs_[i] = 1000; + + rc_sub_ = nh_->subscribe("RC", 1, &SIL_Board::RCCallback, this); +} + +uint16_t SIL_Board::pwm_read(uint8_t channel) +{ + if(rc_sub_.getNumPublishers() > 0) + { + return latestRC_.values[channel]; + } + + //no publishers, set throttle low and center everything else + if(channel == 2) + return 1000; + + return 1500; +} + +void SIL_Board::pwm_write(uint8_t channel, uint16_t value) +{ + pwm_outputs_[channel] = value; +} + +bool SIL_Board::pwm_lost() +{ + return !rc_received_; +} + +// non-volatile memory +void SIL_Board::memory_init(void) {} + +bool SIL_Board::memory_read(void * dest, size_t len) +{ + std::string directory = "rosflight_memory" + nh_->getNamespace(); + std::ifstream memory_file; + memory_file.open(directory + "/mem.bin", std::ios::binary); + + if(!memory_file.is_open()) + { + ROS_ERROR("Unable to load rosflight memory file %s/mem.bin", directory.c_str()); + return false; + } + + memory_file.read((char*) dest, len); + memory_file.close(); + return true; +} + +bool SIL_Board::memory_write(const void * src, size_t len) +{ + std::string directory = "rosflight_memory" + nh_->getNamespace(); + std::string mkdir_command = "mkdir -p " + directory; + const int dir_err = system(mkdir_command.c_str()); + + if (dir_err == -1) + { + ROS_ERROR("Unable to write rosflight memory file %s/mem.bin", directory.c_str()); + return false; + } + + std::ofstream memory_file; + memory_file.open(directory + "/mem.bin", std::ios::binary); + memory_file.write((char*) src, len); + memory_file.close(); + return true; +} + +bool SIL_Board::motors_spinning() +{ + if(pwm_outputs_[2] > 1100) + return true; + else + return false; +} + +// LED + +void SIL_Board::led0_on(void) { } +void SIL_Board::led0_off(void) { } +void SIL_Board::led0_toggle(void) { } + +void SIL_Board::led1_on(void) { } +void SIL_Board::led1_off(void) { } +void SIL_Board::led1_toggle(void) { } + +void SIL_Board::RCCallback(const rosflight_msgs::RCRaw& msg) +{ + rc_received_ = true; + latestRC_ = msg; +} + +} // namespace rosflight_sim diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/xacro/fixedwing.urdf.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/xacro/fixedwing.urdf.xacro new file mode 100644 index 0000000..39abc91 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/xacro/fixedwing.urdf.xacro @@ -0,0 +1,64 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.00 + 0.00 + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/xacro/multirotor.urdf.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/xacro/multirotor.urdf.xacro new file mode 100644 index 0000000..8e0cb45 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/xacro/multirotor.urdf.xacro @@ -0,0 +1,62 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/${color} + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/xacro/rosflight_sil.xacro b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/xacro/rosflight_sil.xacro new file mode 100644 index 0000000..70fc837 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_sim/xacro/rosflight_sil.xacro @@ -0,0 +1,34 @@ + + + + + + + + + + + + + + + + + ${parent_link} + ${namespace} + ${mav_type} + ${parent_frame_id} + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/CHANGELOG.rst b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/CHANGELOG.rst new file mode 100644 index 0000000..0db0e0e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/CHANGELOG.rst @@ -0,0 +1,26 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package rosflight_utils +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.1.3 (2017-06-02) +------------------ +* Updated package.xml files +* Contributors: Daniel Koch + +0.1.2 (2017-05-24) +------------------ + +0.1.1 (2017-05-24) +------------------ +* Added missing dependencies +* Contributors: Daniel Koch + +0.1.0 (2017-05-22) +------------------ +* Added BSD license statements to source files + Closes `#1 `_ +* Replaced outdated package README files with simpler top-level README + The information that used to be in the package README files is now on the ROS wiki (http://wiki.ros.org/rosflight_pkgs, http://wiki.ros.org/rosflight, etc.) + Closes `#7 `_ +* Renamed rosflight_common to rosflight_utils +* Contributors: Daniel Koch diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/CMakeLists.txt b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/CMakeLists.txt new file mode 100644 index 0000000..4220a44 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/CMakeLists.txt @@ -0,0 +1,37 @@ +cmake_minimum_required(VERSION 2.8.3) +project(rosflight_utils) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + roscpp + gazebo_msgs + geometry_msgs + rosflight_msgs + rosgraph_msgs + sensor_msgs + std_srvs +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES rosflight_utils + CATKIN_DEPENDS roscpp rospy rosflight_msgs sensor_msgs +) + +add_definitions(-std=c++11) + +include_directories(include) +include_directories(${catkin_INCLUDE_DIRS}) + +add_library(rosflight_utils + src/simple_pid.cpp + src/turbomath.cpp +) +add_dependencies(${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(rosflight_utils ${catkin_LIBRARIES}) + +#add_executable(joy src/joy.cpp) +#add_dependencies(joy ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +#target_link_libraries(joy ${catkin_LIBRARIES}) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/include/rosflight_utils/joy.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/include/rosflight_utils/joy.h new file mode 100644 index 0000000..6f8fa35 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/include/rosflight_utils/joy.h @@ -0,0 +1,141 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROSFLIGHT_COMMON_JOY_JOY_H +#define ROSFLIGHT_COMMON_JOY_JOY_H + +#include +#include +#include +#include + +struct Axes +{ + int x; + int y; + int F; + int z; + int x_direction; + int y_direction; + int F_direction; + int z_direction; +}; + +struct Max +{ + double roll; + double pitch; + + double roll_rate; + double pitch_rate; + double yaw_rate; + + double aileron; + double elevator; + double rudder; + + double xvel; + double yvel; + double zvel; +}; + +struct Button +{ + int index; + bool prev_value; +}; + +struct Buttons +{ + Button fly; + Button mode; + Button reset; + Button pause; + Button override; +}; + +class Joy +{ + typedef sensor_msgs::Joy::_buttons_type ButtonType; + +private: + ros::NodeHandle nh_; + ros::Publisher command_pub_; + ros::Subscriber autopilot_command_sub_; + ros::Subscriber joy_sub_; + + std::string namespace_; + std::string command_topic_; + std::string autopilot_command_topic_; + + std::string mav_name_; + std::string gazebo_ns_; + + Axes axes_; + + bool override_autopilot_ = true; + bool paused = true; + double equilibrium_thrust_; + + rosflight_msgs::Command command_msg_; + rosflight_msgs::Command autopilot_command_; + sensor_msgs::Joy current_joy_; + + Max max_; + Buttons buttons_; + geometry_msgs::Pose reset_pose_; + geometry_msgs::Twist reset_twist_; + + double current_altitude_setpoint_; + double current_x_setpoint_; + double current_y_setpoint_; + double current_yaw_setpoint_; + double last_time_; + + + double current_yaw_vel_; + double v_yaw_step_; + double mass_; + + void StopMav(); + void ResetMav(); + void PauseSimulation(); + void ResumeSimulation(); + + void JoyCallback(const sensor_msgs::JoyConstPtr &msg); + void APCommandCallback(const rosflight_msgs::CommandConstPtr &msg); + void Publish(); + +public: + Joy(); +}; + +#endif // ROSFLIGHT_COMMON_JOY_JOY_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/include/rosflight_utils/simple_pid.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/include/rosflight_utils/simple_pid.h new file mode 100644 index 0000000..393ee7c --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/include/rosflight_utils/simple_pid.h @@ -0,0 +1,137 @@ +/* + * Copyright (c) 2017 Robert Leishman, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/*! + * \brief This file defines a simple PID controller to be used by other classes to implement a PID control loop + * \author Robert Leishman + * \date Dec. 2013 +*/ + +#ifndef ROTOR_CONTROLLER_SIMPLE_PID_H +#define ROTOR_CONTROLLER_SIMPLE_PID_H + +#include +#include // included temporarily for debug statements + +namespace rosflight_utils +{ +/*! + * \brief The simplePID class is a basic, tried and true PID controller. Only P (proportional) gains are + * necessary, the I (integral) and D (derivative) default to zero. The I control is computed using a + * first-order numerical integral of the error, the derivative is the numerical first-order derivative + * of the error. Due to these crude integration techniques, it is best if the control be computed fast + * (i.e. small dt). + */ +class SimplePID +{ +public: + /*! + * \brief SimplePID is the basic initializer; + */ + SimplePID(); + + /*! + * \brief SimplePID initializes the class. + * \param p the proportional controller gain (required) + * \param i the integral controller gain (defaults to zero) + * \param d the derivative controller gain (defaults to zero) + * \param imin the min value accepted in the output of the integral control + * \param imax the max value accepted in the output of the integral control (saturation for integrator windup) + * \param tau band limited differentiator to reduce noise + */ + SimplePID(double p, double i = 0.0, double d = 0.0, double max = DBL_MAX, double min = -DBL_MAX, double tau = 0.15); + + /*! + * \brief computePID computes the PID control for the given error and timestep (since the last control was computed!) + * \param p_error is the "position" error (or whatever variable you are controlling) + * \param dt is the timestep since the last control was computed. + * \param x_dot derivative of current state (optional) + * \return the control command + */ + double computePID(double desired, double current, double dt, double x_dot = INFINITY); + + /*! + * \brief setgains is used to set the gains for a controller after it's been initialized. It will rewrite + * whatever is already there! + * \param p the proportional controller gain (required) + * \param i the integral controller gain (defaults to zero) + * \param d the derivative controller gain (defaults to zero) + * \param tau band limited differentiator to reduce noise + */ + void setGains(double p, double i = 0.0, double d = 0.0, double tau = 0.15); + + /*! + * \brief setgains is used to set the gains for a controller after it's been initialized. It will rewrite + * whatever is already there! + * \param max the largest output allowed (integrator anti-windup will kick in at this value as well) + * \param min the smallest output allowed (also activates integrator anti-windup + */ + void setLimits(double max, double min); + + /*! + * \brief clearIntegrator allows you to clear the integrator, in case of integrator windup. + */ + void clearIntegrator() + { + integrator_ = 0.0; + } + +protected: + double kp_; //!< the proportional gain + double ki_; //!< the integral gain (zero if you don't want integral control) + double kd_; //!< the derivative gain (zero if you don't want derivative control) + double integrator_; //!< the integral of p_error + double differentiator_; //!< used for noise reduced differentiation + double last_error_; //!< the last p_error, for computing the derivative; + double last_state_; //!< the last state, for computing the derivative; + double tau_; //!< the noise reduction term for the derivative + double max_; //!< Maximum Output + double min_; //!< Minimum Output + + /*! + * \brief saturate saturates the variable val + * \param val the parameter to saturate (makes a copy) + * \param min the minimum value + * \param max the max value + * \return the saturated (if necessary) value + */ + inline double saturate(double val, double &min, double &max) + { + if (val > max) + val = max; + else if (val < min) + val = min; + return val; + } +}; +} + +#endif // ROTOR_CONTROLLER_SIMPLE_PID_H diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/include/rosflight_utils/turbomath.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/include/rosflight_utils/turbomath.h new file mode 100644 index 0000000..02b11e1 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/include/rosflight_utils/turbomath.h @@ -0,0 +1,47 @@ +/* + * Copyright (c) 2017 James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#pragma once + +#include +#ifndef M_PI +#define M_PI 3.14159 +#endif + +// turbo-speed trig approximation +float turboatan2(float y, float x); +float turboasin(float x); +float turbosin(float x); +float turbocos(float x); + +double turbopow(double a, double b); +int32_t sign(int32_t y); +float sign(float y); diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/include/rosflight_utils/viz_mag.h b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/include/rosflight_utils/viz_mag.h new file mode 100644 index 0000000..44e4474 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/include/rosflight_utils/viz_mag.h @@ -0,0 +1,47 @@ +#ifndef VIZ_MAG_H +#define VIZ_MAG_H + +#include +#include +#include +#include +#include +#include +#include + +namespace rosflight_utils +{ + + +class VizMag +{ + +public: + + VizMag(); + +private: + + // Node handles, publishers, subscribers + ros::NodeHandle nh_; + ros::NodeHandle nh_private_; + + // Publishers and Subscribers + ros::Subscriber mag_sub_; + ros::Publisher mag_pub_; + ros::Publisher pts_pub_; + + // Variables + tf::Quaternion q_att_; + std::vector pts_list_; + double mag_sum_; + int mag_count_, mag_throttle_, mag_skip_; + + // Functions + void magCallback(const sensor_msgs::MagneticFieldConstPtr &msg); +}; + +} // namespace visual_naze + +#endif + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/launch/fixedwing_sil.launch b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/launch/fixedwing_sil.launch new file mode 100644 index 0000000..6b50647 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/launch/fixedwing_sil.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/launch/rc.launch b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/launch/rc.launch new file mode 100644 index 0000000..34b219f --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/launch/rc.launch @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/launch/viz_mag.launch b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/launch/viz_mag.launch new file mode 100644 index 0000000..8f655d6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/launch/viz_mag.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/package.xml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/package.xml new file mode 100644 index 0000000..a522beb --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/package.xml @@ -0,0 +1,28 @@ + + + rosflight_utils + 0.1.3 + Supporting utilities for ROSflight packages + + gary + + BSD + + http://rosflight.org + https://github.com/rosflight/rosflight + https://github.com/rosflight/rosflight/issues + + catkin + + roscpp + rospy + gazebo_msgs + geometry_msgs + rosflight_msgs + rosgraph_msgs + sensor_msgs + std_srvs + + + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/param/xbox.yaml b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/param/xbox.yaml new file mode 100644 index 0000000..2a8c673 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/param/xbox.yaml @@ -0,0 +1,30 @@ +x_axis: 3 +y_axis: 4 +F_axis: 1 +z_axis: 0 + +x_sign: -1 +y_sign: -1 +F_sign: 1 +z_sign: -1 + +button_takeoff: 0 +button_mode: 1 +button_reset: 6 +button_pause: 7 +button_override: 4 + +max_aileron: 1.0 +max_elevator: 1.0 +max_rudder: 1.0 + +max_roll_rate: 3.14159 +max_pitch_rate: 3.14159 +max_yaw_rate: 6.283 + +max_roll_angle: 1.4 +max_pitch_angle: 1.4 + +max_xvel: 25.0 +max_yvel: 25.0 +max_zvel: 4.0 \ No newline at end of file diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/rviz/viz_mag.rviz b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/rviz/viz_mag.rviz new file mode 100644 index 0000000..12b147a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/rviz/viz_mag.rviz @@ -0,0 +1,172 @@ +Panels: + - Class: rviz/Displays + Help Height: 104 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + Splitter Ratio: 0.5 + Tree Height: 819 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 255; 0; 0 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XZ + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 0; 85; 255 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 0; 255; 0 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: YZ + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/Pose + Color: 255; 25; 0 + Enabled: true + Head Length: 0.20000000298023224 + Head Radius: 0.10000000149011612 + Name: Mag + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Shape: Arrow + Topic: /viz/magnetometer + Unreliable: false + Value: true + - Class: rviz/Marker + Enabled: true + Marker Topic: /viz/cloud + Name: Mag Measurements + Namespaces: + "": true + Queue Size: 100 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: fixed_frame + Frame Rate: 60 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 16.30889320373535 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.5847976803779602 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.9005014896392822 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1116 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd00000004000000000000017b000003d5fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000027000003d5000000c600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c000002610000000100000111000002adfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000037000002ad0000009e00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000060c00000040fc0100000002fb0000000800540069006d006501000000000000060c0000024400fffffffb0000000800540069006d006501000000000000045000000000000000000000048b000003d500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1548 + X: 144 + Y: 53 + + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/WaypointConvert.py b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/WaypointConvert.py new file mode 100644 index 0000000..db53334 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/WaypointConvert.py @@ -0,0 +1,177 @@ +################################################################################ +# +# Copyright (c) 2017 Taylor Pool, BYU MAGICC Lab. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright notice, this +# list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright notice, +# this list of conditions and the following disclaimer in the documentation +# and/or other materials provided with the distribution. +# +# * Neither the name of the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +################################################################################ + +# Taylor Pool +# December 1, 2016 +#AUVSI Project + +# This script contains a function that converts given GPS coordinates into waypoints for ROS. +#The input supports two types of GPS coordinates +#1) Long Degree Decimal Format +# ex: -34.6830975 +#2) Degrees-Minutes-Seconds Format +# ex: N78-45-76.23 +#The function to be called for conversion is to_meters(originLat, originLong, originAlt, newLat, newLong, newAlt, flag) +#The two formats listed above can be used simultaeously in the same function call. +#NOTE: Degrees-Minutes-Seconds Format is the only format that uses NSEW directions in front. +#NOTE: Degrees-Minutes-Seconds Format needs to be surrounded with quotations when passed as an argument. + +from math import pi +from math import cos +from math import sqrt + +#constant +EARTH_RADIUS = 6371008.0 #in meters + +#Function decimal_degrees +#Pre: string is in format [N/E or S/W]DD-MM-SS.SS +#Post: Returns GPS component in long decimal format +def decimal_degrees (string): + a = 0 + + firstLetter = string[0] + if firstLetter == 'N' or firstLetter == 'E': + a = 1 + elif firstLetter == 'S' or firstLetter == 'W': + a = -1 + + lessString = string.strip("NSEW ") + + values = lessString.split('-', 2) + + d = float(values[0]) + m = float(values[1]) + s = float(values[2]) + + decimal = a*(d+(m/60.0)+(s/3600.0)) + + return decimal + + +#Function meter_convert +#Takes in long decimal GPS format and outputs the destination in meters +#Pre: Lat and Long are given in decimal degrees, and altitude is in meters +#Post: Returns destination in tuple format [latChange, longChange, newAlt, distance] +def meter_convert(originLat, originLong, originAlt, newLat, newLong, newAlt): + + #Find CrossSectional Radius of Earth for Given Latitude Degree + crossRadius = cos(originLat*pi/180.0)*EARTH_RADIUS + + GPSdestination = [newLat, newLong, -newAlt] #Given in terms of N, E, D + + #Convert Change in GPS Coordinates to Change in Meters + latChange = ((newLat - originLat)*pi/180.0)*EARTH_RADIUS #in meters + + longChange = ((newLong - originLong)*pi/180.0)*crossRadius + + altitudeChange = newAlt - originAlt + + #Compute Total Distance to Fly + distance = sqrt(pow(latChange, 2.0) + pow(longChange, 2.0) + pow(altitudeChange, 2.0)) + + #New Waypoint Given in Terms of [North, East, Down]. In meters. + destination = [latChange, longChange, newAlt, distance] + + return destination + + +#Function to_meters +#Pre: input of all the data needed to fly to a waypoint +#flag: tells whether altitude is in meters or feet +# 0: meters else: feet +#Post: outputs destination given in meters that ROS can understand. +def to_meters(originLat, originLong, originAlt, newLat, newLong, newAlt, flag): + + #Altitude in Feet needs to be converted to Meters + if (flag != 0): + originAlt = .305*originAlt + newAlt = .305*newAlt + + GPSorigin = [originLat, originLong, originAlt] + GPSdestination = [newLat, newLong, newAlt] + + values = [str(originLat), str(originLong), str(newLat), str(newLong)] + newValues = [] + + for value in values: + if ("N" in value) or ("S" in value) or ("E" in value) or ("W" in value) == 1: + #print "Degrees Minutes Seconds Format" + #print value + newValues.append(decimal_degrees(value)) + #print decimal_degrees(value) + else: + #print "Long Decimal Format" + newValues.append(float(value)) + + destination = meter_convert(newValues[0], newValues[1], originAlt, newValues[2], newValues[3], newAlt) + + #Test Output + #print("Origin in GPS Coordinates: " + str(GPSorigin)) + #print("\n") + #print("Destination in GPS Coordinates: " + str(GPSdestination)) + #print("\n") + #print("Destination Coordinates (Meters) with Distance: " + str(destination)) + + return destination + + + +####################################################################################################### + + +#Test +#test = to_meters("N90-90-76.45", "W45-67-23.54", 20.0, -40.257049176511316, 111.65421836078167, 20.0, 0) + +#if __name__ == __main__: +# toMeters(40.25787274333326, -111.65480308234692, -20.0, 40.257049176511316, -111.65421836078167, -20.0, 0) + + +####################################################################################################################### + +#Sample Output: +#tpool2@FB280-09:/media/tpool2/TAYLORPOOL/AUVSI/rosflight_utils/src$ python WaypointConvert.py +#Degrees Minutes Seconds Format +#N90-90-76.45 +#91.5212361111 +#Degrees Minutes Seconds Format +#W45-67-23.54 +#-46.1232055556 +#Long Decimal Format +#Long Decimal Format +#Origin in GPS Coordinates: ['N90-90-76.45', 'W45-67-23.54', 20.0] + + +#Destination in GPS Coordinates: [-40.257049176511316, 111.65421836078167, 20.0] + + +#Destination Coordinates (Meters) with Distance: [-14653095.165621338, -465750.5181201244, 20.0, 14660495.267141715] diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/command_joy b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/command_joy new file mode 100644 index 0000000..cab19c2 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/command_joy @@ -0,0 +1,78 @@ +#!/usr/bin/python + +# author: James Jackson + +import time +import rospy +from rosflight_msgs.msg import Command +import pygame +import re +import os + +os.environ["SDL_VIDEODRIVER"] = "dummy" + +rospy.init_node('command_joy') +command_pub = rospy.Publisher('command', Command, queue_size=10) + +pygame.display.init() +pygame.joystick.init() + +joy = pygame.joystick.Joystick(0) +joy.init() + +print "joystick:", joy.get_name() + +mapping = dict() + +if 'Taranis' in joy.get_name(): + print "found Taranis" + mapping['x'] = 0 + mapping['y'] = 1 + mapping['z'] = 3 + mapping['F'] = 2 + mapping['xsign'] = 1 + mapping['ysign'] = 1 + mapping['zsign'] = 1 + mapping['Fsign'] = 1 +elif 'Xbox' in joy.get_name() or 'X-Box' in joy.get_name(): + print "found xbox" + mapping['x'] = 3 + mapping['y'] = 4 + mapping['z'] = 0 + mapping['F'] = 1 + mapping['xsign'] = 1 + mapping['ysign'] = 1 + mapping['zsign'] = 1 + mapping['Fsign'] = -1 +else: + print "using realflght mapping" + mapping['x'] = 1 + mapping['y'] = 2 + mapping['z'] = 4 + mapping['F'] = 0 + mapping['xsign'] = 1 + mapping['ysign'] = 1 + mapping['zsign'] = 1 + mapping['Fsign'] = 1 + +# Main event loop +next_update_time = time.time() +while not rospy.is_shutdown(): + pygame.event.pump() + + # 50 Hz update + if time.time() > next_update_time: + next_update_time += 0.02 + + msg = Command() + msg.header.stamp = rospy.Time.now() + + msg.mode = 2 + + msg.x = joy.get_axis(mapping['x']) * mapping['xsign'] * 0.785 + msg.y = joy.get_axis(mapping['y']) * mapping['ysign'] * 0.785 + msg.z = joy.get_axis(mapping['z']) * mapping['zsign'] * 1.507 + msg.F = joy.get_axis(mapping['F']) * mapping['Fsign'] * 0.5 + 0.5 + + msg.ignore = 0 + command_pub.publish(msg) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/gps b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/gps new file mode 100644 index 0000000..8925e7a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/gps @@ -0,0 +1,59 @@ +#! /usr/bin/env python + +# Software License Agreement (BSD License) +# +# Copyright (c) 2013, Eric Perko +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the names of the authors nor the names of their +# affiliated organizations may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import serial + +import rospy + +import libnmea_navsat_driver.driver + +if __name__ == '__main__': + rospy.init_node('gps') + + serial_port = rospy.get_param('~port','/dev/ttyUSB0') + serial_baud = rospy.get_param('~baud',115200) + frame_id = libnmea_navsat_driver.driver.RosNMEADriver.get_frame_id() + + try: + GPS = serial.Serial(port=serial_port, baudrate=serial_baud, timeout=2) + driver = libnmea_navsat_driver.driver.RosNMEADriver() + while not rospy.is_shutdown(): + data = GPS.readline().strip() + try: + driver.add_sentence(data, frame_id) + except ValueError as e: + rospy.logwarn("Value error, likely due to missing fields in the NMEA message. Error was: %s. Please report this issue at github.com/ros-drivers/nmea_navsat_driver, including a bag file with the NMEA sentences that caused it." % e) + + except rospy.ROSInterruptException: + GPS.close() #Close GPS serial port diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/joy.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/joy.cpp new file mode 100644 index 0000000..ef58d88 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/joy.cpp @@ -0,0 +1,338 @@ +/* + * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +Joy::Joy() +{ + ros::NodeHandle pnh("~"); + ros::NodeHandle namespace_nh(ros::this_node::getNamespace()); + + pnh.param("command_topic", command_topic_, "command"); + pnh.param("autopilot_command_topic", autopilot_command_topic_, "autopilot_command"); + + // Get global parameters + double max_thrust; + namespace_nh.param("mass", mass_, 3.61); + namespace_nh.param("max_F", max_thrust, 64.50); + namespace_nh.param("mav_name", mav_name_,"shredder"); + equilibrium_thrust_ = (mass_*9.80665) / max_thrust; + + // Get Parameters from joystick configuration yaml + pnh.param("gazebo_namespace", gazebo_ns_, ""); + pnh.param("x_axis", axes_.x, 1); + pnh.param("y_axis", axes_.y, 2); + pnh.param("F_axis", axes_.F, 0); + pnh.param("z_axis", axes_.z, 4); + + pnh.param("x_sign", axes_.x_direction, 1); + pnh.param("y_sign", axes_.y_direction, 1); + pnh.param("F_sign", axes_.F_direction, -1); + pnh.param("z_sign", axes_.z_direction, 1); + + pnh.param("max_aileron", max_.aileron, 15.0 * M_PI / 180.0); + pnh.param("max_elevator", max_.elevator, 25.0 * M_PI / 180.0); + pnh.param("max_rudder", max_.rudder, 15.0 * M_PI / 180.0); + + pnh.param("max_roll_rate", max_.roll_rate, 360.0 * M_PI / 180.0); + pnh.param("max_pitch_rate", max_.pitch_rate, 360.0 * M_PI / 180.0); + pnh.param("max_yaw_rate", max_.yaw_rate, 360.0 * M_PI / 180.0); + + pnh.param("max_roll_angle", max_.roll, 45.0 * M_PI / 180.0); + pnh.param("max_pitch_angle", max_.pitch, 45.0 * M_PI / 180.0); + + pnh.param("max_xvel", max_.xvel, 1.5); + pnh.param("max_yvel", max_.yvel, 1.5); + pnh.param("max_zvel", max_.zvel, 1.5); + command_msg_.mode = pnh.param("control_mode", (int)rosflight_msgs::Command::MODE_ROLL_PITCH_YAWRATE_THROTTLE); + + pnh.param("reset_pos_x", reset_pose_.position.x, 0.0); + pnh.param("reset_pos_y", reset_pose_.position.y, 0.0); + pnh.param("reset_pos_z", reset_pose_.position.z, 0.0); + pnh.param("reset_orient_x", reset_pose_.orientation.x, 0.0); + pnh.param("reset_orient_x", reset_pose_.orientation.y, 0.0); + pnh.param("reset_orient_x", reset_pose_.orientation.z, 0.0); + pnh.param("reset_orient_x", reset_pose_.orientation.w, 0.0); + pnh.param("reset_linear_twist_x", reset_twist_.linear.x, 0.0); + pnh.param("reset_linear_twist_y", reset_twist_.linear.y, 0.0); + pnh.param("reset_linear_twist_z", reset_twist_.linear.z, 0.0); + pnh.param("reset_angular_twist_x", reset_twist_.angular.x, 0.0); + pnh.param("reset_angular_twist_x", reset_twist_.angular.y, 0.0); + pnh.param("reset_angular_twist_x", reset_twist_.angular.z, 0.0); + + // Sets which buttons are tied to which commands + pnh.param("button_takeoff", buttons_.fly.index, 0); + pnh.param("button_mode", buttons_.mode.index, 1); + pnh.param("button_reset", buttons_.reset.index, 9); + pnh.param("button_pause", buttons_.pause.index, 8); + pnh.param("button_override", buttons_.override.index, 8); + + command_pub_ = nh_.advertise(command_topic_, 10); + + command_msg_.x = 0; + command_msg_.y = 0; + command_msg_.z = 0; + command_msg_.F = 0; + command_msg_.ignore = 0xFF; + + current_yaw_vel_ = 0; + + namespace_ = nh_.getNamespace(); + autopilot_command_sub_ = nh_.subscribe(autopilot_command_topic_, 10, &Joy::APCommandCallback, this); + joy_sub_ = nh_.subscribe("joy", 10, &Joy::JoyCallback, this); + buttons_.mode.prev_value = 0; + buttons_.reset.prev_value = 0; + + current_altitude_setpoint_ = current_x_setpoint_ = current_y_setpoint_ = 0.0; +} + +void Joy::StopMav() +{ + command_msg_.x = 0; + command_msg_.y = 0; + command_msg_.z = 0; + command_msg_.F = 0; +} + +/* Resets the mav back to origin */ +void Joy::ResetMav() +{ + ROS_INFO("Mav position reset."); + ros::NodeHandle n; + + gazebo_msgs::ModelState modelstate; + modelstate.model_name = (std::string)mav_name_; + modelstate.reference_frame = (std::string) "world"; + modelstate.pose = reset_pose_; + modelstate.twist = reset_twist_; + + ros::ServiceClient client = n.serviceClient("/gazebo/set_model_state"); + gazebo_msgs::SetModelState setmodelstate; + setmodelstate.request.model_state = modelstate; + client.call(setmodelstate); +} + +// Pauses the gazebo physics and time +void Joy::PauseSimulation() +{ + ROS_INFO("Simulation paused."); + ros::NodeHandle n; + + ros::ServiceClient client = n.serviceClient("/gazebo/pause_physics"); + std_srvs::Empty pauseSim; + client.call(pauseSim); +} + +// Resumes the gazebo physics and time +void Joy::ResumeSimulation() +{ + ROS_INFO("Simulation resumed."); + ros::NodeHandle n; + + ros::ServiceClient client = n.serviceClient("/gazebo/unpause_physics"); + std_srvs::Empty resumeSim; + client.call(resumeSim); + last_time_ = ros::Time::now().toSec(); +} + +void Joy::APCommandCallback(const rosflight_msgs::CommandConstPtr &msg) +{ + autopilot_command_ = *msg; +} + +void Joy::JoyCallback(const sensor_msgs::JoyConstPtr &msg) +{ + double dt = ros::Time::now().toSec() - last_time_; + last_time_ = ros::Time::now().toSec(); + + current_joy_ = *msg; + + // Perform button actions + if (msg->buttons[buttons_.override.index] == 0 && buttons_.override.prev_value == 1) + { + override_autopilot_ = true; + } + buttons_.override.prev_value = msg->buttons[buttons_.override.index]; + + // Resets the mav to the origin + if (msg->buttons[buttons_.reset.index] == 0 && buttons_.reset.prev_value == 1) // button release + { + ResetMav(); + } + buttons_.reset.prev_value = msg->buttons[buttons_.reset.index]; + + // Pauses/Unpauses the simulation + if (msg->buttons[buttons_.pause.index] == 0 && buttons_.pause.prev_value == 1) // button release + { + if (!paused) + { + PauseSimulation(); + paused = true; + } + else + { + ResumeSimulation(); + paused = false; + } + } + buttons_.pause.prev_value = msg->buttons[buttons_.pause.index]; + + if (msg->buttons[buttons_.mode.index] == 0 && buttons_.mode.prev_value == 1) + { + command_msg_.mode = (command_msg_.mode + 1) % 6; + if (command_msg_.mode == rosflight_msgs::Command::MODE_PASS_THROUGH) + { + ROS_INFO("Passthrough"); + } + else if (command_msg_.mode == rosflight_msgs::Command::MODE_ROLL_PITCH_YAWRATE_THROTTLE) + { + ROS_INFO("Angle Mode"); + } + else if (command_msg_.mode == rosflight_msgs::Command::MODE_ROLL_PITCH_YAWRATE_ALTITUDE) + { + ROS_INFO("Altitude Mode"); + } + else if (command_msg_.mode == rosflight_msgs::Command::MODE_XVEL_YVEL_YAWRATE_ALTITUDE) + { + ROS_INFO("Velocity Mode"); + } + else if (command_msg_.mode == rosflight_msgs::Command::MODE_XPOS_YPOS_YAW_ALTITUDE) + { + ROS_INFO("Position Mode"); + } + else + { + ROS_INFO("Passthrough"); + } + } + buttons_.mode.prev_value = msg->buttons[buttons_.mode.index]; + + // calculate the output command from the joysticks + if(override_autopilot_) + { + command_msg_.F = msg->axes[axes_.F] * axes_.F_direction; + command_msg_.x = msg->axes[axes_.x] * axes_.x_direction; + command_msg_.y = msg->axes[axes_.y] * axes_.y_direction; + command_msg_.z = msg->axes[axes_.z] * axes_.z_direction; + + switch (command_msg_.mode) + { + case rosflight_msgs::Command::MODE_ROLLRATE_PITCHRATE_YAWRATE_THROTTLE: + command_msg_.x *= max_.roll_rate; + command_msg_.y *= max_.pitch_rate; + command_msg_.z *= max_.yaw_rate; + if (command_msg_.F > 0.0) + { + command_msg_.F = equilibrium_thrust_ + (1.0 - equilibrium_thrust_) * command_msg_.F; + } + else + { + command_msg_.F = equilibrium_thrust_ + (equilibrium_thrust_) * command_msg_.F; + } + break; + + case rosflight_msgs::Command::MODE_ROLL_PITCH_YAWRATE_THROTTLE: + command_msg_.x *= max_.roll; + command_msg_.y *= max_.pitch; + command_msg_.z *= max_.yaw_rate; + if (command_msg_.F > 0.0) + { + command_msg_.F = equilibrium_thrust_ + (1.0 - equilibrium_thrust_) * command_msg_.F; + } + else + { + command_msg_.F = equilibrium_thrust_ + (equilibrium_thrust_) * command_msg_.F; + } + break; + + case rosflight_msgs::Command::MODE_ROLL_PITCH_YAWRATE_ALTITUDE: + command_msg_.x *= max_.roll; + command_msg_.y *= max_.pitch; + command_msg_.z *= max_.yaw_rate; + // Integrate altitude + current_altitude_setpoint_ -= dt * max_.zvel * command_msg_.F; + command_msg_.F = current_altitude_setpoint_; + break; + + case rosflight_msgs::Command::MODE_XVEL_YVEL_YAWRATE_ALTITUDE: + { + // Remember that roll affects y velocity and pitch affects -x velocity + double original_x = command_msg_.x; + command_msg_.x = max_.xvel * -1.0 * command_msg_.y; + command_msg_.y = max_.yvel * original_x; + command_msg_.z *= max_.yaw_rate; + // Integrate altitude + current_altitude_setpoint_ -= dt * max_.zvel * command_msg_.F; + command_msg_.F = current_altitude_setpoint_; + break; + } + + case rosflight_msgs::Command::MODE_XPOS_YPOS_YAW_ALTITUDE: + // Integrate all axes + // (Remember that roll affects y velocity and pitch affects -x velocity) + current_x_setpoint_ -= dt * max_.xvel * command_msg_.y; + command_msg_.x = current_x_setpoint_; + + current_y_setpoint_ += dt * max_.yvel * command_msg_.x; + command_msg_.y = current_y_setpoint_; + + current_yaw_setpoint_ += dt * max_.yaw_rate * command_msg_.z; + current_yaw_setpoint_ = fmod(current_yaw_setpoint_, (2.0 * M_PI)); + + current_altitude_setpoint_ -= dt * max_.zvel * command_msg_.z; + command_msg_.z = current_altitude_setpoint_; + break; + } + } + else + { + command_msg_ = autopilot_command_; + } + + Publish(); +} + +void Joy::Publish() +{ + command_pub_.publish(command_msg_); +} + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "rosflight_utils_joy"); + Joy joy; + + ros::spin(); + + return 0; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/libnmea_navsat_driver/__init__.py b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/libnmea_navsat_driver/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/libnmea_navsat_driver/checksum_utils.py b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/libnmea_navsat_driver/checksum_utils.py new file mode 100644 index 0000000..899ae38 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/libnmea_navsat_driver/checksum_utils.py @@ -0,0 +1,48 @@ +# Software License Agreement (BSD License) +# +# Copyright (c) 2013, Eric Perko +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the names of the authors nor the names of their +# affiliated organizations may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + + +# Check the NMEA sentence checksum. Return True if passes and False if failed +def check_nmea_checksum(nmea_sentence): + split_sentence = nmea_sentence.split('*') + if len(split_sentence) != 2: + #No checksum bytes were found... improperly formatted/incomplete NMEA data? + return False + transmitted_checksum = split_sentence[1].strip() + + #Remove the $ at the front + data_to_checksum = split_sentence[0][1:] + checksum = 0 + for c in data_to_checksum: + checksum ^= ord(c) + + return ("%02X" % checksum) == transmitted_checksum.upper() diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/libnmea_navsat_driver/driver.py b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/libnmea_navsat_driver/driver.py new file mode 100644 index 0000000..56ff029 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/libnmea_navsat_driver/driver.py @@ -0,0 +1,187 @@ +# Software License Agreement (BSD License) +# +# Copyright (c) 2013, Eric Perko +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the names of the authors nor the names of their +# affiliated organizations may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import math + +import rospy + +from sensor_msgs.msg import NavSatFix, NavSatStatus, TimeReference +from geometry_msgs.msg import TwistStamped +from rosflight_msgs.msg import GPS + +from libnmea_navsat_driver.checksum_utils import check_nmea_checksum +import libnmea_navsat_driver.parser + + +class RosNMEADriver(object): + def __init__(self): + self.fix_pub = rospy.Publisher('gps', GPS, queue_size=1) + # self.vel_pub = rospy.Publisher('vel', TwistStamped, queue_size=1) + self.time_ref_pub = rospy.Publisher('time_reference', TimeReference, queue_size=1) + + self.time_ref_source = rospy.get_param('~time_ref_source', None) + self.use_RMC = rospy.get_param('~useRMC', False) + + self.speed = 0 + self.ground_course = 0 + + # Returns True if we successfully did something with the passed in + # nmea_string + def add_sentence(self, nmea_string, frame_id, timestamp=None): + if not check_nmea_checksum(nmea_string): + rospy.logwarn("Received a sentence with an invalid checksum. " + + "Sentence was: %s" % repr(nmea_string)) + return False + + parsed_sentence = libnmea_navsat_driver.parser.parse_nmea_sentence(nmea_string) + if not parsed_sentence: + rospy.logdebug("Failed to parse NMEA sentence. Sentece was: %s" % nmea_string) + return False + + if timestamp: + current_time = timestamp + else: + current_time = rospy.get_rostime() + current_fix = GPS() + current_fix.header.stamp = current_time + current_fix.header.frame_id = frame_id + current_time_ref = TimeReference() + current_time_ref.header.stamp = current_time + current_time_ref.header.frame_id = frame_id + if self.time_ref_source: + current_time_ref.source = self.time_ref_source + else: + current_time_ref.source = frame_id + + if 'RMC' in parsed_sentence: + data = parsed_sentence['RMC'] + if data['fix_valid']: + self.speed = data['speed'] + if not math.isnan(data['true_course']): + self.ground_course = data['true_course'] + + if not self.use_RMC and 'GGA' in parsed_sentence: + data = parsed_sentence['GGA'] + gps_qual = data['fix_type'] + if gps_qual > 0: + current_fix.fix = True + current_fix.NumSat = data['num_satellites'] + # current_fix.status.service = NavSatStatus.SERVICE_GPS + + current_fix.header.stamp = current_time + + latitude = data['latitude'] + if data['latitude_direction'] == 'S': + latitude = -latitude + current_fix.latitude = latitude + + longitude = data['longitude'] + if data['longitude_direction'] == 'W': + longitude = -longitude + current_fix.longitude = longitude + + hdop = data['hdop'] + current_fix.covariance = hdop ** 2 + # current_fix.position_covariance[4] = hdop ** 2 + # current_fix.position_covariance[8] = (2 * hdop) ** 2 # FIXME + # current_fix.position_covariance_type = \ + # NavSatFix.COVARIANCE_TYPE_APPROXIMATED + + # Altitude is above ellipsoid, so adjust for mean-sea-level + altitude = data['altitude'] + data['mean_sea_level'] + current_fix.altitude = altitude + + current_fix.speed = self.speed + current_fix.ground_course = self.ground_course + + self.fix_pub.publish(current_fix) + + if not math.isnan(data['utc_time']): + current_time_ref.time_ref = rospy.Time.from_sec(data['utc_time']) + self.time_ref_pub.publish(current_time_ref) + + elif 'RMC' in parsed_sentence: + data = parsed_sentence['RMC'] + + # Only publish a fix from RMC if the use_RMC flag is set. + if self.use_RMC: + current_fix.fix = True + current_fix.NumSat = data['num_satellites'] + + # current_fix.status.service = NavSatStatus.SERVICE_GPS + + latitude = data['latitude'] + if data['latitude_direction'] == 'S': + latitude = -latitude + current_fix.latitude = latitude + + longitude = data['longitude'] + if data['longitude_direction'] == 'W': + longitude = -longitude + current_fix.longitude = longitude + + current_fix.altitude = float('NaN') + + # current_fix.position_covariance_type = \ + # NavSatFix.COVARIANCE_TYPE_UNKNOWN + if data['fix_valid']: + current_fix.speed = data['speed'] + if not math.isnan(data['true_course']): + current_fix.ground_course = data['true_course'] + else: + current_fix.ground_course = self.ground_course + + self.fix_pub.publish(current_fix) + + if not math.isnan(data['utc_time']): + current_time_ref.time_ref = rospy.Time.from_sec(data['utc_time']) + self.time_ref_pub.publish(current_time_ref) + + else: + return False + + """Helper method for getting the frame_id with the correct TF prefix""" + + @staticmethod + def get_frame_id(): + frame_id = rospy.get_param('~frame_id', 'gps') + if frame_id[0] != "/": + """Add the TF prefix""" + prefix = "" + prefix_param = rospy.search_param('tf_prefix') + if prefix_param: + prefix = rospy.get_param(prefix_param) + if prefix[0] != "/": + prefix = "/%s" % prefix + return "%s/%s" % (prefix, frame_id) + else: + return frame_id diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/libnmea_navsat_driver/parser.py b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/libnmea_navsat_driver/parser.py new file mode 100644 index 0000000..6fe986e --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/libnmea_navsat_driver/parser.py @@ -0,0 +1,149 @@ +# Software License Agreement (BSD License) +# +# Copyright (c) 2013, Eric Perko +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the names of the authors nor the names of their +# affiliated organizations may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import re +import time +import calendar +import math +import logging +logger = logging.getLogger('rosout') + + +def safe_float(field): + try: + return float(field) + except ValueError: + return float('NaN') + + +def safe_int(field): + try: + return int(field) + except ValueError: + return 0 + + +def convert_latitude(field): + return safe_float(field[0:2]) + safe_float(field[2:]) / 60.0 + + +def convert_longitude(field): + return safe_float(field[0:3]) + safe_float(field[3:]) / 60.0 + + +def convert_time(nmea_utc): + # Get current time in UTC for date information + utc_struct = time.gmtime() # immutable, so cannot modify this one + utc_list = list(utc_struct) + # If one of the time fields is empty, return NaN seconds + if not nmea_utc[0:2] or not nmea_utc[2:4] or not nmea_utc[4:6]: + return float('NaN') + else: + hours = int(nmea_utc[0:2]) + minutes = int(nmea_utc[2:4]) + seconds = int(nmea_utc[4:6]) + utc_list[3] = hours + utc_list[4] = minutes + utc_list[5] = seconds + unix_time = calendar.timegm(tuple(utc_list)) + return unix_time + + +def convert_status_flag(status_flag): + if status_flag == "A": + return True + elif status_flag == "V": + return False + else: + return False + + +def convert_knots_to_mps(knots): + return safe_float(knots) * 0.514444444444 + + +# Need this wrapper because math.radians doesn't auto convert inputs +def convert_deg_to_rads(degs): + return math.radians(safe_float(degs)) + +"""Format for this is a sentence identifier (e.g. "GGA") as the key, with a +tuple of tuples where each tuple is a field name, conversion function and index +into the split sentence""" +parse_maps = { + "GGA": [ + ("fix_type", int, 6), + ("latitude", convert_latitude, 2), + ("latitude_direction", str, 3), + ("longitude", convert_longitude, 4), + ("longitude_direction", str, 5), + ("altitude", safe_float, 9), + ("mean_sea_level", safe_float, 11), + ("hdop", safe_float, 8), + ("num_satellites", safe_int, 7), + ("utc_time", convert_time, 1), + ], + "RMC": [ + ("utc_time", convert_time, 1), + ("fix_valid", convert_status_flag, 2), + ("latitude", convert_latitude, 3), + ("latitude_direction", str, 4), + ("longitude", convert_longitude, 5), + ("longitude_direction", str, 6), + ("speed", convert_knots_to_mps, 7), + ("true_course", convert_deg_to_rads, 8), + ] + } + + +def parse_nmea_sentence(nmea_sentence): + # Check for a valid nmea sentence + if not re.match('^\$G*.*\*[0-9A-Fa-f]{2}$', nmea_sentence): + logger.debug("Regex didn't match, sentence not valid NMEA? Sentence was: %s" + % repr(nmea_sentence)) + return False + fields = [field.strip(',') for field in nmea_sentence.split(',')] + + # Ignore the $ and talker ID portions (e.g. GP) + sentence_type = fields[0][3:] + + if not sentence_type in parse_maps: + logger.debug("Sentence type %s not in parse map, ignoring." + % repr(sentence_type)) + return False + + parse_map = parse_maps[sentence_type] + + parsed_sentence = {} + for entry in parse_map: + parsed_sentence[entry[0]] = entry[1](fields[entry[2]]) + + return {sentence_type: parsed_sentence} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/rc_joy b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/rc_joy new file mode 100644 index 0000000..740a53a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/rc_joy @@ -0,0 +1,90 @@ +#!/usr/bin/python + +# author: James Jackson + +import time +import rospy +from rosflight_msgs.msg import RCRaw +import pygame +import re + +rospy.init_node('rc_joy') +rc_pub = rospy.Publisher('RC', RCRaw, queue_size=10) + +pygame.display.init() +pygame.joystick.init() + +joy = pygame.joystick.Joystick(0) +joy.init() + +print "joystick:", joy.get_name() + +mapping = dict() + +if 'Taranis' in joy.get_name(): + print "found Taranis" + mapping['x'] = 0 + mapping['y'] = 1 + mapping['z'] = 3 + mapping['F'] = 2 + mapping['xsign'] = 1 + mapping['ysign'] = 1 + mapping['zsign'] = 1 + mapping['Fsign'] = 1 +elif 'Xbox' in joy.get_name() or 'X-Box' in joy.get_name(): + print "found xbox" + mapping['x'] = 3 + mapping['y'] = 4 + mapping['z'] = 0 + mapping['F'] = 1 + mapping['xsign'] = 1 + mapping['ysign'] = 1 + mapping['zsign'] = 1 + mapping['Fsign'] = -1 +else: + print "using realflght mapping" + mapping['x'] = 1 + mapping['y'] = 2 + mapping['z'] = 4 + mapping['F'] = 0 + mapping['xsign'] = 1 + mapping['ysign'] = 1 + mapping['zsign'] = 1 + mapping['Fsign'] = 1 + +# Main event loop +next_update_time = time.time() +while not rospy.is_shutdown(): + pygame.event.pump() + + time.sleep(0.02) + + # 50 Hz update + if time.time() > next_update_time: + + msg = RCRaw() + msg.header.stamp = rospy.Time.now() + + msg.values[0] = joy.get_axis(0) * 500 + 1500 + msg.values[1] = joy.get_axis(1) * 500 + 1500 + msg.values[2] = joy.get_axis(2) * 500 + 1500 + msg.values[3] = joy.get_axis(3) * 500 + 1500 + msg.values[4] = joy.get_axis(4) * 500 + 1500 + msg.values[5] = joy.get_button(0) * 1000 + 1000 + msg.values[6] = joy.get_button(1) * 1000 + 1000 + msg.values[7] = joy.get_button(2) * 1000 + 1000 + + rc_pub.publish(msg) + + # realflght mapping + else: + msg.values[0] = joy.get_axis(0) * 500 + 1500 + msg.values[1] = joy.get_axis(1) * 500 + 1500 + msg.values[2] = joy.get_axis(2) * -500 + 1500 + msg.values[3] = joy.get_axis(4) * 500 + 1500 + msg.values[4] = joy.get_axis(3) * 500 + 1500 + msg.values[5] = joy.get_button(0) * 1000 + 1000 + msg.values[6] = joy.get_button(1) * 1000 + 1000 + msg.values[7] = joy.get_button(2) * 1000 + 1000 + + rc_pub.publish(msg) diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/rc_sim b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/rc_sim new file mode 100644 index 0000000..f1c8d12 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/rc_sim @@ -0,0 +1,38 @@ +#!/usr/bin/python + +# author: James Jackson + +import time +import rospy +from rosflight_msgs.msg import RCRaw +from std_srvs.srv import Trigger + +rospy.init_node('dummy_rc') +rc_pub = rospy.Publisher('RC', RCRaw, queue_size=10) + +rc_message = RCRaw() + +for i in range(8): + rc_message.values[i] = 1500 +rc_message.values[2] = 1000 + +def arm(req): + global rc_message + rc_message.values[4] = 2000 + return True + +def disarm(req): + global rc_message + rc_message.values[4] = 1000 + return True + +arm_service = rospy.Service('arm', Trigger, arm) +disarm_service = rospy.Service('disarm', Trigger, disarm) + +next_update_time = time.time() + +while not rospy.is_shutdown(): + if time.time() > next_update_time: + rc_message.header.stamp = rospy.Time.now() + rc_pub.publish(rc_message) + next_update_time = time.time() + 0.02 diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/simple_pid.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/simple_pid.cpp new file mode 100644 index 0000000..2776e9a --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/simple_pid.cpp @@ -0,0 +1,153 @@ +/* + * Copyright (c) 2017 Robert Leishman, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +namespace rosflight_utils +{ +// +// Basic initialization +// +SimplePID::SimplePID() +{ + kp_ = 0.0; + ki_ = 0.0; + kd_ = 0.0; + integrator_ = 0.0; + differentiator_ = 0.0; + last_error_ = 0.0; + last_state_ = 0.0; + tau_ = 0.0; +} + +// +// Initialize the controller +// +SimplePID::SimplePID(double p, double i, double d, double max, double min, double tau) : + kp_(p), ki_(i), kd_(d), max_(max), min_(min), tau_(tau) +{ + integrator_ = 0.0; + differentiator_ = 0.0; + last_error_ = 0.0; + last_state_ = 0.0; +} + +// +// Compute the control; +// +double SimplePID::computePID(double desired, double current, double dt, double x_dot) +{ + double error = desired - current; + + // Don't do stupid things (like divide by nearly zero, gigantic control jumps) + if (dt < 0.00001 || std::abs(error) > 9999999) + { + return 0.0; + } + + if (dt > 1.0) + { + // This means that this is a ''stale'' controller and needs to be reset. + // This would happen if we have been operating in a different mode for a while + // and will result in some enormous integrator. + // Or, it means we are disarmed and shouldn't integrate + // Setting dt for this loop will mean that the integrator and dirty derivative + // doesn't do anything this time but will keep it from exploding. + dt = 0.0; + differentiator_ = 0.0; + } + + double p_term = error*kp_; + double i_term = 0.0; + double d_term = 0.0; + + + // Calculate Derivative Term + if (kd_ > 0.0) + { + if (std::isfinite(x_dot)) + { + d_term = kd_ * x_dot; + } + else if (dt > 0.0) + { + // Noise reduction (See "Small Unmanned Aircraft". Chapter 6. Slide 31/33) + // d/dx w.r.t. error:: differentiator_ = (2*tau_ - dt)/(2*tau_ + dt)*differentiator_ + 2/(2*tau_ + dt)*(error - + // last_error_); + differentiator_ = + (2 * tau_ - dt) / (2 * tau_ + dt) * differentiator_ + 2 / (2 * tau_ + dt) * (current - last_state_); + d_term = kd_* differentiator_; + } + } + + // Calculate Integrator Term + if (ki_ > 0.0) + { + integrator_ += dt / 2 * (error + last_error_); // (trapezoidal rule) + i_term = ki_ * integrator_; + } + + // Save off this state for next loop + last_error_ = error; + last_state_ = current; + + // Sum three terms + double u = p_term + i_term - d_term; + + return u; + + // Integrator anti-windup +// double u_sat = saturate(u, min_, max_); +// if (u != u_sat && std::fabs(i_term) > fabs(u - p_term + d_term)) +// { +// // If we are at the saturation limits, then make sure the integrator doesn't get +// // bigger if it won't do anything (except take longer to unwind). Just set it to the +// // largest value it could be to max out the control +// integrator_ = (u_sat - p_term + d_term) / ki_; +// } + +// return u_sat; +} + + +// +// Late initialization or redo +// +void SimplePID::setGains(double p, double i, double d, double tau) +{ + //! \todo Should we really be zeroing this while we are gain tuning? + kp_ = p; + ki_ = i; + kd_ = d; + tau_ = tau; +} + +} // namespace relative_nav diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/turbomath.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/turbomath.cpp new file mode 100644 index 0000000..d8829a6 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/turbomath.cpp @@ -0,0 +1,274 @@ +/* + * Copyright (c) 2017 James Jackson, BYU MAGICC Lab. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +#include + +static const int16_t atan_lookup_table[250] = { + 0, 40, 80, 120, 160, 200, 240, 280, 320, 360, 400, 440, 480, 520, 559, + 599, 639, 679, 719, 759, 798, 838, 878, 917, 957, 997, 1036, 1076, 1115, 1155, + 1194, 1234, 1273, 1312, 1352, 1391, 1430, 1469, 1508, 1548, 1587, 1626, 1664, 1703, 1742, + 1781, 1820, 1858, 1897, 1935, 1974, 2012, 2051, 2089, 2127, 2166, 2204, 2242, 2280, 2318, + 2355, 2393, 2431, 2469, 2506, 2544, 2581, 2618, 2656, 2693, 2730, 2767, 2804, 2841, 2878, + 2915, 2951, 2988, 3024, 3061, 3097, 3133, 3169, 3206, 3241, 3277, 3313, 3349, 3385, 3420, + 3456, 3491, 3526, 3561, 3596, 3631, 3666, 3701, 3736, 3771, 3805, 3839, 3874, 3908, 3942, + 3976, 4010, 4044, 4078, 4112, 4145, 4179, 4212, 4245, 4278, 4311, 4344, 4377, 4410, 4443, + 4475, 4508, 4540, 4572, 4604, 4636, 4668, 4700, 4732, 4764, 4795, 4827, 4858, 4889, 4920, + 4951, 4982, 5013, 5044, 5074, 5105, 5135, 5166, 5196, 5226, 5256, 5286, 5315, 5345, 5375, + 5404, 5434, 5463, 5492, 5521, 5550, 5579, 5608, 5636, 5665, 5693, 5721, 5750, 5778, 5806, + 5834, 5862, 5889, 5917, 5944, 5972, 5999, 6026, 6053, 6080, 6107, 6134, 6161, 6187, 6214, + 6240, 6267, 6293, 6319, 6345, 6371, 6397, 6422, 6448, 6473, 6499, 6524, 6549, 6574, 6599, + 6624, 6649, 6674, 6698, 6723, 6747, 6772, 6796, 6820, 6844, 6868, 6892, 6916, 6940, 6963, + 6987, 7010, 7033, 7057, 7080, 7103, 7126, 7149, 7171, 7194, 7217, 7239, 7261, 7284, 7306, + 7328, 7350, 7372, 7394, 7416, 7438, 7459, 7481, 7502, 7524, 7545, 7566, 7587, 7608, 7629, + 7650, 7671, 7691, 7712, 7733, 7753, 7773, 7794, 7814, 7834}; + + +static const int16_t asin_lookup_table[250] = { + 0, 40, 80, 120, 160, 200, 240, 280, 320, 360, 400, 440, 480, 520, 560, + 600, 640, 681, 721, 761, 801, 841, 881, 921, 961, 1002, 1042, 1082, 1122, 1163, + 1203, 1243, 1284, 1324, 1364, 1405, 1445, 1485, 1526, 1566, 1607, 1647, 1688, 1729, 1769, + 1810, 1851, 1891, 1932, 1973, 2014, 2054, 2095, 2136, 2177, 2218, 2259, 2300, 2341, 2382, + 2424, 2465, 2506, 2547, 2589, 2630, 2672, 2713, 2755, 2796, 2838, 2880, 2921, 2963, 3005, + 3047, 3089, 3131, 3173, 3215, 3257, 3300, 3342, 3384, 3427, 3469, 3512, 3554, 3597, 3640, + 3683, 3726, 3769, 3812, 3855, 3898, 3941, 3985, 4028, 4072, 4115, 4159, 4203, 4246, 4290, + 4334, 4379, 4423, 4467, 4511, 4556, 4601, 4645, 4690, 4735, 4780, 4825, 4870, 4916, 4961, + 5007, 5052, 5098, 5144, 5190, 5236, 5282, 5329, 5375, 5422, 5469, 5515, 5562, 5610, 5657, + 5704, 5752, 5800, 5848, 5896, 5944, 5992, 6041, 6089, 6138, 6187, 6236, 6286, 6335, 6385, + 6435, 6485, 6535, 6586, 6637, 6687, 6739, 6790, 6841, 6893, 6945, 6997, 7050, 7102, 7155, + 7208, 7262, 7315, 7369, 7423, 7478, 7532, 7587, 7643, 7698, 7754, 7810, 7867, 7923, 7981, + 8038, 8096, 8154, 8213, 8271, 8331, 8390, 8450, 8511, 8572, 8633, 8695, 8757, 8820, 8883, + 8947, 9011, 9076, 9141, 9207, 9273, 9340, 9407, 9476, 9545, 9614, 9684, 9755, 9827, 9900, + 9973, 10047, 10122, 10198, 10275, 10353, 10432, 10512, 10593, 10675, 10759, 10844, 10930, 11018, 11107, + 11198, 11290, 11385, 11481, 11580, 11681, 11784, 11890, 11999, 12111, 12226, 12346, 12469, 12597, 12730, + 12870, 13017, 13171, 13336, 13513, 13705, 13917, 14157, 14442, 14813}; + +static const int16_t sin_lookup_table[250] = { + 0, 63, 126, 188, 251, 314, 377, 440, 502, 565, 628, 691, 753, 816, 879, + 941, 1004, 1066, 1129, 1191, 1253, 1316, 1378, 1440, 1502, 1564, 1626, 1688, 1750, 1812, + 1874, 1935, 1997, 2059, 2120, 2181, 2243, 2304, 2365, 2426, 2487, 2548, 2608, 2669, 2730, + 2790, 2850, 2910, 2970, 3030, 3090, 3150, 3209, 3269, 3328, 3387, 3446, 3505, 3564, 3623, + 3681, 3740, 3798, 3856, 3914, 3971, 4029, 4086, 4144, 4201, 4258, 4315, 4371, 4428, 4484, + 4540, 4596, 4652, 4707, 4762, 4818, 4873, 4927, 4982, 5036, 5090, 5144, 5198, 5252, 5305, + 5358, 5411, 5464, 5516, 5569, 5621, 5673, 5724, 5776, 5827, 5878, 5929, 5979, 6029, 6079, + 6129, 6179, 6228, 6277, 6326, 6374, 6423, 6471, 6518, 6566, 6613, 6660, 6707, 6753, 6800, + 6845, 6891, 6937, 6982, 7026, 7071, 7115, 7159, 7203, 7247, 7290, 7333, 7375, 7417, 7459, + 7501, 7543, 7584, 7624, 7665, 7705, 7745, 7785, 7824, 7863, 7902, 7940, 7978, 8016, 8053, + 8090, 8127, 8163, 8200, 8235, 8271, 8306, 8341, 8375, 8409, 8443, 8477, 8510, 8543, 8575, + 8607, 8639, 8671, 8702, 8733, 8763, 8793, 8823, 8852, 8881, 8910, 8938, 8966, 8994, 9021, + 9048, 9075, 9101, 9127, 9152, 9178, 9202, 9227, 9251, 9274, 9298, 9321, 9343, 9365, 9387, + 9409, 9430, 9451, 9471, 9491, 9511, 9530, 9549, 9567, 9585, 9603, 9620, 9637, 9654, 9670, + 9686, 9701, 9716, 9731, 9745, 9759, 9773, 9786, 9799, 9811, 9823, 9834, 9846, 9856, 9867, + 9877, 9887, 9896, 9905, 9913, 9921, 9929, 9936, 9943, 9950, 9956, 9961, 9967, 9972, 9976, + 9980, 9984, 9987, 9990, 9993, 9995, 9997, 9998, 9999, 10000}; + +float sign(float y) +{ + return (0 < y) - (y < 0); +} + + +float asin_lookup(float x) +{ + static const float max = 1.0; + static const float min = 0.0; + static const int16_t num_entries = 250; + static float dx = 0.0; + static const float scale = 10000.0; + + float t = (x - min) / (max - min) * num_entries; + uint8_t index = (uint8_t)t; + dx = t - (float)index; + + if (index >= num_entries) + { + return max; + } + else if (index < num_entries - 1) + { + return (float)asin_lookup_table[index]/scale + + dx * (float)(asin_lookup_table[index + 1] - asin_lookup_table[index]) / scale; + } + else + { + return (float)asin_lookup_table[index]/scale + + dx * (float)(asin_lookup_table[index] - asin_lookup_table[index - 1]) / scale; + } +} + +float turboacos(float x) +{ + if (x < 0) + return M_PI + asin_lookup(-x); + else + return M_PI - asin_lookup(x); +} + + +float turboasin(float x) +{ + if (x < 0) + return -asin_lookup(-x); + else + return asin_lookup(x); +} + +float sin_lookup(float x) +{ + static const float max = 1.0; + static const float min = 0.0; + static const int16_t num_entries = 250; + static float dx = 0.0; + static const float scale = 10000.0; + + float t = (x - min) / (max - min) * num_entries; + uint8_t index = (uint8_t)t; + dx = t - (float)index; + + if (index >= num_entries) + return max; + else if (index < num_entries - 1) + return (float)sin_lookup_table[index]/scale + + dx * (float)(sin_lookup_table[index + 1] - sin_lookup_table[index]) / scale; + else + return (float)sin_lookup_table[index]/scale + + dx * (float)(sin_lookup_table[index] - sin_lookup_table[index - 1]) / scale; +} + +float turbosin(float x) +{ + while (x > M_PI) + x -= 2.0*M_PI; + while (x <= -M_PI) + x += 2.0*M_PI; + + if (0 <= x && x<=M_PI / 2.0) + return sin_lookup(x); + else if (-M_PI / 2.0 <= x && x < 0) + return -sin_lookup(-x); + else if (M_PI/2.0 < x) + return sin_lookup(M_PI - x); + else + return -sin_lookup(x + M_PI); +} + +float turbocos(float x) +{ + return turbosin(x + M_PI); +} + + +float atan_lookup(float x) +{ + if (x < 0) + return -1*atan_lookup(-1 * x); + if (x > 1.0) + return M_PI - atan_lookup(1.0/x); + + static const float max = 1.0; + static const float min = 0.0; + static const int16_t num_entries = 250; + static float dx = 0.0; + static const float scale = 10000.0; + + float t = (x - min) / (max - min) * num_entries; + uint8_t index = (uint8_t)t; + dx = t - (float)index; + + if (index >= num_entries) + return max; + else if (index < num_entries - 1) + return (float)atan_lookup_table[index]/scale + + dx * (float)(atan_lookup_table[index + 1] - atan_lookup_table[index]) / scale; + else + return (float)atan_lookup_table[index]/scale + + dx * (float)(atan_lookup_table[index] - atan_lookup_table[index - 1]) / scale; +} + + +float turboatan2(float y, float x) +{ + if (y == 0) + { + if (x < 0) + return M_PI; + else + return 0; + } + + else if (x == 0) + { + return M_PI/2.0 * sign(y); + } + + else + { + float arctan = atan_lookup(x / y); + + if (y > 0) + return M_PI/2.0 - arctan; + else if (y < 0) + return -M_PI/2.0 - arctan; + else if (x < 0) + return arctan + M_PI; + else + return arctan; + } +} + +double turbopow(double a, double b) +{ + union{ + double d; + int x[2]; + } u = {a}; + u.x[1] = (int)(b*(u.x[1] - 1072632447) + 1072632447); + u.x[0] = 0; + return u.d; +} + +float turboInvSqrt(float x) +{ + long i; + float x2, y; + const float threehalfs = 1.5F; + + x2 = x * 0.5F; + y = x; + i = * ( long * ) &y; // evil floating point bit level hacking + i = 0x5f3759df - ( i >> 1 ); + y = * ( float * ) &i; + y = y * ( threehalfs - ( x2 * y * y ) ); // 1st iteration + // y = y * ( threehalfs - ( x2 * y * y ) ); // 2nd iteration, this can be removed + + return y; +} diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/viz_mag.cpp b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/viz_mag.cpp new file mode 100644 index 0000000..21bf7ec --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/rosflight/rosflight_utils/src/viz_mag.cpp @@ -0,0 +1,99 @@ +#include + +namespace rosflight_utils +{ + +VizMag::VizMag() : + nh_private_("~") +{ + // retrieve params + + // initialize variables + mag_sum_ = 0; + mag_skip_ = 20; + mag_count_ = 0; + mag_throttle_ = 0; + + // Set up Publishers and Subscribers + mag_sub_ = nh_.subscribe("/magnetometer", 1, &VizMag::magCallback, this); + + mag_pub_ = nh_.advertise( "viz/magnetometer", 1 ); + pts_pub_ = nh_.advertise( "viz/cloud", 1); +} + +void VizMag::magCallback(const sensor_msgs::MagneticFieldConstPtr &msg) +{ + if (mag_throttle_ > mag_skip_) + { + // unpack message + double x = msg->magnetic_field.x; + double y = msg->magnetic_field.y; + double z = msg->magnetic_field.z; + + // get euler angles from vector (assume no roll) + double yaw = atan2(y, x); + double pitch = atan2(-z, sqrt(x*x + y*y)); + + // convert to body quaternion and rotation into the vehicle frame + tf::Quaternion q_v = tf::createQuaternionFromRPY(0, pitch, yaw); + + // pack data into pose message + geometry_msgs::PoseStamped pose_msg; + pose_msg.header = msg->header; + pose_msg.header.frame_id = "fixed_frame"; + pose_msg.pose.position.x = 0; + pose_msg.pose.position.y = 0; + pose_msg.pose.position.z = 0; + tf::quaternionTFToMsg(q_v, pose_msg.pose.orientation); + + // Publish the messages + mag_pub_.publish(pose_msg); + + + // MEASUREMENT CLOUD // + + // store the current measurement + geometry_msgs::Point p; + p.x = x; + p.y = y; + p.z = z; + pts_list_.push_back(p); + + // begin packing marker message + visualization_msgs::Marker pts_msg; + pts_msg.header.frame_id = "fixed_frame"; + pts_msg.header.stamp = msg->header.stamp; + pts_msg.type = visualization_msgs::Marker::POINTS; + pts_msg.action = visualization_msgs::Marker::ADD; + + // set points style + pts_msg.scale.x = 0.1; + pts_msg.scale.y = pts_msg.scale.x; + pts_msg.scale.z = pts_msg.scale.x; + pts_msg.color.a = 1.0; + pts_msg.color.r = 0.0; + pts_msg.color.g = 1.0; + pts_msg.color.b = 0.0; + + for (uint32_t i = 0; i < pts_list_.size(); ++i) + { + pts_msg.points.push_back(pts_list_[i]); + } + + // publish point cloud + pts_pub_.publish(pts_msg); + } + mag_throttle_++; +} + + +} // namespace rosflight + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "viz_mag_node"); + rosflight::VizMag thing; + ros::spin(); + return 0; +} + diff --git a/Gazebo_Hector_Test/src/hector_quadrotor/tutorials.rosinstall b/Gazebo_Hector_Test/src/hector_quadrotor/tutorials.rosinstall new file mode 100644 index 0000000..bdfce35 --- /dev/null +++ b/Gazebo_Hector_Test/src/hector_quadrotor/tutorials.rosinstall @@ -0,0 +1,5 @@ +- git: {local-name: hector_quadrotor, uri: 'https://github.com/tu-darmstadt-ros-pkg/hector_quadrotor.git', version: indigo-devel} +- git: {local-name: hector_slam, uri: 'https://github.com/tu-darmstadt-ros-pkg/hector_slam.git', version: catkin} +- git: {local-name: hector_localization, uri: 'https://github.com/tu-darmstadt-ros-pkg/hector_localization.git', version: catkin} +- git: {local-name: hector_gazebo, uri: 'https://github.com/tu-darmstadt-ros-pkg/hector_gazebo.git', version: indigo-devel} +- git: {local-name: hector_models, uri: 'https://github.com/tu-darmstadt-ros-pkg/hector_models.git', version: indigo-devel} diff --git a/sdformat/.gitignore b/sdformat/.gitignore new file mode 100644 index 0000000..378eac2 --- /dev/null +++ b/sdformat/.gitignore @@ -0,0 +1 @@ +build diff --git a/sdformat/AUTHORS b/sdformat/AUTHORS new file mode 100644 index 0000000..d98f8de --- /dev/null +++ b/sdformat/AUTHORS @@ -0,0 +1 @@ +Nate Koenig diff --git a/sdformat/CMakeLists.txt b/sdformat/CMakeLists.txt new file mode 100644 index 0000000..81ba1f7 --- /dev/null +++ b/sdformat/CMakeLists.txt @@ -0,0 +1,306 @@ +cmake_minimum_required(VERSION 2.8.6 FATAL_ERROR) + +if(COMMAND CMAKE_POLICY) + CMAKE_POLICY(SET CMP0003 NEW) + CMAKE_POLICY(SET CMP0004 NEW) +endif(COMMAND CMAKE_POLICY) +enable_testing() + +# with -fPIC +if(UNIX AND NOT WIN32) + set (CMAKE_INSTALL_PREFIX "/usr" CACHE STRING "Install Prefix") + find_program(CMAKE_UNAME uname /bin /usr/bin /usr/local/bin ) + if(CMAKE_UNAME) + exec_program(uname ARGS -m OUTPUT_VARIABLE CMAKE_SYSTEM_PROCESSOR) + set(CMAKE_SYSTEM_PROCESSOR ${CMAKE_SYSTEM_PROCESSOR} CACHE INTERNAL + "processor type (i386 and x86_64)") + if(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") + ADD_DEFINITIONS(-fPIC) + endif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64") + endif(CMAKE_UNAME) +endif() + +project (SDFormat) +string (TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER) + +# The protocol version has nothing to do with the package version set below. +# It represents the current version of sdformat implement by the software +set (SDF_PROTOCOL_VERSION 1.6) + +set (SDF_MAJOR_VERSION 4) +set (SDF_MINOR_VERSION 4) +set (SDF_PATCH_VERSION 0) + +set (SDF_VERSION ${SDF_MAJOR_VERSION}.${SDF_MINOR_VERSION}) +set (SDF_VERSION_FULL ${SDF_MAJOR_VERSION}.${SDF_MINOR_VERSION}.${SDF_PATCH_VERSION}) + +set (project_cmake_dir ${PROJECT_SOURCE_DIR}/cmake + CACHE PATH "Location of CMake scripts") + +message (STATUS "${PROJECT_NAME} version ${SDF_VERSION_FULL}") +set (CMAKE_INCLUDE_DIRECTORIES_PROJECT_BEFORE ON) + +# Include GNUInstallDirs to get canonical paths +include(GNUInstallDirs) + +# Default test type for test all over source +set(TEST_TYPE "UNIT") + +# developer's option to cache PKG_CONFIG_PATH and +# LD_LIBRARY_PATH for local installs +if(PKG_CONFIG_PATH) + set (ENV{PKG_CONFIG_PATH} ${PKG_CONFIG_PATH}:$ENV{PKG_CONFIG_PATH}) +endif() +if(LD_LIBRARY_PATH) + set (ENV{LD_LIBRARY_PATH} ${LD_LIBRARY_PATH}:$ENV{LD_LIBRARY_PATH}) +endif() + +set (INCLUDE_INSTALL_DIR "${CMAKE_INSTALL_INCLUDEDIR}/sdformat-${SDF_VERSION}/sdf") +set (LIB_INSTALL_DIR ${CMAKE_INSTALL_LIBDIR} CACHE STRING "Installation directory for libraries (relative to CMAKE_INSTALL_PREFIX)") +set (BIN_INSTALL_DIR ${CMAKE_INSTALL_BINDIR} CACHE STRING "Installation directory for binaries (relative to CMAKE_INSTALL_PREFIX)") + +set (USE_FULL_RPATH OFF CACHE BOOL "Set to true to enable full rpath") + + +if (USE_FULL_RPATH) + # use, i.e. don't skip the full RPATH for the build tree + set(CMAKE_SKIP_BUILD_RPATH FALSE) + + # when building, don't use the install RPATH already + # (but later on when installing) + set(CMAKE_BUILD_WITH_INSTALL_RPATH FALSE) + + set(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/${LIB_INSTALL_DIR}") + + # add the automatically determined parts of the RPATH + # which point to directories outside the build tree to the install RPATH + set(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) + + # the RPATH to be used when installing, but only if its not a system directory + list(FIND CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES "${CMAKE_INSTALL_PREFIX}/${LIB_INSTALL_DIR}" isSystemDir) + if("${isSystemDir}" STREQUAL "-1") + set(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/${LIB_INSTALL_DIR}") + endif("${isSystemDir}" STREQUAL "-1") +endif() + +set (BUILD_SDF ON CACHE INTERNAL "Build SDF" FORCE) +set (build_errors "" CACHE INTERNAL "build errors" FORCE) +set (build_warnings "" CACHE INTERNAL "build warnings" FORCE) + +set (sdf_cmake_dir ${PROJECT_SOURCE_DIR}/cmake CACHE PATH + "Location of CMake scripts") + +include (${sdf_cmake_dir}/SDFUtils.cmake) + +message (STATUS "\n\n====== Finding 3rd Party Packages ======") + # Use of tinyxml. System installation on UNIX. Internal copy on WIN +if (UNIX) + message (STATUS "Using system tinyxml") + set (USE_EXTERNAL_TINYXML True) +elseif(WIN32) + message (STATUS "Using internal tinyxml code") + set (USE_EXTERNAL_TINYXML False) +else() + message (STATUS "Unknown platform") + BUILD_ERROR("Unknown platform") +endif() +include (${sdf_cmake_dir}/SearchForStuff.cmake) +message (STATUS "----------------------------------------\n") + +##################################### +# Set the default build type +if (NOT CMAKE_BUILD_TYPE) + set (CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING + "Choose the type of build, options are: Debug Release RelWithDebInfo Profile Check" FORCE) +endif (NOT CMAKE_BUILD_TYPE) +string(TOUPPER ${CMAKE_BUILD_TYPE} CMAKE_BUILD_TYPE_UPPERCASE) + +set (BUILD_TYPE_PROFILE FALSE) +set (BUILD_TYPE_RELEASE FALSE) +set (BUILD_TYPE_RELWITHDEBINFO FALSE) +set (BUILD_TYPE_DEBUG FALSE) + +if ("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "PROFILE") + set (BUILD_TYPE_PROFILE TRUE) +elseif ("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "RELEASE") + set (BUILD_TYPE_RELEASE TRUE) +elseif ("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "RELWITHDEBINFO") + set (BUILD_TYPE_RELWITHDEBINFO TRUE) +elseif ("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "DEBUG") + set (BUILD_TYPE_DEBUG TRUE) +elseif ("${CMAKE_BUILD_TYPE_UPPERCASE}" STREQUAL "COVERAGE") + include (${project_cmake_dir}/CodeCoverage.cmake) + set (BUILD_TYPE_DEBUG TRUE) + SETUP_TARGET_FOR_COVERAGE(coverage ctest coverage) +else() + build_error("CMAKE_BUILD_TYPE ${CMAKE_BUILD_TYPE} unknown. Valid options are: Debug Release RelWithDebInfo Profile Check") +endif() + +##################################### +# Handle CFlags +unset (CMAKE_C_FLAGS_ALL CACHE) +unset (CMAKE_CXX_FLAGS CACHE) + +# USE_HOST_CFLAGS (default TRUE) +# Will check building host machine for proper cflags +if(NOT DEFINED USE_HOST_CFLAGS OR USE_HOST_CFLAGS) + message(STATUS "Enable host CFlags") + include (${project_cmake_dir}/HostCFlags.cmake) +endif() + +# USE_UPSTREAM_CFLAGS (default TRUE) +# Will use predefined ignition developers cflags +if(NOT DEFINED USE_UPSTREAM_CFLAGS OR USE_UPSTREAM_CFLAGS) + message(STATUS "Enable upstream CFlags") + include(${project_cmake_dir}/DefaultCFlags.cmake) +endif() + +# Check if warning options are avaliable for the compiler and return WARNING_CXX_FLAGS variable +if (MSVC) + set(WARN_LEVEL "/W4") + + # Unable to be filtered flags (failing due to limitations in filter_valid_compiler_warnings) + # Handling exceptions rightly and ignore unknown pragmas + set(UNFILTERED_FLAGS "/EHsc /wd4068") +else() + # Equivalent to Wall (according to man gcc) but removed the unknown pragmas since we use + # MSVC only pragmas all over the code + list(APPEND WARN_LEVEL -Waddress -Warray-bounds -Wcomment -Wformat -Wnonnull) + list(APPEND WARN_LEVEL -Wparentheses -Wreorder -Wreturn-type) + list(APPEND WARN_LEVEL -Wsequence-point -Wsign-compare -Wstrict-aliasing) + list(APPEND WARN_LEVEL -Wstrict-overflow=1 -Wswitch -Wtrigraphs -Wuninitialized) + list(APPEND WARN_LEVEL -Wunused-function -Wunused-label -Wunused-value) + list(APPEND WARN_LEVEL -Wunused-variable -Wvolatile-register-var) + + # Unable to be filtered flags (failing due to limitations in filter_valid_compiler_warnings) + set(UNFILTERED_FLAGS "-Wc++11-compat") +endif() + +filter_valid_compiler_warnings(${WARN_LEVEL} -Wextra -Wno-long-long + -Wno-unused-value -Wno-unused-value -Wno-unused-value -Wno-unused-value + -Wfloat-equal -Wshadow -Winit-self -Wswitch-default + -Wmissing-include-dirs -pedantic -Wno-pragmas) +set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}${WARNING_CXX_FLAGS} ${UNFILTERED_FLAGS}") + +################################################# +# OS Specific initialization +if (UNIX) + sdf_setup_unix() +endif () + +if (WIN32) + sdf_setup_windows() +endif () + +if (APPLE) + sdf_setup_apple() +endif () + +################################################# +# Print warnings and errors +if ( build_warnings ) + message(STATUS "BUILD WARNINGS") + foreach (msg ${build_warnings}) + message(STATUS ${msg}) + endforeach () + message(STATUS "END BUILD WARNINGS\n") +endif (build_warnings) + +########### Add uninstall target ############### +configure_file( + "${CMAKE_CURRENT_SOURCE_DIR}/cmake/cmake_uninstall.cmake.in" + "${CMAKE_CURRENT_BINARY_DIR}/cmake/cmake_uninstall.cmake" + IMMEDIATE @ONLY) +add_custom_target(uninstall + "${CMAKE_COMMAND}" -P + "${CMAKE_CURRENT_BINARY_DIR}/cmake/cmake_uninstall.cmake") + +if (build_errors) + message(STATUS "BUILD ERRORS: These must be resolved before compiling.") + foreach (msg ${build_errors}) + message(STATUS ${msg}) + endforeach () + message(STATUS "END BUILD ERRORS\n") + message (FATAL_ERROR "Errors encountered in build. Please see the BUILD ERRORS above.") + +else (buid_errors) + + ######################################## + # Write the config.h file + configure_file (${sdf_cmake_dir}/sdf_config.h.in + ${PROJECT_BINARY_DIR}/sdf/sdf_config.h) + sdf_install_includes("" ${PROJECT_BINARY_DIR}/sdf/sdf_config.h) + + message (STATUS "C Flags:${CMAKE_CXX_FLAGS} ${CMAKE_CXX_FLAGS_${CMAKE_BUILD_TYPE}}") + message (STATUS "Build Type: ${CMAKE_BUILD_TYPE}") + message (STATUS "Install path: ${CMAKE_INSTALL_PREFIX}") + + if (BUILD_SDF) + include_directories(include + ${PROJECT_BINARY_DIR} + ${PROJECT_BINARY_DIR}/include + ) + + link_directories(${PROJECT_BINARY_DIR}/src) + + add_subdirectory(test) + add_subdirectory(src) + add_subdirectory(include/sdf) + add_subdirectory(sdf) + add_subdirectory(doc) + endif(BUILD_SDF) + + ######################################## + # Make the package config file + configure_file(${CMAKE_SOURCE_DIR}/cmake/sdformat_pc.in + ${CMAKE_CURRENT_BINARY_DIR}/cmake/sdformat.pc @ONLY) + install(FILES ${CMAKE_CURRENT_BINARY_DIR}/cmake/sdformat.pc DESTINATION + ${LIB_INSTALL_DIR}/pkgconfig COMPONENT pkgconfig) + + ######################################## + # Configure documentation uploader + configure_file("${CMAKE_SOURCE_DIR}/cmake/upload_doc.sh.in" + ${CMAKE_BINARY_DIR}/upload_doc.sh @ONLY) + + ######################################## + # Make the cmake config files + set(PKG_NAME ${PROJECT_NAME}) + set(PKG_LIBRARIES sdformat) + set(cmake_conf_file "cmake/sdf_config.cmake") + set(cmake_conf_version_file "cmake/SDFormatConfigVersion.cmake") + configure_file("${CMAKE_CURRENT_SOURCE_DIR}/${cmake_conf_file}.in" "${CMAKE_CURRENT_BINARY_DIR}/SDFormatConfig.cmake" @ONLY) + # Use write_basic_package_version_file to generate a ConfigVersion file that + # allow users of gazebo to specify the API or version to depend on + # TODO: keep this instruction until deprecate Ubuntu/Precise and update with + # https://github.com/Kitware/CMake/blob/v2.8.8/Modules/CMakePackageConfigHelpers.cmake + include(WriteBasicConfigVersionFile) + write_basic_config_version_file( + ${CMAKE_CURRENT_BINARY_DIR}/${cmake_conf_version_file} + VERSION "${SDF_VERSION_FULL}" + COMPATIBILITY SameMajorVersion) + install(FILES + ${CMAKE_CURRENT_BINARY_DIR}/SDFormatConfig.cmake + ${CMAKE_CURRENT_BINARY_DIR}/${cmake_conf_version_file} + DESTINATION + ${LIB_INSTALL_DIR}/cmake/${PROJECT_NAME_LOWER}/ + COMPONENT cmake) + + ######################################## + # Package Creation: + include (${sdf_cmake_dir}/sdf_cpack.cmake) + set (CPACK_PACKAGE_VERSION "${SDF_VERSION_FULL}") + set (CPACK_PACKAGE_VERSION_MAJOR "${SDF_MAJOR_VERSION}") + set (CPACK_PACKAGE_VERSION_MINOR "${SDF_MINOR_VERSION}") + set (CPACK_PACKAGE_VERSION_PATCH "${SDF_PATCH_VERSION}") + + if (CPACK_GENERATOR) + message(STATUS "Found CPack generators: ${CPACK_GENERATOR}") + + configure_file("${sdf_cmake_dir}/cpack_options.cmake.in" + ${SDF_CPACK_CFG_FILE} @ONLY) + set(CPACK_PROJECT_CONFIG_FILE ${SDF_CPACK_CFG_FILE}) + include (CPack) + endif() + + message(STATUS "Configuration successful. Type make to compile sdf") +endif(build_errors) diff --git a/sdformat/COPYING b/sdformat/COPYING new file mode 100644 index 0000000..4909afd --- /dev/null +++ b/sdformat/COPYING @@ -0,0 +1,178 @@ + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + diff --git a/sdformat/Changelog.md b/sdformat/Changelog.md new file mode 100644 index 0000000..9f3f430 --- /dev/null +++ b/sdformat/Changelog.md @@ -0,0 +1,345 @@ +## SDFormat 4.0 + +### SDFormat 4.x.x (2017-xx-xx) + +### SDFormat 4.4.0 (2017-10-26) + +1. Add ODE parallelization parameters: threaded islands and position correction + * [Pull request 380](https://bitbucket.org/osrf/sdformat/pull-request/380) + +1. surface.sdf: expand documentation of friction and slip coefficients + * [Pull request 343](https://bitbucket.org/osrf/sdformat/pull-request/343) + +1. Add preserveFixedJoint option to the URDF parser + * [Pull request 352](https://bitbucket.org/osrf/sdformat/pull-request/352) + +1. Add light as child of link + * [Pull request 373](https://bitbucket.org/osrf/sdformat/pull-request/373) + +### SDFormat 4.3.2 (2017-07-19) + +1. Add documentation for `Element::GetFirstElement()` and `Element::GetNextElement()` + * [Pull request 341](https://bitbucket.org/osrf/sdformat/pull-request/341) + +1. Fix parser to read plugin child elements within an `` + * [Pull request 350](https://bitbucket.org/osrf/sdformat/pull-request/350) + +### SDFormat 4.3.1 (2017-03-24) + +1. Fix segmentation Fault in `sdf::getBestSupportedModelVersion` + * [Pull request 327](https://bitbucket.org/osrf/sdformat/pull-requests/327) + * [Issue 152](https://bitbucket.org/osrf/sdformat/issues/152) + +### SDFormat 4.3.0 (2017-03-20) + +1. Choosing models with more recent sdf version with `` tag + * [Pull request 291](https://bitbucket.org/osrf/sdformat/pull-request/291) + * [Issue 123](https://bitbucket.org/osrf/sdformat/issues/123) + +1. Added `` to 1.6 surface contact parameters + * [Pull request 318](https://bitbucket.org/osrf/sdformat/pull-request/318) + +1. Support light insertion in state + * [Pull request 325](https://bitbucket.org/osrf/sdformat/pull-request/325) + +1. Case insensitive boolean strings + * [Pull request 322](https://bitbucket.org/osrf/sdformat/pull-request/322) + +1. Enable coverage testing + * [Pull request 317](https://bitbucket.org/osrf/sdformat/pull-request/317) + +1. Add `friction_model` parameter to ode solver + * [Pull request 294](https://bitbucket.org/osrf/sdformat/pull-request/294) + * [Gazebo pull request 1522](https://bitbucket.org/osrf/gazebo/pull-request/1522) + +1. Added `sampling` parameter to `` SDF element. + * [Pull request 293](https://bitbucket.org/osrf/sdformat/pull-request/293) + +1. Added Migration guide + * [Pull request 290](https://bitbucket.org/osrf/sdformat/pull-request/290) + +1. Add cmake `@PKG_NAME@_LIBRARY_DIRS` variable to cmake config file + * [Pull request 292](https://bitbucket.org/osrf/sdformat/pull-request/292) + +### SDFormat 4.2.0 (2016-10-10) + +1. Added tag to specify ODE friction model. + * [Pull request 294](https://bitbucket.org/osrf/sdformat/pull-request/294) + +1. Fix URDF to SDF `self_collide` bug. + * [Pull request 287](https://bitbucket.org/osrf/sdformat/pull-request/287) + +1. Added IMU orientation specification to SDF. + * [Pull request 284](https://bitbucket.org/osrf/sdformat/pull-request/284) + +### SDFormat 4.1.1 (2016-07-08) + +1. Added documentation and animation to `` element. + * [Pull request 280](https://bitbucket.org/osrf/sdformat/pull-request/280) + +1. Added tag to specify initial joint position + * [Pull request 279](https://bitbucket.org/osrf/sdformat/pull-request/279) + +### SDFormat 4.1.0 (2016-04-01) + +1. Added SDF conversion functions to parser including sdf::convertFile and sdf::convertString. + * [Pull request 266](https://bitbucket.org/osrf/sdformat/pull-request/266) + +1. Added an upload script + * [Pull request 256](https://bitbucket.org/osrf/sdformat/pull-request/256) + +### SDFormat 4.0.0 (2015-01-12) + +1. Boost pointers and boost::function in the public API have been replaced + by their std::equivalents (C++11 standard) +1. Move gravity and magnetic_field tags from physics to world + * [Pull request 247](https://bitbucket.org/osrf/sdformat/pull-request/247) +1. Switch lump link prefix from lump:: to lump_ + * [Pull request 245](https://bitbucket.org/osrf/sdformat/pull-request/245) +1. New element. + A contribution from Olivier Crave + * [Pull request 240](https://bitbucket.org/osrf/sdformat/pull-request/240) +1. Add scale to model state + * [Pull request 246](https://bitbucket.org/osrf/sdformat/pull-request/246) +1. Use stof functions to parse hex strings as floating point params. + A contribution from Rich Mattes + * [Pull request 250](https://bitbucket.org/osrf/sdformat/pull-request/250) +1. Fix memory leaks. + A contribution from Silvio Traversaro + * [Pull request 249](https://bitbucket.org/osrf/sdformat/pull-request/249) +1. Update SDF to version 1.6: new style for representing the noise properties + of an `imu` + * [Pull request 243](https://bitbucket.org/osrf/sdformat/pull-request/243) + * [Pull request 199](https://bitbucket.org/osrf/sdformat/pull-requests/199) + +## SDFormat 3.0 + +### SDFormat 3.X.X (201X-XX-XX) + +1. Improve precision of floating point parameters + * [Pull request 273](https://bitbucket.org/osrf/sdformat/pull-requests/273) + * [Pull request 276](https://bitbucket.org/osrf/sdformat/pull-requests/276) + +### SDFormat 3.7.0 (2015-11-20) + +1. Add spring pass through for sdf3 + * [Design document](https://bitbucket.org/osrf/gazebo_design/pull-requests/23) + * [Pull request 242](https://bitbucket.org/osrf/sdformat/pull-request/242) + +1. Support frame specification in SDF + * [Pull request 237](https://bitbucket.org/osrf/sdformat/pull-request/237) + +1. Remove boost from SDFExtension + * [Pull request 229](https://bitbucket.org/osrf/sdformat/pull-request/229) + +### SDFormat 3.6.0 (2015-10-27) + +1. Add light state + * [Pull request 227](https://bitbucket.org/osrf/sdformat/pull-request/227) +1. redo pull request #222 for sdf3 branch + * [Pull request 232](https://bitbucket.org/osrf/sdformat/pull-request/232) +1. Fix links in API documentation + * [Pull request 231](https://bitbucket.org/osrf/sdformat/pull-request/231) + +### SDFormat 3.5.0 (2015-10-07) + +1. Camera lens description (Replaces #213) + * [Pull request 215](https://bitbucket.org/osrf/sdformat/pull-request/215) +1. Fix shared pointer reference loop in Element and memory leak (#104) + * [Pull request 230](https://bitbucket.org/osrf/sdformat/pull-request/230) + +### SDFormat 3.4.0 (2015-10-05) + +1. Support nested model states + * [Pull request 223](https://bitbucket.org/osrf/sdformat/pull-request/223) +1. Cleaner way to set SDF_PATH for tests + * [Pull request 226](https://bitbucket.org/osrf/sdformat/pull-request/226) + +### SDFormat 3.3.0 (2015-09-15) + +1. Windows Boost linking errors + * [Pull request 206](https://bitbucket.org/osrf/sdformat/pull-request/206) +1. Nested SDF -> sdf3 + * [Pull request 221](https://bitbucket.org/osrf/sdformat/pull-request/221) +1. Pointer types + * [Pull request 218](https://bitbucket.org/osrf/sdformat/pull-request/218) +1. Torsional friction default surface radius not infinity + * [Pull request 217](https://bitbucket.org/osrf/sdformat/pull-request/217) + +### SDFormat 3.2.2 (2015-08-24) + +1. Added battery element (contribution from Olivier Crave) + * [Pull request #204](https://bitbucket.org/osrf/sdformat/pull-request/204) +1. Torsional friction backport + * [Pull request #211](https://bitbucket.org/osrf/sdformat/pull-request/211) +1. Allow Visual Studio 2015 + * [Pull request #208](https://bitbucket.org/osrf/sdformat/pull-request/208) + +### SDFormat 3.1.1 (2015-08-03) + +1. Fix tinyxml linking error + * [Pull request #209](https://bitbucket.org/osrf/sdformat/pull-request/209) + +### SDFormat 3.1.0 (2015-08-02) + +1. Added logical camera sensor to SDF + * [Pull request #207](https://bitbucket.org/osrf/sdformat/pull-request/207) + +### SDFormat 3.0.0 (2015-07-24) + +1. Added battery to SDF + * [Pull request 204](https://bitbucket.org/osrf/sdformat/pull-request/204) +1. Added altimeter sensor to SDF + * [Pull request #197](https://bitbucket.org/osrf/sdformat/pull-request/197) +1. Added magnetometer sensor to SDF + * [Pull request 198](https://bitbucket.org/osrf/sdformat/pull-request/198) +1. Fix detection of XML parsing errors + * [Pull request 190](https://bitbucket.org/osrf/sdformat/pull-request/190) +1. Support for fixed joints + * [Pull request 194](https://bitbucket.org/osrf/sdformat/pull-request/194) +1. Adding iterations to state + * [Pull request 188](https://bitbucket.org/osrf/sdformat/pull-request/188) +1. Convert to use ignition-math + * [Pull request 173](https://bitbucket.org/osrf/sdformat/pull-request/173) +1. Add world origin to scene + * [Pull request 183](https://bitbucket.org/osrf/sdformat/pull-request/183) +1. Fix collide bitmask + * [Pull request 182](https://bitbucket.org/osrf/sdformat/pull-request/182) +1. Adding meta information to visuals + * [Pull request 180](https://bitbucket.org/osrf/sdformat/pull-request/180) +1. Add projection type to gui camera + * [Pull request 178](https://bitbucket.org/osrf/sdformat/pull-request/178) +1. Fix print description to include attribute description + * [Pull request 170](https://bitbucket.org/osrf/sdformat/pull-request/170) +1. Add -std=c++11 flag to sdf_config.cmake.in and sdformat.pc.in, needed by downstream code + * [Pull request 172](https://bitbucket.org/osrf/sdformat/pull-request/172) +1. Added boost::any accessor for Param and Element + * [Pull request 166](https://bitbucket.org/osrf/sdformat/pull-request/166) +1. Remove tinyxml from dependency list + * [Pull request 152](https://bitbucket.org/osrf/sdformat/pull-request/152) +1. Added self_collide element for model + * [Pull request 149](https://bitbucket.org/osrf/sdformat/pull-request/149) +1. Added a collision bitmask field to sdf-1.5 and c++11 support + * [Pull request 145](https://bitbucket.org/osrf/sdformat/pull-request/145) +1. Fix problems with latin locales and decimal numbers (issue #60) + * [Pull request 147](https://bitbucket.org/osrf/sdformat/pull-request/147) + * [Issue 60](https://bitbucket.org/osrf/sdformat/issues/60) + +## SDFormat 2.x + +1. rename cfm_damping --> implicit_spring_damper + * [Pull request 59](https://bitbucket.org/osrf/sdformat/pull-request/59) +1. add gear_ratio and reference_body for gearbox joint. + * [Pull request 62](https://bitbucket.org/osrf/sdformat/pull-request/62) +1. Update joint stop stiffness and dissipation + * [Pull request 61](https://bitbucket.org/osrf/sdformat/pull-request/61) +1. Support for GNUInstallDirs + * [Pull request 64](https://bitbucket.org/osrf/sdformat/pull-request/64) +1. `` element used by DEM heightmaps + * [Pull request 67](https://bitbucket.org/osrf/sdformat/pull-request/67) +1. Do not export urdf symbols in sdformat 1.4 + * [Pull request 75](https://bitbucket.org/osrf/sdformat/pull-request/75) +1. adding deformable properties per issue #32 + * [Pull request 78](https://bitbucket.org/osrf/sdformat/pull-request/78) + * [Issue 32](https://bitbucket.org/osrf/sdformat/issues/32) +1. Support to use external URDF + * [Pull request 77](https://bitbucket.org/osrf/sdformat/pull-request/77) +1. Add lighting element to visual + * [Pull request 79](https://bitbucket.org/osrf/sdformat/pull-request/79) +1. SDF 1.5: add flag to fix joint axis frame #43 (gazebo issue 494) + * [Pull request 83](https://bitbucket.org/osrf/sdformat/pull-request/83) + * [Issue 43](https://bitbucket.org/osrf/sdformat/issues/43) + * [Gazebo issue 494](https://bitbucket.org/osrf/gazebo/issues/494) +1. Implement SDF_PROTOCOL_VERSION (issue #51) + * [Pull request 90](https://bitbucket.org/osrf/sdformat/pull-request/90) +1. Port sdformat to compile on Windows (MSVC) + * [Pull request 101](https://bitbucket.org/osrf/sdformat/pull-request/101) +1. Separate material properties in material.sdf + * [Pull request 104](https://bitbucket.org/osrf/sdformat/pull-request/104) +1. Add road textures (repeat pull request #104 for sdf_2.0) + * [Pull request 105](https://bitbucket.org/osrf/sdformat/pull-request/105) +1. Add Extruded Polylines as a model + * [Pull request 93](https://bitbucket.org/osrf/sdformat/pull-request/93) +1. Added polyline for sdf_2.0 + * [Pull request 106](https://bitbucket.org/osrf/sdformat/pull-request/106) +1. Add spring_reference and spring_stiffness tags to joint axis dynamics + * [Pull request 102](https://bitbucket.org/osrf/sdformat/pull-request/102) +1. Fix actor static + * [Pull request 110](https://bitbucket.org/osrf/sdformat/pull-request/110) +1. New element + * [Pull request 112](https://bitbucket.org/osrf/sdformat/pull-request/112) +1. Add camera distortion element + * [Pull request 120](https://bitbucket.org/osrf/sdformat/pull-request/120) +1. Inclusion of magnetic field strength sensor + * [Pull request 123](https://bitbucket.org/osrf/sdformat/pull-request/123) +1. Properly add URDF gazebo extensions blobs to SDF joint elements + * [Pull request 125](https://bitbucket.org/osrf/sdformat/pull-request/125) +1. Allow gui plugins to be specified in SDF + * [Pull request 127](https://bitbucket.org/osrf/sdformat/pull-request/127) +1. Backport magnetometer + * [Pull request 128](https://bitbucket.org/osrf/sdformat/pull-request/128) +1. Add flag for MOI rescaling to sdf 1.4 + * [Pull request 121](https://bitbucket.org/osrf/sdformat/pull-request/121) +1. Parse urdf joint friction parameters, add corresponding test + * [Pull request 129](https://bitbucket.org/osrf/sdformat/pull-request/129) +1. Allow reading of boolean values from plugin elements. + * [Pull request 132](https://bitbucket.org/osrf/sdformat/pull-request/132) +1. Implement generation of XML Schema files (issue #2) + * [Pull request 91](https://bitbucket.org/osrf/sdformat/pull-request/91) +1. Fix build for OS X 10.10 + * [Pull request 135](https://bitbucket.org/osrf/sdformat/pull-request/135) +1. Improve performance in loading SDF elements + * [Pull request 138](https://bitbucket.org/osrf/sdformat/pull-request/138) +1. Added urdf gazebo extension option to disable fixed joint lumping + * [Pull request 133](https://bitbucket.org/osrf/sdformat/pull-request/133) +1. Support urdfdom 0.3 (alternative to pull request #122) + * [Pull request 141](https://bitbucket.org/osrf/sdformat/pull-request/141) +1. Update list of supported joint types + * [Pull request 142](https://bitbucket.org/osrf/sdformat/pull-request/142) +1. Ignore unknown elements + * [Pull request 148](https://bitbucket.org/osrf/sdformat/pull-request/148) +1. Physics preset attributes + * [Pull request 146](https://bitbucket.org/osrf/sdformat/pull-request/146) +1. Backport fix for latin locales (pull request #147) + * [Pull request 150](https://bitbucket.org/osrf/sdformat/pull-request/150) + +## SDFormat 1.4 + +### SDFormat 1.4.8 (2013-09-06) + +1. Fix inertia transformations when reducing fixed joints in URDF + * [Pull request 48](https://bitbucket.org/osrf/sdformat/pull-request/48/fix-for-issue-22-reducing-inertia-across/diff) +1. Add element to support terrain paging in gazebo + * [Pull request 47](https://bitbucket.org/osrf/sdformat/pull-request/47/add-element-inside-heightmap/diff) +1. Further reduce console output when using URDF models + * [Pull request 46](https://bitbucket.org/osrf/sdformat/pull-request/46/convert-a-few-more-sdfwarns-to-sdflog-fix/diff) + * [Commit](https://bitbucket.org/osrf/sdformat/commits/b15d5a1ecc57abee6691618d02d59bbc3d1b84dc) + +### SDFormat 1.4.7 (2013-08-22) + +1. Direct console messages to std_err + * [Pull request 44](https://bitbucket.org/osrf/sdformat/pull-request/44/fix-19-direct-all-messages-to-std_err) + +### SDFormat 1.4.6 (2013-08-20) + +1. Add tags for GPS sensor and sensor noise + * [Pull request 36](https://bitbucket.org/osrf/sdformat/pull-request/36/gps-sensor-sensor-noise-and-spherical) +1. Add tags for wireless transmitter/receiver models + * [Pull request 34](https://bitbucket.org/osrf/sdformat/pull-request/34/transceiver-support) + * [Pull request 43](https://bitbucket.org/osrf/sdformat/pull-request/43/updated-description-of-the-transceiver-sdf) +1. Add tags for playback of audio files in Gazebo + * [Pull request 26](https://bitbucket.org/osrf/sdformat/pull-request/26/added-audio-tags) + * [Pull request 35](https://bitbucket.org/osrf/sdformat/pull-request/35/move-audio-to-link-and-playback-on-contact) +1. Add tags for simbody physics parameters + * [Pull request 32](https://bitbucket.org/osrf/sdformat/pull-request/32/merging-some-updates-from-simbody-branch) +1. Log messages to a file, reduce console output + * [Pull request 33](https://bitbucket.org/osrf/sdformat/pull-request/33/log-messages-to-file-8) +1. Generalize ode's element + * [Pull request 38](https://bitbucket.org/osrf/sdformat/pull-request/38/add-provide_feedback-for-bullet-joint) +1. Various bug, style and test fixes + +### SDFormat 1.4.5 (2013-07-23) + +1. Deprecated Gazebo's internal SDF code +1. Use templatized Get functions for retrieving values from SDF files +1. Removed dependency on ROS diff --git a/sdformat/INSTALL_WIN32.md b/sdformat/INSTALL_WIN32.md new file mode 100644 index 0000000..c114218 --- /dev/null +++ b/sdformat/INSTALL_WIN32.md @@ -0,0 +1,46 @@ +# Installation on Windows + +This documentation describes how to set up a workspace for trying to compile sdformat on Windows. + +## Supported compilers + +At this moment, compilation has been tested on Windows 7 and 8.1 and is supported +when using Visual Studio 2013. Patches for other versions are welcome. + +## Installation + +Totally experimental, using pre-compiled binaries in a local workspace. To +make things easier, use a MinGW shell for your editing work, and only use the +Windows `cmd` for configuring and building. + +1. Make a directory to work in, e.g.: + + mkdir sdformat-ws + cd sdformat-ws + +1. Download boost into that directory: + + - [boost 1.56.0](http://packages.osrfoundation.org/win32/deps/boost_1_56_0.zip) + +1. Unzip it in sdformat-ws. + +1. Clone sdformat + + hg clone https://bitbucket.org/osrf/sdformat + +1. Load your compiler setup, e.g. (note that we are asking for the 64-bit toolchain here): + + "C:\Program Files (x86)\Microsoft Visual Studio 12.0\VC\vcvarsall.bat" x86_amd64 + +1. Configure and build sdformat: + + cd sdformat + mkdir build + cd build + ..\configure + nmake + nmake install + + You should now have an installation of sdformat in sdformat-ws/sdformat/build/install/Release. + + Once this all works (which it does with tender love and care): you should now have an installation of sdformat in sdformat-ws/sdformat/build/install/Release. diff --git a/sdformat/LICENSE b/sdformat/LICENSE new file mode 100644 index 0000000..bd33c43 --- /dev/null +++ b/sdformat/LICENSE @@ -0,0 +1,15 @@ +Software License Agreement (Apache License) + +Copyright 2012 Open Source Robotics Foundation + +Licensed under the Apache License, Version 2.0 (the "License"); +you may not use this file except in compliance with the License. +You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + +Unless required by applicable law or agreed to in writing, software +distributed under the License is distributed on an "AS IS" BASIS, +WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +See the License for the specific language governing permissions and +limitations under the License. diff --git a/sdformat/Migration.md b/sdformat/Migration.md new file mode 100644 index 0000000..149d31e --- /dev/null +++ b/sdformat/Migration.md @@ -0,0 +1,116 @@ +# Migration Guide for SDF Protocol +This document contains information about migrating +between different versions of the SDF protocol. +The SDF protocol version number is specified in the `version` attribute +of the `sdf` element (1.4, 1.5, 1.6, etc.) +and is distinct from sdformat library version +(2.3, 3.0, 4.0, etc.). + +# Note on backward compatibility +There are `*.convert` files that allow old sdf files to be migrated +forward programmatically. +This document aims to contain similar information to those files +but with improved human-readability.. + +## SDFormat 3.x to 4.x + +### Additions + +1. **New SDF protocol version 1.6** + + Details about the 1.5 to 1.6 transition are explained below in this same + document + +### Modifications + +1. **Boost pointers and boost::function** + + All boost pointers, boost::function in the public API have been replaced + by their std:: equivalents (C++11 standard) + +1. **`gravity` and `magnetic_field` elements are moved from `physics` to `world`** + + In physics element: gravity and magnetic_field tags have been moved + from Physics to World element. + + [pull request 247](https://bitbucket.org/osrf/sdformat/pull-requests/247) + + [gazebo pull request 2090](https://bitbucket.org/osrf/gazebo/pull-requests/2090) + +1. **New noise for IMU** + + A new style for representing the noise properties of an `imu` was implemented + in [pull request 199](https://bitbucket.org/osrf/sdformat/pull-requests/199) + for sdf 1.5 and the old style was declared as deprecated. + The old style has been removed from sdf 1.6 with the conversion script + updating to the new style. + + [pull request 199](https://bitbucket.org/osrf/sdformat/pull-requests/199) + + [pull request 243](https://bitbucket.org/osrf/sdformat/pull-requests/243) + + [pull request 244](https://bitbucket.org/osrf/sdformat/pull-requests/244) + +1. **Lump:: prefix in link names** + + Changed to \_fixed_joint_lump__ to avoid confusion with scoped names + + [Pull request 245](https://bitbucket.org/osrf/sdformat/pull-request/245) + +## SDF protocol 1.5 to 1.6 + +### Additions + +1. **link.sdf** `enable_wind` element + + description: If true, the link is affected by the wind + + type: bool + + default: false + + required: 0 + + [pull request 240](https://bitbucket.org/osrf/sdformat/pull-requests/240) + +1. **link.sdf** `light` element + + included from `light.sdf` with required="*", + so a link can have any number of attached lights. + + [pull request 373](https://bitbucket.org/osrf/sdformat/pull-requests/373) + +1. **model.sdf** `enable_wind` element + + description: If set to true, all links in the model will be affected by + the wind. Can be overriden by the link wind property. + + type: bool + + default: false + + required: 0 + + [pull request 240](https://bitbucket.org/osrf/sdformat/pull-requests/240) + +1. **model_state.sdf** `scale` element + + description: Scale for the 3 dimensions of the model. + + type: vector3 + + default: "1 1 1" + + required: 0 + + [pull request 246](https://bitbucket.org/osrf/sdformat/pull-requests/246) + +1. **physics.sdf** `island_threads` element under `ode::solver` + + description: Number of threads to use for "islands" of disconnected models. + + type: int + + default: 0 + + required: 0 + + [pull request 380](https://bitbucket.org/osrf/sdformat/pull-requests/380) + +1. **physics.sdf** `thread_position_correction` element under `ode::solver` + + description: Flag to use threading to speed up position correction computation. + + type: bool + + default: 0 + + required: 0 + + [pull request 380](https://bitbucket.org/osrf/sdformat/pull-requests/380) + +1. **state.sdf** allow `light` tags within `insertions` element + * [pull request 325](https://bitbucket.org/osrf/sdformat/pull-request/325) + +1. **surface.sdf** `category_bitmask` element + + description: Bitmask for category of collision filtering. + Collision happens if `((category1 & collision2) | (category2 & collision1))` is not zero. + If not specified, the category_bitmask should be interpreted as being the same as collide_bitmask. + + type: unsigned int + + default: 65535 + + required: 0 + + [pull request 318](https://bitbucket.org/osrf/sdformat/pull-requests/318) + +1. **world.sdf** `wind` element + + description: The wind tag specifies the type and properties of the wind. + + required: 0 + + [pull request 240](https://bitbucket.org/osrf/sdformat/pull-requests/240) + +1. **world.sdf** `wind::linear_velocity` element + + description: Linear velocity of the wind. + + type: vector3 + + default: "0 0 0" + + required: 0 + + [pull request 240](https://bitbucket.org/osrf/sdformat/pull-requests/240) diff --git a/sdformat/NEWS b/sdformat/NEWS new file mode 100644 index 0000000..e69de29 diff --git a/sdformat/README b/sdformat/README new file mode 100644 index 0000000..05a6e0a --- /dev/null +++ b/sdformat/README @@ -0,0 +1,36 @@ +sdformat - Simulation Description Format (SDF) parser +----------------------------------------------------- + +SDF is an XML file format that describes environments, objects, and robots +in a manner suitable for robotic applications. SDF is capable of representing +and describing different physic engines, lighting properties, terrain, static +or dynamic objects, and articulated robots with various sensors, and acutators. +The format of SDF is also described by XML, which facilitates updates and +allows conversion from previous versions. A parser is also contained within +this package that reads SDF files and returns a C++ interface. + + http://sdformat.org + +Installation +------------ +Standard installation can be performed in UNIX systems using the following +steps: + + - mkdir build/ + - cd build/ + - cmake .. + - sudo make install + +sdformat supported cmake parameters at configuring time: + - USE_EXTERNAL_URDF (bool) [default False] + Do not use the internal copy of urdfdom and use the one installed in the + system instead. Recommended if you have a working installation of urdfdom. + - USE_UPSTREAM_CFLAGS (bool) [default True] + Use the sdformat team compilation flags instead of the common set defined + by cmake. + +Uninstallation +-------------- +To uninstall the software installed with the previous steps: + - cd build/ + - sudo make uninstall diff --git a/sdformat/cmake/CodeCoverage.cmake b/sdformat/cmake/CodeCoverage.cmake new file mode 100644 index 0000000..3948211 --- /dev/null +++ b/sdformat/cmake/CodeCoverage.cmake @@ -0,0 +1,132 @@ +# +# 2012-01-31, Lars Bilke +# - Enable Code Coverage +# +# 2013-09-17, Joakim Söderberg +# - Added support for Clang. +# - Some additional usage instructions. +# +# USAGE: +# 1. Copy this file into your cmake modules path. +# +# 2. Add the following line to your CMakeLists.txt: +# INCLUDE(CodeCoverage) +# +# 3. Set compiler flags to turn off optimization and enable coverage: +# SET(CMAKE_CXX_FLAGS "-g -O0 -fprofile-arcs -ftest-coverage") +# SET(CMAKE_C_FLAGS "-g -O0 -fprofile-arcs -ftest-coverage") +# +# 3. Use the function SETUP_TARGET_FOR_COVERAGE to create a custom make target +# which runs your test executable and produces a lcov code coverage report: +# Example: +# SETUP_TARGET_FOR_COVERAGE( +# my_coverage_target # Name for custom target. +# test_driver # Name of the test driver executable that runs the tests. +# # NOTE! This should always have a ZERO as exit code +# # otherwise the coverage generation will not complete. +# coverage # Name of output directory. +# ) +# +# 4. Build a Debug build: +# cmake -DCMAKE_BUILD_TYPE=Debug .. +# make +# make my_coverage_target +# +# + +# Check prereqs +FIND_PROGRAM( GCOV_PATH gcov ) +FIND_PROGRAM( LCOV_PATH lcov ) +FIND_PROGRAM( GREP_PATH grep ) +FIND_PROGRAM( GENHTML_PATH genhtml ) +FIND_PROGRAM( GCOVR_PATH gcovr PATHS ${CMAKE_SOURCE_DIR}/tests) + +IF(NOT GCOV_PATH) + MESSAGE(FATAL_ERROR "gcov not found! Aborting...") +ENDIF() # NOT GCOV_PATH + +IF(NOT CMAKE_COMPILER_IS_GNUCXX) + # Clang version 3.0.0 and greater now supports gcov as well. + MESSAGE(WARNING "Compiler is not GNU gcc! Clang Version 3.0.0 and greater supports gcov as well, but older versions don't.") + + IF(NOT "${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") + MESSAGE(FATAL_ERROR "Compiler is not GNU gcc! Aborting...") + ENDIF() +ENDIF() # NOT CMAKE_COMPILER_IS_GNUCXX + +SET(CMAKE_CXX_FLAGS_COVERAGE + "-g -O0 --coverage -fprofile-arcs -ftest-coverage" + CACHE STRING "Flags used by the C++ compiler during coverage builds." + FORCE ) +SET(CMAKE_C_FLAGS_COVERAGE + "-g -O0 --coverage -fprofile-arcs -ftest-coverage" + CACHE STRING "Flags used by the C compiler during coverage builds." + FORCE ) +SET(CMAKE_EXE_LINKER_FLAGS_COVERAGE + "" + CACHE STRING "Flags used for linking binaries during coverage builds." + FORCE ) +SET(CMAKE_SHARED_LINKER_FLAGS_COVERAGE + "" + CACHE STRING "Flags used by the shared libraries linker during coverage builds." + FORCE ) +MARK_AS_ADVANCED( + CMAKE_CXX_FLAGS_COVERAGE + CMAKE_C_FLAGS_COVERAGE + CMAKE_EXE_LINKER_FLAGS_COVERAGE + CMAKE_SHARED_LINKER_FLAGS_COVERAGE ) + +IF ( NOT (CMAKE_BUILD_TYPE STREQUAL "Debug" OR CMAKE_BUILD_TYPE STREQUAL "Coverage")) + MESSAGE( WARNING "Code coverage results with an optimized (non-Debug) build may be misleading" ) +ENDIF() # NOT CMAKE_BUILD_TYPE STREQUAL "Debug" + + +# Param _targetname The name of new the custom make target +# Param _testrunner The name of the target which runs the tests. +# MUST return ZERO always, even on errors. +# If not, no coverage report will be created! +# Param _outputname lcov output is generated as _outputname.info +# HTML report is generated in _outputname/index.html +# Optional fourth parameter is passed as arguments to _testrunner +# Pass them in list form, e.g.: "-j;2" for -j 2 +FUNCTION(SETUP_TARGET_FOR_COVERAGE _targetname _testrunner _outputname) + + IF(NOT LCOV_PATH) + MESSAGE(FATAL_ERROR "lcov not found! Aborting...") + ENDIF() # NOT LCOV_PATH + + IF(NOT GENHTML_PATH) + MESSAGE(FATAL_ERROR "genhtml not found! Aborting...") + ENDIF() # NOT GENHTML_PATH + + IF(NOT GREP_PATH) + MESSAGE(FATAL_ERROR "grep not found! Run code coverage on linux or mac.") + ENDIF() + + # Setup target + ADD_CUSTOM_TARGET(${_targetname} + + # Capturing lcov counters and generating report + COMMAND ${LCOV_PATH} -q --no-checksum --directory ${PROJECT_BINARY_DIR} + --capture --output-file ${_outputname}.info 2>/dev/null + COMMAND ${LCOV_PATH} -q --remove ${_outputname}.info + 'test/*' '/usr/*' '*_TEST*' --output-file ${_outputname}.info.cleaned + COMMAND ${GENHTML_PATH} -q --legend -o ${_outputname} + ${_outputname}.info.cleaned + COMMAND ${LCOV_PATH} --summary ${_outputname}.info.cleaned 2>&1 | grep "lines" | cut -d ' ' -f 4 | cut -d '%' -f 1 > coverage/lines.txt + COMMAND ${LCOV_PATH} --summary ${_outputname}.info.cleaned 2>&1 | grep "functions" | cut -d ' ' -f 4 | cut -d '%' -f 1 > coverage/functions.txt + COMMAND ${CMAKE_COMMAND} -E remove ${_outputname}.info + ${_outputname}.info.cleaned + + WORKING_DIRECTORY ${CMAKE_BINARY_DIR} + COMMENT "Resetting code coverage counters to zero.\n" + "Processing code coverage counters and generating report." + ) + + # Show info where to find the report + ADD_CUSTOM_COMMAND(TARGET ${_targetname} POST_BUILD + COMMAND COMMAND ${LCOV_PATH} -q --zerocounters --directory ${PROJECT_BINARY_DIR}; + COMMENT "Open ./${_outputname}/index.html in your browser to view the coverage report." + ) + +ENDFUNCTION() # SETUP_TARGET_FOR_COVERAGE diff --git a/sdformat/cmake/DefaultCFlags.cmake b/sdformat/cmake/DefaultCFlags.cmake new file mode 100644 index 0000000..584d920 --- /dev/null +++ b/sdformat/cmake/DefaultCFlags.cmake @@ -0,0 +1,77 @@ +# Build type link flags +set (CMAKE_LINK_FLAGS_RELEASE " " CACHE INTERNAL "Link flags for release" FORCE) +set (CMAKE_LINK_FLAGS_RELWITHDEBINFO " " CACHE INTERNAL "Link flags for release with debug support" FORCE) +set (CMAKE_LINK_FLAGS_DEBUG " " CACHE INTERNAL "Link flags for debug" FORCE) +set (CMAKE_LINK_FLAGS_PROFILE " -pg" CACHE INTERNAL "Link flags for profile" FORCE) +set (CMAKE_LINK_FLAGS_COVERAGE " --coverage" CACHE INTERNAL "Link flags for static code coverage" FORCE) + +set (CMAKE_C_FLAGS_RELEASE "") +if (NOT "${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang" AND NOT MSVC) + # -s doesn't work with clang or Visual Studio, see alternative in link below: + # http://stackoverflow.com/questions/6085491/gcc-vs-clang-symbol-strippingu + set (CMAKE_C_FLAGS_RELEASE "-s") +endif() + +if (NOT MSVC) + set (CMAKE_C_FLAGS_RELEASE " ${CMAKE_C_FLAGS_RELEASE} -O3 -DNDEBUG ${CMAKE_C_FLAGS_ALL}" CACHE INTERNAL "C Flags for release" FORCE) + set (CMAKE_CXX_FLAGS_RELEASE ${CMAKE_C_FLAGS_RELEASE}) + + set (CMAKE_C_FLAGS_RELWITHDEBINFO " -g -O2 ${CMAKE_C_FLAGS_ALL}" CACHE INTERNAL "C Flags for release with debug support" FORCE) + set (CMAKE_CXX_FLAGS_RELWITHDEBINFO ${CMAKE_C_FLAGS_RELWITHDEBINFO}) + + set (CMAKE_C_FLAGS_DEBUG " -ggdb3 ${CMAKE_C_FLAGS_ALL}" CACHE INTERNAL "C Flags for debug" FORCE) + set (CMAKE_CXX_FLAGS_DEBUG ${CMAKE_C_FLAGS_DEBUG}) + + set (CMAKE_C_FLAGS_PROFILE " -fno-omit-frame-pointer -g -pg ${CMAKE_C_FLAGS_ALL}" CACHE INTERNAL "C Flags for profile" FORCE) + set (CMAKE_CXX_FLAGS_PROFILE ${CMAKE_C_FLAGS_PROFILE}) + + set (CMAKE_C_FLAGS_COVERAGE " -g -O0 -Wformat=2 --coverage -fno-inline ${CMAKE_C_FLAGS_ALL}" CACHE INTERNAL "C Flags for static code coverage" FORCE) + set (CMAKE_CXX_FLAGS_COVERAGE "${CMAKE_C_FLAGS_COVERAGE}") + foreach(flag + -fno-default-inline + -fno-elide-constructors + -fno-implicit-inline-templates) + CHECK_CXX_COMPILER_FLAG(${flag} R${flag}) + if (R${flag}) + set (CMAKE_CXX_FLAGS_COVERAGE "${CMAKE_CXX_FLAGS_COVERAGE} ${flag}") + endif() + endforeach() +endif() + +##################################### +# Set all the global build flags +set (CMAKE_C_FLAGS "${CMAKE_C_FLAGS_${CMAKE_BUILD_TYPE_UPPERCASE}}") +set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS_${CMAKE_BUILD_TYPE_UPPERCASE}}") +set (CMAKE_EXE_LINKER_FLAGS "${CMAKE_LINK_FLAGS_${CMAKE_BUILD_TYPE_UPPERCASE}}") +set (CMAKE_SHARED_LINKER_FLAGS "${CMAKE_LINK_FLAGS_${CMAKE_BUILD_TYPE_UPPERCASE}}") +set (CMAKE_MODULE_LINKER_FLAGS "${CMAKE_LINK_FLAGS_${CMAKE_BUILD_TYPE_UPPERCASE}}") + +# Visual Studio enables c++11 support by default +if (NOT MSVC) + set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS_${CMAKE_BUILD_TYPE_UPPERCASE}} -std=c++11") +endif() + +if (UNIX) + # Add visibility in UNIX + check_gcc_visibility() + if (GCC_SUPPORTS_VISIBILITY) + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fvisibility=hidden") + endif() +endif() + +# Compiler-specific C++11 activation. +if ("${CMAKE_CXX_COMPILER_ID} " MATCHES "GNU ") + execute_process( + COMMAND ${CMAKE_CXX_COMPILER} -dumpversion OUTPUT_VARIABLE GCC_VERSION) + if (NOT (GCC_VERSION VERSION_GREATER 4.7)) + message(FATAL_ERROR "${PROJECT_NAME} requires g++ 4.8 or greater.") + endif () +elseif ("${CMAKE_CXX_COMPILER_ID} " MATCHES "Clang ") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -stdlib=libc++") +elseif ("${CMAKE_CXX_COMPILER_ID} " STREQUAL "MSVC ") + if (MSVC_VERSION LESS 1800) + message(FATAL_ERROR "${PROJECT_NAME} requires VS 2013 or greater.") + endif() +else () + message(FATAL_ERROR "Your C++ compiler does not support C++11.") +endif () diff --git a/sdformat/cmake/FindOS.cmake b/sdformat/cmake/FindOS.cmake new file mode 100644 index 0000000..efc6d11 --- /dev/null +++ b/sdformat/cmake/FindOS.cmake @@ -0,0 +1,45 @@ +# Check the OS type. + +# CMake does not distinguish Linux from other Unices. +STRING (REGEX MATCH "Linux" PLAYER_OS_LINUX ${CMAKE_SYSTEM_NAME}) +# Nor *BSD +STRING (REGEX MATCH "BSD" PLAYER_OS_BSD ${CMAKE_SYSTEM_NAME}) +# Or Solaris. I'm seeing a trend, here +STRING (REGEX MATCH "SunOS" PLAYER_OS_SOLARIS ${CMAKE_SYSTEM_NAME}) + +# Windows is easy (for once) +IF (WIN32) + SET (PLAYER_OS_WIN TRUE BOOL INTERNAL) +ENDIF (WIN32) + +# Check if it's an Apple OS +IF (APPLE) + # Check if it's OS X or another MacOS (that's got to be pretty unlikely) + STRING (REGEX MATCH "Darwin" PLAYER_OS_OSX ${CMAKE_SYSTEM_NAME}) + IF (NOT PLAYER_OS_OSX) + SET (PLAYER_OS_MACOS TRUE BOOL INTERNAL) + ENDIF (NOT PLAYER_OS_OSX) +ENDIF (APPLE) + +# QNX +IF (QNXNTO) + SET (PLAYER_OS_QNX TRUE BOOL INTERNAL) +ENDIF (QNXNTO) + +IF (PLAYER_OS_LINUX) + MESSAGE (STATUS "Operating system is Linux") +ELSEIF (PLAYER_OS_BSD) + MESSAGE (STATUS "Operating system is BSD") +ELSEIF (PLAYER_OS_WIN) + MESSAGE (STATUS "Operating system is Windows") +ELSEIF (PLAYER_OS_OSX) + MESSAGE (STATUS "Operating system is Apple MacOS X") +ELSEIF (PLAYER_OS_MACOS) + MESSAGE (STATUS "Operating system is Apple MacOS (not OS X)") +ELSEIF (PLAYER_OS_QNX) + MESSAGE (STATUS "Operating system is QNX") +ELSEIF (PLAYER_OS_SOLARIS) + MESSAGE (STATUS "Operating system is Solaris") +ELSE (PLAYER_OS_LINUX) + MESSAGE (STATUS "Operating system is generic Unix") +ENDIF (PLAYER_OS_LINUX) diff --git a/sdformat/cmake/FindSSE.cmake b/sdformat/cmake/FindSSE.cmake new file mode 100644 index 0000000..8a8634b --- /dev/null +++ b/sdformat/cmake/FindSSE.cmake @@ -0,0 +1,115 @@ +# Check if SSE instructions are available on the machine where +# the project is compiled. + +IF (ARCH MATCHES "i386" OR ARCH MATCHES "x86_64") + IF(CMAKE_SYSTEM_NAME MATCHES "Linux") + EXEC_PROGRAM(cat ARGS "/proc/cpuinfo" OUTPUT_VARIABLE CPUINFO) + + STRING(REGEX REPLACE "^.*(sse2).*$" "\\1" SSE_THERE ${CPUINFO}) + STRING(COMPARE EQUAL "sse2" "${SSE_THERE}" SSE2_TRUE) + IF (SSE2_TRUE) + set(SSE2_FOUND true CACHE BOOL "SSE2 available on host") + ELSE (SSE2_TRUE) + set(SSE2_FOUND false CACHE BOOL "SSE2 available on host") + ENDIF (SSE2_TRUE) + + # /proc/cpuinfo apparently omits sse3 :( + STRING(REGEX REPLACE "^.*[^s](sse3).*$" "\\1" SSE_THERE ${CPUINFO}) + STRING(COMPARE EQUAL "sse3" "${SSE_THERE}" SSE3_TRUE) + IF (NOT SSE3_TRUE) + STRING(REGEX REPLACE "^.*(T2300).*$" "\\1" SSE_THERE ${CPUINFO}) + STRING(COMPARE EQUAL "T2300" "${SSE_THERE}" SSE3_TRUE) + ENDIF (NOT SSE3_TRUE) + + STRING(REGEX REPLACE "^.*(ssse3).*$" "\\1" SSE_THERE ${CPUINFO}) + STRING(COMPARE EQUAL "ssse3" "${SSE_THERE}" SSSE3_TRUE) + IF (SSE3_TRUE OR SSSE3_TRUE) + set(SSE3_FOUND true CACHE BOOL "SSE3 available on host") + ELSE (SSE3_TRUE OR SSSE3_TRUE) + set(SSE3_FOUND false CACHE BOOL "SSE3 available on host") + ENDIF (SSE3_TRUE OR SSSE3_TRUE) + IF (SSSE3_TRUE) + set(SSSE3_FOUND true CACHE BOOL "SSSE3 available on host") + ELSE (SSSE3_TRUE) + set(SSSE3_FOUND false CACHE BOOL "SSSE3 available on host") + ENDIF (SSSE3_TRUE) + + STRING(REGEX REPLACE "^.*(sse4_1).*$" "\\1" SSE_THERE ${CPUINFO}) + STRING(COMPARE EQUAL "sse4_1" "${SSE_THERE}" SSE41_TRUE) + IF (SSE41_TRUE) + set(SSE4_1_FOUND true CACHE BOOL "SSE4.1 available on host") + ELSE (SSE41_TRUE) + set(SSE4_1_FOUND false CACHE BOOL "SSE4.1 available on host") + ENDIF (SSE41_TRUE) + + STRING(REGEX REPLACE "^.*(sse4_2).*$" "\\1" SSE_THERE ${CPUINFO}) + STRING(COMPARE EQUAL "sse4_2" "${SSE_THERE}" SSE42_TRUE) + IF (SSE42_TRUE) + set(SSE4_2_FOUND true CACHE BOOL "SSE4.2 available on host") + ELSE (SSE42_TRUE) + set(SSE4_2_FOUND false CACHE BOOL "SSE4.2 available on host") + ENDIF (SSE42_TRUE) + + ELSEIF(CMAKE_SYSTEM_NAME MATCHES "Darwin") + EXEC_PROGRAM("/usr/sbin/sysctl -n machdep.cpu.features" OUTPUT_VARIABLE + CPUINFO) + + STRING(REGEX REPLACE "^.*[^S](SSE2).*$" "\\1" SSE_THERE ${CPUINFO}) + STRING(COMPARE EQUAL "SSE2" "${SSE_THERE}" SSE2_TRUE) + IF (SSE2_TRUE) + set(SSE2_FOUND true CACHE BOOL "SSE2 available on host") + ELSE (SSE2_TRUE) + set(SSE2_FOUND false CACHE BOOL "SSE2 available on host") + ENDIF (SSE2_TRUE) + + STRING(REGEX REPLACE "^.*[^S](SSE3).*$" "\\1" SSE_THERE ${CPUINFO}) + STRING(COMPARE EQUAL "SSE3" "${SSE_THERE}" SSE3_TRUE) + IF (SSE3_TRUE) + set(SSE3_FOUND true CACHE BOOL "SSE3 available on host") + ELSE (SSE3_TRUE) + set(SSE3_FOUND false CACHE BOOL "SSE3 available on host") + ENDIF (SSE3_TRUE) + + STRING(REGEX REPLACE "^.*(SSSE3).*$" "\\1" SSE_THERE ${CPUINFO}) + STRING(COMPARE EQUAL "SSSE3" "${SSE_THERE}" SSSE3_TRUE) + IF (SSSE3_TRUE) + set(SSSE3_FOUND true CACHE BOOL "SSSE3 available on host") + ELSE (SSSE3_TRUE) + set(SSSE3_FOUND false CACHE BOOL "SSSE3 available on host") + ENDIF (SSSE3_TRUE) + + STRING(REGEX REPLACE "^.*(SSE4.1).*$" "\\1" SSE_THERE ${CPUINFO}) + STRING(COMPARE EQUAL "SSE4.1" "${SSE_THERE}" SSE41_TRUE) + IF (SSE41_TRUE) + set(SSE4_1_FOUND true CACHE BOOL "SSE4.1 available on host") + ELSE (SSE41_TRUE) + set(SSE4_1_FOUND false CACHE BOOL "SSE4.1 available on host") + ENDIF (SSE41_TRUE) + ELSEIF(CMAKE_SYSTEM_NAME MATCHES "Windows") + # TODO + set(SSE2_FOUND true CACHE BOOL "SSE2 available on host") + set(SSE3_FOUND false CACHE BOOL "SSE3 available on host") + set(SSSE3_FOUND false CACHE BOOL "SSSE3 available on host") + set(SSE4_1_FOUND false CACHE BOOL "SSE4.1 available on host") + ELSE(CMAKE_SYSTEM_NAME MATCHES "Linux") + set(SSE2_FOUND true CACHE BOOL "SSE2 available on host") + set(SSE3_FOUND false CACHE BOOL "SSE3 available on host") + set(SSSE3_FOUND false CACHE BOOL "SSSE3 available on host") + set(SSE4_1_FOUND false CACHE BOOL "SSE4.1 available on host") + ENDIF(CMAKE_SYSTEM_NAME MATCHES "Linux") +ENDIF(ARCH MATCHES "i386" OR ARCH MATCHES "x86_64") + +if(NOT SSE2_FOUND) + MESSAGE(STATUS "Could not find hardware support for SSE2 on this machine.") +endif(NOT SSE2_FOUND) +if(NOT SSE3_FOUND) + MESSAGE(STATUS "Could not find hardware support for SSE3 on this machine.") +endif(NOT SSE3_FOUND) +if(NOT SSSE3_FOUND) + MESSAGE(STATUS "Could not find hardware support for SSSE3 on this machine.") +endif(NOT SSSE3_FOUND) +if(NOT SSE4_1_FOUND) + MESSAGE(STATUS "Could not find hardware support for SSE4.1 on this machine.") +endif(NOT SSE4_1_FOUND) + +mark_as_advanced(SSE2_FOUND SSE3_FOUND SSSE3_FOUND SSE4_1_FOUND) diff --git a/sdformat/cmake/HostCFlags.cmake b/sdformat/cmake/HostCFlags.cmake new file mode 100644 index 0000000..f38d8d7 --- /dev/null +++ b/sdformat/cmake/HostCFlags.cmake @@ -0,0 +1,27 @@ +include (${project_cmake_dir}/FindSSE.cmake) + +if (SSE2_FOUND) + set (CMAKE_C_FLAGS_ALL "-msse -msse2 ${CMAKE_C_FLAGS_ALL}") + if (NOT APPLE) + set (CMAKE_C_FLAGS_ALL "-mfpmath=sse ${CMAKE_C_FLAGS_ALL}") + endif() +endif() + +if (SSE3_FOUND) + set (CMAKE_C_FLAGS_ALL "-msse3 ${CMAKE_C_FLAGS_ALL}") +endif() +if (SSSE3_FOUND) + set (CMAKE_C_FLAGS_ALL "-mssse3 ${CMAKE_C_FLAGS_ALL}") +endif() + +if (SSE4_1_FOUND OR SSE4_2_FOUND) + if (SSE4_1_FOUND) + set (CMAKE_C_FLAGS_ALL "-msse4.1 ${CMAKE_C_FLAGS_ALL}") + endif() + if (SSE4_2_FOUND) + set (CMAKE_C_FLAGS_ALL "-msse4.2 ${CMAKE_C_FLAGS_ALL}") + endif() +else() + message(STATUS "\nSSE4 disabled.\n") +endif() + diff --git a/sdformat/cmake/SDFUtils.cmake b/sdformat/cmake/SDFUtils.cmake new file mode 100644 index 0000000..206d32b --- /dev/null +++ b/sdformat/cmake/SDFUtils.cmake @@ -0,0 +1,278 @@ +################################################################################ +#APPEND_TO_CACHED_STRING(_string _cacheDesc [items...]) +# Appends items to a cached list. +MACRO (APPEND_TO_CACHED_STRING _string _cacheDesc) + FOREACH (newItem ${ARGN}) + SET (${_string} "${${_string}} ${newItem}" CACHE INTERNAL ${_cacheDesc} FORCE) + ENDFOREACH (newItem ${ARGN}) + #STRING(STRIP ${${_string}} ${_string}) +ENDMACRO (APPEND_TO_CACHED_STRING) + +################################################################################ +# APPEND_TO_CACHED_LIST (_list _cacheDesc [items...] +# Appends items to a cached list. +MACRO (APPEND_TO_CACHED_LIST _list _cacheDesc) + SET (tempList ${${_list}}) + FOREACH (newItem ${ARGN}) + LIST (APPEND tempList ${newItem}) + ENDFOREACH (newItem ${newItem}) + SET (${_list} ${tempList} CACHE INTERNAL ${_cacheDesc} FORCE) +ENDMACRO(APPEND_TO_CACHED_LIST) + +################################################# +# Macro to turn a list into a string (why doesn't CMake have this built-in?) +MACRO (LIST_TO_STRING _string _list) + SET (${_string}) + FOREACH (_item ${_list}) + SET (${_string} "${${_string}} ${_item}") + ENDFOREACH (_item) + #STRING(STRIP ${${_string}} ${_string}) +ENDMACRO (LIST_TO_STRING) + +################################################# +# BUILD ERROR macro +macro (BUILD_ERROR) + foreach (str ${ARGN}) + SET (msg "\t${str}") + MESSAGE (STATUS ${msg}) + APPEND_TO_CACHED_LIST(build_errors "build errors" ${msg}) + endforeach () +endmacro (BUILD_ERROR) + +################################################# +# BUILD WARNING macro +macro (BUILD_WARNING) + foreach (str ${ARGN}) + SET (msg "\t${str}" ) + MESSAGE (STATUS ${msg} ) + APPEND_TO_CACHED_LIST(build_warnings "build warning" ${msg}) + endforeach (str ${ARGN}) +endmacro (BUILD_WARNING) + +################################################# +macro (sdf_add_library _name) + set(LIBS_DESTINATION ${PROJECT_BINARY_DIR}/src) + set_source_files_properties(${ARGN} PROPERTIES COMPILE_DEFINITIONS "BUILDING_DLL") + add_library(${_name} SHARED ${ARGN}) + target_link_libraries (${_name} ${general_libraries}) + set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${LIBS_DESTINATION}) + if (MSVC) + set_target_properties( ${_name} PROPERTIES ARCHIVE_OUTPUT_DIRECTORY ${LIBS_DESTINATION}) + set_target_properties( ${_name} PROPERTIES ARCHIVE_OUTPUT_DIRECTORY_DEBUG ${LIBS_DESTINATION}) + set_target_properties( ${_name} PROPERTIES ARCHIVE_OUTPUT_DIRECTORY_RELEASE ${LIBS_DESTINATION}) + endif () +endmacro () + +################################################# +macro (sdf_add_executable _name) + add_executable(${_name} ${ARGN}) + target_link_libraries (${_name} ${general_libraries}) +endmacro () + + +################################################# +macro (sdf_install_includes _subdir) + install(FILES ${ARGN} DESTINATION ${INCLUDE_INSTALL_DIR}/${_subdir} COMPONENT headers) +endmacro() + +################################################# +macro (sdf_install_library _name) + set_target_properties(${_name} PROPERTIES SOVERSION ${SDF_MAJOR_VERSION} VERSION ${SDF_VERSION_FULL}) + install (TARGETS ${_name} DESTINATION ${LIB_INSTALL_DIR} COMPONENT shlib) +endmacro () + +################################################# +macro (sdf_install_executable _name) + set_target_properties(${_name} PROPERTIES VERSION ${SDF_VERSION_FULL}) + install (TARGETS ${_name} DESTINATION ${BIN_INSTALL_DIR}) +endmacro () + +################################################# +macro (sdf_setup_unix) +endmacro() + +################################################# +macro (sdf_setup_windows) + # Need for M_PI constant + add_definitions(-D_USE_MATH_DEFINES -DWINDOWS_LEAN_AND_MEAN) + # Suppress warnings caused by boost + add_definitions(/wd4512 /wd4996) + # Use dynamic linking for boost + add_definitions(-DBOOST_ALL_DYN_LINK) + # And force linking to MSVC dynamic runtime + set(CMAKE_C_FLAGS_DEBUG "/MDd ${CMAKE_C_FLAGS_DEBUG}") + set(CMAKE_C_FLAGS_RELEASE "/MD ${CMAKE_C_FLAGS_RELEASE}") + if (MSVC AND CMAKE_SIZEOF_VOID_P EQUAL 8) + # Not need if proper cmake gnerator (-G "...Win64") is passed to cmake + # Enable as a second measeure to workaround over bug + # http://www.cmake.org/Bug/print_bug_page.php?bug_id=11240 + set(CMAKE_SHARED_LINKER_FLAGS "/machine:x64") + endif() +endmacro() + +################################################# +macro (sdf_setup_apple) + set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -Wl,-undefined -Wl,dynamic_lookup") +endmacro() + +################################################# +include_directories(${PROJECT_SOURCE_DIR}/test/gtest/include) +macro (sdf_build_tests) + # Build all the tests + foreach(GTEST_SOURCE_file ${ARGN}) + string(REGEX REPLACE ".cc" "" BINARY_NAME ${GTEST_SOURCE_file}) + set(BINARY_NAME ${TEST_TYPE}_${BINARY_NAME}) + + if (UNIX) + add_executable(${BINARY_NAME} ${GTEST_SOURCE_file}) + elseif(WIN32) + add_executable(${BINARY_NAME} + ${GTEST_SOURCE_file} + ${PROJECT_SOURCE_DIR}/src/win/tinyxml/tinystr.cpp + ${PROJECT_SOURCE_DIR}/src/win/tinyxml/tinyxmlerror.cpp + ${PROJECT_SOURCE_DIR}/src/win/tinyxml/tinyxml.cpp + ${PROJECT_SOURCE_DIR}/src/win/tinyxml/tinyxmlparser.cpp + ) + else() + message(FATAL_ERROR "Unsupported platform") + endif() + + add_dependencies(${BINARY_NAME} + gtest gtest_main sdformat + ) + + link_directories(${IGNITION-MATH_LIBRARY_DIRS}) + + if (UNIX) + target_link_libraries(${BINARY_NAME} + libgtest.a + libgtest_main.a + sdformat + pthread + ${tinyxml_LIBRARIES} + ${IGNITION-MATH_LIBRARIES} + ) + elseif(WIN32) + target_link_libraries(${BINARY_NAME} + gtest.lib + gtest_main.lib + sdformat.dll + ${IGNITION-MATH_LIBRARIES} + ${Boost_LIBRARIES} + ) + + # Copy in sdformat library + add_custom_command(TARGET ${BINARY_NAME} + COMMAND ${CMAKE_COMMAND} -E copy_if_different + $ + $ VERBATIM) + + # Copy in ignition-math library + add_custom_command(TARGET ${BINARY_NAME} + COMMAND ${CMAKE_COMMAND} -E copy_if_different + "${IGNITION-MATH_LIBRARY_DIRS}/${IGNITION-MATH_LIBRARIES}.dll" + $ VERBATIM) + + # Copy in boost libraries + foreach(lib ${Boost_LIBRARIES}) + if (EXISTS ${lib}) + add_custom_command(TARGET ${BINARY_NAME} + COMMAND ${CMAKE_COMMAND} -E copy_if_different "${lib}" + $ VERBATIM) + + string(REPLACE ".lib" ".dll" dll ${lib}) + if (EXISTS ${dll}) + add_custom_command(TARGET ${BINARY_NAME} + COMMAND ${CMAKE_COMMAND} -E copy_if_different "${dll}" + $ VERBATIM) + endif() + + # Check if there is a .dll in the /bin/ directory, sibling of /lib/ + # This is the structure used by vcpkg boost port + string(REPLACE "/lib/" "/bin/" alt_dll ${dll}) + if (EXISTS ${alt_dll}) + add_custom_command(TARGET ${BINARY_NAME} + COMMAND ${CMAKE_COMMAND} -E copy_if_different "${alt_dll}" + $ VERBATIM) + endif() + + endif() + endforeach() + endif() + + add_test(${BINARY_NAME} ${CMAKE_CURRENT_BINARY_DIR}/${BINARY_NAME} + --gtest_output=xml:${CMAKE_BINARY_DIR}/test_results/${BINARY_NAME}.xml) + + set (_env_vars) + set (sdf_paths) + + # Get all the sdf protocol directory names + file(GLOB dirs RELATIVE "${PROJECT_SOURCE_DIR}/sdf" + "${PROJECT_SOURCE_DIR}/sdf/*") + list(SORT dirs) + + # Add each sdf protocol to the sdf_path variable + foreach(dir ${dirs}) + if (IS_DIRECTORY ${PROJECT_SOURCE_DIR}/sdf/${dir}) + set(sdf_paths "${PROJECT_SOURCE_DIR}/sdf/${dir}:${sdf_paths}") + endif() + endforeach() + + # Set the SDF_PATH environment variable + list(APPEND _env_vars "SDF_PATH=${sdf_paths}") + + set_tests_properties(${BINARY_NAME} PROPERTIES + TIMEOUT 240 + ENVIRONMENT "${_env_vars}") + + if(PYTHONINTERP_FOUND) + # Check that the test produced a result and create a failure if it didn't. + # Guards against crashed and timed out tests. + add_test(check_${BINARY_NAME} ${PYTHON_EXECUTABLE} ${PROJECT_SOURCE_DIR}/tools/check_test_ran.py + ${CMAKE_BINARY_DIR}/test_results/${BINARY_NAME}.xml) + endif() + + if(SDFORMAT_RUN_VALGRIND_TESTS AND VALGRIND_PROGRAM) + add_test(memcheck_${BINARY_NAME} ${VALGRIND_PROGRAM} --leak-check=full + --error-exitcode=1 --show-leak-kinds=all ${CMAKE_CURRENT_BINARY_DIR}/${BINARY_NAME}) + endif() + endforeach() +endmacro() + +################################################# +# Macro to setup supported compiler warnings +# Based on work of Florent Lamiraux, Thomas Moulard, JRL, CNRS/AIST. +include(CheckCXXCompilerFlag) + +macro(filter_valid_compiler_warnings) + foreach(flag ${ARGN}) + CHECK_CXX_COMPILER_FLAG(${flag} R${flag}) + if(${R${flag}}) + set(WARNING_CXX_FLAGS "${WARNING_CXX_FLAGS} ${flag}") + endif() + endforeach() +endmacro() + +################################################# +# Copied from catkin/cmake/empy.cmake +function(find_python_module module) + # cribbed from http://www.cmake.org/pipermail/cmake/2011-January/041666.html + string(TOUPPER ${module} module_upper) + if(NOT PY_${module_upper}) + if(ARGC GREATER 1 AND ARGV1 STREQUAL "REQUIRED") + set(${module}_FIND_REQUIRED TRUE) + endif() + # A module's location is usually a directory, but for + # binary modules + # it's a .so file. + execute_process(COMMAND "${PYTHON_EXECUTABLE}" "-c" "import re, ${module}; print(re.compile('/__init__.py.*').sub('',${module}.__file__))" + RESULT_VARIABLE _${module}_status + OUTPUT_VARIABLE _${module}_location + ERROR_QUIET OUTPUT_STRIP_TRAILING_WHITESPACE) + if(NOT _${module}_status) + set(PY_${module_upper} ${_${module}_location} CACHE STRING "Location of Python module ${module}") + endif(NOT _${module}_status) + endif(NOT PY_${module_upper}) + include(FindPackageHandleStandardArgs) + find_package_handle_standard_args(PY_${module} DEFAULT_MSG PY_${module_upper}) +endfunction(find_python_module) diff --git a/sdformat/cmake/SearchForStuff.cmake b/sdformat/cmake/SearchForStuff.cmake new file mode 100644 index 0000000..d19225e --- /dev/null +++ b/sdformat/cmake/SearchForStuff.cmake @@ -0,0 +1,142 @@ +include (${sdf_cmake_dir}/FindOS.cmake) +include (FindPkgConfig) + +# Detect the architecture +include (${project_cmake_dir}/TargetArch.cmake) +target_architecture(ARCH) +message(STATUS "Building for arch: ${ARCH}") + +######################################## +# Find Boost, if not specified manually +if (WIN32) + set(Boost_USE_STATIC_LIBS OFF) + set(Boost_USE_MULTITHREADED ON) + set(Boost_USE_STATIC_RUNTIME OFF) +endif() + +include(FindBoost) +find_package(Boost ${MIN_BOOST_VERSION} REQUIRED system filesystem program_options regex iostreams) + +if (NOT Boost_FOUND) + set (BUILD_SDF OFF CACHE INTERNAL "Build SDF" FORCE) + BUILD_ERROR ("Boost not found. Please install thread signals system filesystem program_options regex boost version ${MIN_BOOST_VERSION} or higher.") +endif() + +if (USE_EXTERNAL_TINYXML) + ################################################# + # Find tinyxml. Only debian distributions package tinyxml with a pkg-config + # Use pkg_check_modules and fallback to manual detection (needed, at least, for MacOS) + pkg_check_modules(tinyxml tinyxml) + if (NOT tinyxml_FOUND) + find_path (tinyxml_include_dirs tinyxml.h ${tinyxml_include_dirs} ENV CPATH) + find_library(tinyxml_LIBRARIES NAMES tinyxml) + set (tinyxml_FAIL False) + if (NOT tinyxml_include_dirs) + message (STATUS "Looking for tinyxml headers - not found") + set (tinyxml_FAIL True) + endif() + if (NOT tinyxml_LIBRARIES) + message (STATUS "Looking for tinyxml library - not found") + set (tinyxml_FAIL True) + endif() + endif() + + if (tinyxml_FAIL) + message (STATUS "Looking for tinyxml.h - not found") + BUILD_ERROR("Missing: tinyxml") + endif() +else() + # Needed in WIN32 since in UNIX the flag is added in the code installed + add_definitions(-DTIXML_USE_STL) + include_directories (${PROJECT_SOURCE_DIR}/src/win/tinyxml) + set (tinyxml_LIBRARIES "tinyxml") + set (tinyxml_LIBRARY_DIRS "") +endif() + +################################################ +# Find urdfdom parser +if (USE_EXTERNAL_URDF) + if (NOT PKG_CONFIG_FOUND) + BUILD_ERROR ("pkgconfig not found. Please install to so USE_EXTERNAL_URDF can found the urdf library") + else() + # check for urdfdom with pkg-config + pkg_check_modules(URDF urdfdom>=0.3) + + if (NOT URDF_FOUND) + # version >= 0.3.x not found, check for urdfdom again with no version + # restriction. + pkg_check_modules(URDF urdfdom) + + + if (NOT URDF_FOUND) + BUILD_ERROR ("URDF library not found. Please install it to use with USE_EXTERNAL_URDF or set this flag to false to use internal URDF code") + else() + # urdfdom library found < 0.3, unset flag + set (URDF_GE_0P3 FALSE) + endif() + + else() + # urdfdom library found >= 0.3, set flag + set (URDF_GE_0P3 TRUE) + endif() + + # what am I doing here? pkg-config and cmake + set(URDF_INCLUDE_DIRS ${URDF_INCLUDEDIR}) + set(URDF_LIBRARY_DIRS ${URDF_LIBDIR}) + endif() +else() + # the internal copy is currently 0.3.0 + set (URDF_GE_0P3 TRUE) +endif() + +################################################ +# Find the Python interpreter for running the +# check_test_ran.py script +find_package(PythonInterp QUIET) + +################################################ +# Find psutil python package for memory tests +find_python_module(psutil) +if(NOT PY_PSUTIL) + BUILD_WARNING("Python psutil package not found. Memory leak tests will be skipped") +endif() + +################################################ +# Find Valgrind for checking memory leaks in the +# tests +find_program(VALGRIND_PROGRAM NAMES valgrind PATH ${VALGRIND_ROOT}/bin) +option(SDFORMAT_RUN_VALGRIND_TESTS "Run sdformat tests with Valgrind" FALSE) +mark_as_advanced(SDFORMAT_RUN_VALGRIND_TESTS) +if (SDFORMAT_RUN_VALGRIND_TESTS AND NOT VALGRIND_PROGRAM) + BUILD_WARNING("valgrind not found. Memory check tests will be skipped.") +endif() + +################################################ +# Find ruby executable to produce xml schemas +find_program(RUBY ruby) +if (NOT RUBY) + BUILD_ERROR ("Ruby version 1.9 is needed to build xml schemas") +else() + message(STATUS "Found ruby executable: ${RUBY}") +endif() + +################################################# +# Macro to check for visibility capability in compiler +# Original idea from: https://gitorious.org/ferric-cmake-stuff/ +macro (check_gcc_visibility) + include (CheckCXXCompilerFlag) + check_cxx_compiler_flag(-fvisibility=hidden GCC_SUPPORTS_VISIBILITY) +endmacro() + +######################################## +# Find ignition math +set(IGNITION-MATH_REQUIRED_MAJOR_VERSION 2) +if (NOT DEFINED IGNITION-MATH_LIBRARY_DIRS AND NOT DEFINED IGNITION-MATH_INCLUDE_DIRS AND NOT DEFINED IGNITION-MATH_LIBRARIES) + find_package(ignition-math${IGNITION-MATH_REQUIRED_MAJOR_VERSION} QUIET) + if (NOT ignition-math${IGNITION-MATH_REQUIRED_MAJOR_VERSION}_FOUND) + message(STATUS "Looking for ignition-math${IGNITION-MATH_REQUIRED_MAJOR_VERSION}-config.cmake - not found") + BUILD_ERROR ("Missing: Ignition math${IGNITION-MATH_REQUIRED_MAJOR_VERSION} library.") + else() + message(STATUS "Looking for ignition-math${IGNITION-MATH_REQUIRED_MAJOR_VERSION}-config.cmake - found") + endif() +endif() diff --git a/sdformat/cmake/TargetArch.cmake b/sdformat/cmake/TargetArch.cmake new file mode 100644 index 0000000..323824b --- /dev/null +++ b/sdformat/cmake/TargetArch.cmake @@ -0,0 +1,158 @@ +# Copyright (c) 2012 Petroules Corporation. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# Redistributions of source code must retain the above copyright notice, this +# list of conditions and the following disclaimer. Redistributions in binary +# form must reproduce the above copyright notice, this list of conditions and +# the following disclaimer in the documentation and/or other materials +# provided with the distribution. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +# ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +# WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +# DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR +# ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +# (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON +# ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +# SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +# Based on the Qt 5 processor detection code, so should be very accurate +# https://qt.gitorious.org/qt/qtbase/blobs/master/src/corelib/global/qprocessordetection.h +# Currently handles arm (v5, v6, v7), x86 (32/64), ia64, and ppc (32/64) + +# Regarding POWER/PowerPC, just as is noted in the Qt source, +# "There are many more known variants/revisions that we do not handle/detect." + + + +set(archdetect_c_code " +#if defined(__arm__) || defined(__TARGET_ARCH_ARM) + #if defined(__ARM_ARCH_7__) \\ + || defined(__ARM_ARCH_7A__) \\ + || defined(__ARM_ARCH_7R__) \\ + || defined(__ARM_ARCH_7M__) \\ + || (defined(__TARGET_ARCH_ARM) && __TARGET_ARCH_ARM-0 >= 7) + #error cmake_ARCH armv7 + #elif defined(__ARM_ARCH_6__) \\ + || defined(__ARM_ARCH_6J__) \\ + || defined(__ARM_ARCH_6T2__) \\ + || defined(__ARM_ARCH_6Z__) \\ + || defined(__ARM_ARCH_6K__) \\ + || defined(__ARM_ARCH_6ZK__) \\ + || defined(__ARM_ARCH_6M__) \\ + || (defined(__TARGET_ARCH_ARM) && __TARGET_ARCH_ARM-0 >= 6) + #error cmake_ARCH armv6 + #elif defined(__ARM_ARCH_5TEJ__) \\ + || (defined(__TARGET_ARCH_ARM) && __TARGET_ARCH_ARM-0 >= 5) + #error cmake_ARCH armv5 + #else + #error cmake_ARCH arm + #endif +#elif defined(__i386) || defined(__i386__) || defined(_M_IX86) + #error cmake_ARCH i386 +#elif defined(__x86_64) || defined(__x86_64__) || defined(__amd64) || defined(_M_X64) + #error cmake_ARCH x86_64 +#elif defined(__ia64) || defined(__ia64__) || defined(_M_IA64) + #error cmake_ARCH ia64 +#elif defined(__ppc__) || defined(__ppc) || defined(__powerpc__) \\ + || defined(_ARCH_COM) || defined(_ARCH_PWR) || defined(_ARCH_PPC) \\ + || defined(_M_MPPC) || defined(_M_PPC) + #if defined(__ppc64__) || defined(__powerpc64__) || defined(__64BIT__) + #error cmake_ARCH ppc64 + #else + #error cmake_ARCH ppc + #endif +#endif + +#error cmake_ARCH unknown +") + +# Set ppc_support to TRUE before including this file or ppc and ppc64 +# will be treated as invalid architectures since they are no longer supported by Apple + +function(target_architecture output_var) + if(APPLE AND CMAKE_OSX_ARCHITECTURES) + # On OS X we use CMAKE_OSX_ARCHITECTURES *if* it was set + # First let's normalize the order of the values + + # Note that it's not possible to compile PowerPC applications if you are using + # the OS X SDK version 10.6 or later - you'll need 10.4/10.5 for that, so we + # disable it by default + # See this page for more information: + # http://stackoverflow.com/questions/5333490/how-can-we-restore-ppc-ppc64-as-well-as-full-10-4-10-5-sdk-support-to-xcode-4 + + # Architecture defaults to i386 or ppc on OS X 10.5 and earlier, depending on the CPU type detected at runtime. + # On OS X 10.6+ the default is x86_64 if the CPU supports it, i386 otherwise. + + foreach(osx_arch ${CMAKE_OSX_ARCHITECTURES}) + if("${osx_arch}" STREQUAL "ppc" AND ppc_support) + set(osx_arch_ppc TRUE) + elseif("${osx_arch}" STREQUAL "i386") + set(osx_arch_i386 TRUE) + elseif("${osx_arch}" STREQUAL "x86_64") + set(osx_arch_x86_64 TRUE) + elseif("${osx_arch}" STREQUAL "ppc64" AND ppc_support) + set(osx_arch_ppc64 TRUE) + else() + message(FATAL_ERROR "Invalid OS X arch name: ${osx_arch}") + endif() + endforeach() + + # Now add all the architectures in our normalized order + if(osx_arch_ppc) + list(APPEND ARCH ppc) + endif() + + if(osx_arch_i386) + list(APPEND ARCH i386) + endif() + + if(osx_arch_x86_64) + list(APPEND ARCH x86_64) + endif() + + if(osx_arch_ppc64) + list(APPEND ARCH ppc64) + endif() + else() + file(WRITE "${CMAKE_BINARY_DIR}/arch.c" "${archdetect_c_code}") + + enable_language(C) + + # Detect the architecture in a rather creative way... + # This compiles a small C program which is a series of ifdefs that selects a + # particular #error preprocessor directive whose message string contains the + # target architecture. The program will always fail to compile (both because + # file is not a valid C program, and obviously because of the presence of the + # #error preprocessor directives... but by exploiting the preprocessor in this + # way, we can detect the correct target architecture even when cross-compiling, + # since the program itself never needs to be run (only the compiler/preprocessor) + try_run( + run_result_unused + compile_result_unused + "${CMAKE_BINARY_DIR}" + "${CMAKE_BINARY_DIR}/arch.c" + COMPILE_OUTPUT_VARIABLE ARCH + CMAKE_FLAGS CMAKE_OSX_ARCHITECTURES=${CMAKE_OSX_ARCHITECTURES} + ) + + # Parse the architecture name from the compiler output + string(REGEX MATCH "cmake_ARCH ([a-zA-Z0-9_]+)" ARCH "${ARCH}") + + # Get rid of the value marker leaving just the architecture name + string(REPLACE "cmake_ARCH " "" ARCH "${ARCH}") + + # If we are compiling with an unknown architecture this variable should + # already be set to "unknown" but in the case that it's empty (i.e. due + # to a typo in the code), then set it to unknown + if (NOT ARCH) + set(ARCH unknown) + endif() + endif() + + set(${output_var} "${ARCH}" PARENT_SCOPE) +endfunction() diff --git a/sdformat/cmake/cmake_uninstall.cmake.in b/sdformat/cmake/cmake_uninstall.cmake.in new file mode 100644 index 0000000..2037e36 --- /dev/null +++ b/sdformat/cmake/cmake_uninstall.cmake.in @@ -0,0 +1,21 @@ +if(NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt") + message(FATAL_ERROR "Cannot find install manifest: @CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt") +endif(NOT EXISTS "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt") + +file(READ "@CMAKE_CURRENT_BINARY_DIR@/install_manifest.txt" files) +string(REGEX REPLACE "\n" ";" files "${files}") +foreach(file ${files}) + message(STATUS "Uninstalling $ENV{DESTDIR}${file}") + if(IS_SYMLINK "$ENV{DESTDIR}${file}" OR EXISTS "$ENV{DESTDIR}${file}") + exec_program( + "@CMAKE_COMMAND@" ARGS "-E remove \"$ENV{DESTDIR}${file}\"" + OUTPUT_VARIABLE rm_out + RETURN_VALUE rm_retval + ) + if(NOT "${rm_retval}" STREQUAL 0) + message(FATAL_ERROR "Problem when removing $ENV{DESTDIR}${file}") + endif(NOT "${rm_retval}" STREQUAL 0) + else(IS_SYMLINK "$ENV{DESTDIR}${file}" OR EXISTS "$ENV{DESTDIR}${file}") + message(STATUS "File $ENV{DESTDIR}${file} does not exist.") + endif(IS_SYMLINK "$ENV{DESTDIR}${file}" OR EXISTS "$ENV{DESTDIR}${file}") +endforeach(file) diff --git a/sdformat/cmake/cpack_options.cmake.in b/sdformat/cmake/cpack_options.cmake.in new file mode 100644 index 0000000..39de756 --- /dev/null +++ b/sdformat/cmake/cpack_options.cmake.in @@ -0,0 +1,23 @@ +set(CPACK_PACKAGE_NAME "@PROJECT_NAME@") +set(CPACK_PACKAGE_VENDOR "sdformat.org") +set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "Scene Description Format (SDF)") +set(CPACK_PACKAGE_INSTALL_DIRECTORY "@PROJECT_NAME_LOWER@") +set(CPACK_RESOURCE_FILE_LICENSE "@CMAKE_CURRENT_SOURCE_DIR@/LICENSE") +set(CPACK_RESOURCE_FILE_README "@CMAKE_CURRENT_SOURCE_DIR@/README") +set(CPACK_PACKAGE_DESCRIPTION_FILE "@CMAKE_CURRENT_SOURCE_DIR@/README") +set(CPACK_PACKAGE_MAINTAINER "Nate Koenig ") +set(CPACK_PACKAGE_CONTACT "Nate Koenig ") + +set(CPACK_DEBIAN_PACKAGE_ARCHITECTURE "@DPKG_ARCH@") +set(CPACK_DEBIAN_PACKAGE_DEPENDS "@DEBIAN_PACKAGE_DEPENDS@") +set(CPACK_DEBIAN_PACKAGE_SECTION "devel") +set(CPACK_DEBIAN_PACKAGE_PRIORITY "optional") +set(CPACK_DEBIAN_PACKAGE_SHLIBDEPS ON) +set(CPACK_DEBIAN_PACKAGE_DESCRIPTION "Format and parser for scene description files.") + +set(CPACK_RPM_PACKAGE_ARCHITECTURE "@DPKG_ARCH@") +set(CPACK_RPM_PACKAGE_REQUIRES "@DEBIAN_PACKAGE_DEPENDS@") +set(CPACK_RPM_PACKAGE_DESCRIPTION "Format and parser for scene description files.") + +set (CPACK_PACKAGE_FILE_NAME "@PROJECT_NAME_LOWER@-@SDF_VERSION_FULL@") +set (CPACK_SOURCE_PACKAGE_FILE_NAME "@PROJECT_NAME_LOWER@-@SDF_VERSION_FULL@") diff --git a/sdformat/cmake/sdf_config.cmake.in b/sdformat/cmake/sdf_config.cmake.in new file mode 100644 index 0000000..48291fe --- /dev/null +++ b/sdformat/cmake/sdf_config.cmake.in @@ -0,0 +1,37 @@ +if (@PKG_NAME@_CONFIG_INCLUDED) + return() +endif() +set(@PKG_NAME@_CONFIG_INCLUDED TRUE) + +list(APPEND @PKG_NAME@_INCLUDE_DIRS "@CMAKE_INSTALL_PREFIX@/include/sdformat-@SDF_VERSION@") + +list(APPEND @PKG_NAME@_CFLAGS "-I@CMAKE_INSTALL_PREFIX@/include/sdformat-@SDF_VERSION@") +if (NOT WIN32) + list(APPEND @PKG_NAME@_CXX_FLAGS "${@PKG_NAME@_CFLAGS} -std=c++11") +endif() + +list(APPEND @PKG_NAME@_LIBRARY_DIRS "@CMAKE_INSTALL_PREFIX@/@CMAKE_INSTALL_LIBDIR@") + +foreach(lib @PKG_LIBRARIES@) + set(onelib "${lib}-NOTFOUND") + find_library(onelib ${lib} + PATHS "@CMAKE_INSTALL_PREFIX@/@LIB_INSTALL_DIR@" + NO_DEFAULT_PATH + ) + if(NOT onelib) + message(FATAL_ERROR "Library '${lib}' in package @PKG_NAME@ is not installed properly") + endif() + list(APPEND @PKG_NAME@_LIBRARIES "${onelib}") +endforeach() + +find_package(ignition-math@IGNITION-MATH_REQUIRED_MAJOR_VERSION@) +list(APPEND @PKG_NAME@_INCLUDE_DIRS ${IGNITION-MATH_INCLUDE_DIRS}) +list(APPEND @PKG_NAME@_LIBRARIES ${IGNITION-MATH_LIBRARIES}) +list(APPEND @PKG_NAME@_LIBRARY_DIRS ${IGNITION-MATH_LIBRARY_DIRS}) + +find_package(Boost) +list(APPEND @PKG_NAME@_INCLUDE_DIRS ${Boost_INCLUDE_DIRS}) +list(APPEND @PKG_NAME@_LIBRARIES ${Boost_LIBRARIES}) +list(APPEND @PKG_NAME@_LIBRARY_DIRS ${Boost_LIBRARY_DIRS}) + +list(APPEND @PKG_NAME@_LDFLAGS "-L@CMAKE_INSTALL_PREFIX@/@LIB_INSTALL_DIR@") diff --git a/sdformat/cmake/sdf_config.h.in b/sdformat/cmake/sdf_config.h.in new file mode 100644 index 0000000..77479cc --- /dev/null +++ b/sdformat/cmake/sdf_config.h.in @@ -0,0 +1,32 @@ +/* config.h. Generated by CMake for @PROJECT_NAME@. */ + +/* Protocol version */ +#define SDF_PROTOCOL_VERSION "${SDF_PROTOCOL_VERSION}" +/* \deprecated SDF_VERSION is deprecated. Please + * use SDF_PROTOCOL_VERSION or SDF_PKG_VERSION + * + * SDF_VERSION is here to keep backwards compatibility. It was used + * when the package version and protocol version were the same + */ +#define SDF_VERSION "${SDF_PROTOCOL_VERSION}" + +/* Package version number */ +#define SDF_MAJOR_VERSION ${SDF_MAJOR_VERSION} +#define SDF_MINOR_VERSION ${SDF_MINOR_VERSION} +#define SDF_PATCH_VERSION ${SDF_PATCH_VERSION} + +#define SDF_PKG_VERSION "${SDF_VERSION}" +#define SDF_VERSION_FULL "${SDF_VERSION_FULL}" +#define SDF_VERSION_NAME ${SDF_VERSION_NAME} + +#define SDF_VERSION_HEADER "Simulation Description Format (SDF), version ${SDF_PROTOCOL_VERSION}\nCopyright (C) 2014 Open Source Robotics Foundation.\nReleased under the Apache 2 License.\nhttp://gazebosim.org/sdf\n\n" + +#cmakedefine BUILD_TYPE_PROFILE 1 +#cmakedefine BUILD_TYPE_DEBUG 1 +#cmakedefine BUILD_TYPE_RELEASE 1 +#cmakedefine HAVE_URDFDOM 1 +#cmakedefine USE_EXTERNAL_URDF 1 +#cmakedefine URDF_GE_0P3 1 + +#define SDF_SHARE_PATH "${CMAKE_INSTALL_FULL_DATAROOTDIR}/" +#define SDF_VERSION_PATH "${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat/${SDF_PKG_VERSION}" diff --git a/sdformat/cmake/sdf_cpack.cmake b/sdformat/cmake/sdf_cpack.cmake new file mode 100644 index 0000000..c216904 --- /dev/null +++ b/sdformat/cmake/sdf_cpack.cmake @@ -0,0 +1,25 @@ +################################################################################ +#Find available package generators + +# DEB +if ("${CMAKE_SYSTEM}" MATCHES "Linux") + find_program(DPKG_PROGRAM dpkg) + if (EXISTS ${DPKG_PROGRAM}) + list (APPEND CPACK_GENERATOR "DEB") + endif(EXISTS ${DPKG_PROGRAM}) + + find_program(RPMBUILD_PROGRAM rpmbuild) +endif() + +list (APPEND CPACK_SOURCE_GENERATOR "TBZ2") +list (APPEND CPACK_SOURCE_GENERATOR "ZIP") +list (APPEND CPACK_SOURCE_IGNORE_FILES ";TODO;/.hg/;.swp$;/build/") + +include (InstallRequiredSystemLibraries) + +#execute_process(COMMAND dpkg --print-architecture _NPROCE) +set (DEBIAN_PACKAGE_DEPENDS "libboost-all-dev, libtinyxml-dev") + +set (RPM_PACKAGE_DEPENDS "libboost-all-dev, libtinyxml-dev") + +set (SDF_CPACK_CFG_FILE "${PROJECT_BINARY_DIR}/cpack_options.cmake") diff --git a/sdformat/cmake/sdformat_pc.in b/sdformat/cmake/sdformat_pc.in new file mode 100644 index 0000000..54e9627 --- /dev/null +++ b/sdformat/cmake/sdformat_pc.in @@ -0,0 +1,10 @@ +prefix="@CMAKE_INSTALL_PREFIX@" +libdir=${prefix}/@LIB_INSTALL_DIR@ +includedir=${prefix}/@CMAKE_INSTALL_INCLUDEDIR@ + +Name: SDF +Description: Robot Modeling Language (SDF) +Version: @SDF_VERSION_FULL@ +Requires: ignition-math@IGNITION-MATH_REQUIRED_MAJOR_VERSION@ +Libs: -L${libdir} -lsdformat +CFlags: -I${includedir}/sdformat-@SDF_VERSION@ -std=c++11 diff --git a/sdformat/cmake/upload_doc.sh.in b/sdformat/cmake/upload_doc.sh.in new file mode 100644 index 0000000..09bfe1a --- /dev/null +++ b/sdformat/cmake/upload_doc.sh.in @@ -0,0 +1,30 @@ +#!/bin/sh + +# Usage: Only an administrator of OSRF's amazon s3 bucket will be able to use +# this script. +# +# sh build/upload_doc.sh + +# Check if the node was configured to use s3cmd +# This is done by running s3cmd --configure +if [ ! -f "${HOME}/.s3cfg" ]; then + echo "No $HOME/.s3cfg file found. Please config the software first in your system" + exit 1 +fi + +# Make documentation if not build +make doc +if [ ! -f "@CMAKE_BINARY_DIR@/doxygen/html/index.html" ]; then + echo "Documentation not present. Install doxygen, and run `make doc` in the build directory" + exit 1 +fi + +# The code API +s3cmd sync @CMAKE_BINARY_DIR@/doxygen/html/* s3://osrf-distributions/sdformat/api/@SDF_VERSION_FULL@/ --dry-run -v + +echo -n "Upload code API(Y/n)? " +read ans + +if [ "$ans" = "y" ] || [ "$ans" = "Y" ]; then + s3cmd sync @CMAKE_BINARY_DIR@/doxygen/html/* s3://osrf-distributions/sdformat/api/@SDF_VERSION_FULL@/ -v +fi diff --git a/sdformat/configure.bat b/sdformat/configure.bat new file mode 100644 index 0000000..35ee96c --- /dev/null +++ b/sdformat/configure.bat @@ -0,0 +1,12 @@ +@set build_type=Release +@if not "%1"=="" set build_type=%1 +@echo Configuring for build type %build_type% + +cmake -G "NMake Makefiles"^ + -DBOOST_ROOT:STRING="%cd%\..\..\boost_1_56_0"^ + -DBOOST_LIBRARYDIR:STRING="%cd%\..\..\boost_1_56_0\lib64-msvc-12.0"^ + -DCMAKE_INSTALL_PREFIX="install/%build_type%"^ + -DIGNITION-MATH_INCLUDE_DIRS:STRING="%cd%\..\..\ign-math\build\install\%build_type%\include\ignition\math2"^ + -DIGNITION-MATH_LIBRARY_DIRS:STRING="%cd%\..\..\ign-math\build\install\%build_type%\lib"^ + -DIGNITION-MATH_LIBRARIES="ignition-math2"^ + -DCMAKE_BUILD_TYPE="%build_type%" .. diff --git a/sdformat/doc/CMakeLists.txt b/sdformat/doc/CMakeLists.txt new file mode 100644 index 0000000..0191499 --- /dev/null +++ b/sdformat/doc/CMakeLists.txt @@ -0,0 +1,21 @@ +find_package(Doxygen) + +if (DOXYGEN_FOUND) + configure_file(${CMAKE_SOURCE_DIR}/doc/sdf.in + ${CMAKE_BINARY_DIR}/sdf.dox @ONLY) + + add_custom_target(doc + + # Generate the API documentation + ${DOXYGEN_EXECUTABLE} ${CMAKE_BINARY_DIR}/sdf.dox + WORKING_DIRECTORY ${CMAKE_BINARY_DIR} + COMMAND cp ${CMAKE_SOURCE_DIR}/doc/sdf_logo.png + ${CMAKE_BINARY_DIR}/doxygen/html + COMMAND cp ${CMAKE_SOURCE_DIR}/doc/search.js + ${CMAKE_BINARY_DIR}/doxygen/html/search + COMMAND make -C ${CMAKE_BINARY_DIR}/doxygen/latex + COMMAND mv ${CMAKE_BINARY_DIR}/doxygen/latex/refman.pdf + ${CMAKE_BINARY_DIR}/doxygen/latex/sdf-${SDF_VERSION_FULL}.pdf + + COMMENT "Generating API documentation with Doxygen" VERBATIM) +endif() diff --git a/sdformat/doc/doxygen.css b/sdformat/doc/doxygen.css new file mode 100644 index 0000000..5588342 --- /dev/null +++ b/sdformat/doc/doxygen.css @@ -0,0 +1,775 @@ +/* The standard CSS for doxygen */ + +body, table, div, p, dl { + font-family: Lucida Grande, Verdana, Geneva, Arial, sans-serif; + font-size: 12px; +} + +/* @group Heading Levels */ + +h1 { + font-size: 150%; +} + +h2 { + font-size: 120%; +} + +h3 { + font-size: 100%; +} + +dt { + font-weight: bold; +} + +div.multicol { + -moz-column-gap: 1em; + -webkit-column-gap: 1em; + -moz-column-count: 3; + -webkit-column-count: 3; +} + +p.startli, p.startdd, p.starttd { + margin-top: 2px; +} + +p.endli { + margin-bottom: 0px; +} + +p.enddd { + margin-bottom: 4px; +} + +p.endtd { + margin-bottom: 2px; +} + +/* @end */ + +caption { + font-weight: bold; +} + +span.legend { + font-size: 70%; + text-align: center; +} + +h3.version { + font-size: 90%; + text-align: center; +} + +div.qindex, div.navtab{ + background-color: #EBEFF6; + border: 1px solid #A3B4D7; + text-align: center; + margin: 2px; + padding: 2px; +} + +div.qindex +{ + width: 100%; + line-height: 140%; +} + +div.navpath +{ + margin-left: 20em; + line-height: 140%; +} + +div.navtab { + margin-right: 15px; +} + +/* @group Link Styling */ + +a { + color: #3D578C; + font-weight: normal; + text-decoration: none; +} + +.contents a:visited { + color: #4665A2; +} + +a:hover { + text-decoration: underline; +} + +a.qindex { + font-weight: bold; +} + +a.qindexHL { + font-weight: bold; + background-color: #9CAFD4; + color: #ffffff; + border: 1px double #869DCA; +} + +.contents a.qindexHL:visited { + color: #ffffff; +} + +a.el { + font-weight: bold; +} + +a.elRef { +} + +a.code { + color: #4665A2; +} + +a.codeRef { + color: #4665A2; +} + +/* @end */ + +dl.el { + margin-left: -1cm; +} + +.fragment { + font-family: monospace, fixed; + font-size: 105%; +} + +pre.fragment { + border: 1px solid #C4CFE5; + background-color: #FBFCFD; + padding: 4px 6px; + margin: 4px 8px 4px 2px; + overflow: auto; + word-wrap: break-word; + font-size: 9pt; + line-height: 125%; +} + +div.ah { + background-color: black; + font-weight: bold; + color: #ffffff; + margin-bottom: 3px; + margin-top: 3px; + padding: 0.2em; + border: solid thin #333; + border-radius: 0.5em; + -webkit-border-radius: .5em; + -moz-border-radius: .5em; + -webkit-box-shadow: 2px 2px 3px #999; + -moz-box-shadow: rgba(0, 0, 0, 0.15) 2px 2px 2px; + background-image: -webkit-gradient(linear, left top, left bottom, from(#eee), to(#000),color-stop(0.3, #444)); + background-image: -moz-linear-gradient(center top, #eee 0%, #444 40%, #000); +} + +div.groupHeader { + margin-left: 16px; + margin-top: 12px; + margin-bottom: 6px; + font-weight: bold; +} + +div.groupText { + margin-left: 16px; + font-style: italic; +} + +body { + background: white; + color: black; + margin: 0; +} + +div.contents { + margin-top: 10px; + margin-left: 20em; + margin-right: 10px; +} + +td.indexkey { + background-color: #EBEFF6; + font-weight: bold; + border: 1px solid #C4CFE5; + margin: 2px 0px 2px 0; + padding: 2px 10px; +} + +td.indexvalue { + background-color: #EBEFF6; + border: 1px solid #C4CFE5; + padding: 2px 10px; + margin: 2px 0px; +} + +tr.memlist { + background-color: #EEF1F7; +} + +p.formulaDsp { + text-align: center; +} + +img.formulaDsp { + +} + +img.formulaInl { + vertical-align: middle; +} + +div.center { + text-align: center; + margin-top: 0px; + margin-bottom: 0px; + padding: 0px; +} + +div.center img { + border: 0px; +} + +address.footer { + text-align: right; + padding-right: 12px; +} + +img.footer { + border: 0px; + vertical-align: middle; +} + +/* @group Code Colorization */ + +span.keyword { + color: #008000 +} + +span.keywordtype { + color: #604020 +} + +span.keywordflow { + color: #e08000 +} + +span.comment { + color: #800000 +} + +span.preprocessor { + color: #806020 +} + +span.stringliteral { + color: #002080 +} + +span.charliteral { + color: #008080 +} + +span.vhdldigit { + color: #ff00ff +} + +span.vhdlchar { + color: #000000 +} + +span.vhdlkeyword { + color: #700070 +} + +span.vhdllogic { + color: #ff0000 +} + +/* @end */ + +/* +.search { + color: #003399; + font-weight: bold; +} + +form.search { + margin-bottom: 0px; + margin-top: 0px; +} + +input.search { + font-size: 75%; + color: #000080; + font-weight: normal; + background-color: #e8eef2; +} +*/ + +td.tiny { + font-size: 75%; +} + +.dirtab { + padding: 4px; + border-collapse: collapse; + border: 1px solid #A3B4D7; +} + +th.dirtab { + background: #EBEFF6; + font-weight: bold; +} + +hr { + height: 0px; + border: none; + border-top: 1px solid #4A6AAA; +} + +hr.footer { + height: 1px; +} + +/* @group Member Descriptions */ + +table.memberdecls { + border-spacing: 0px; + padding: 0px; +} + +.mdescLeft, .mdescRight, +.memItemLeft, .memItemRight, +.memTemplItemLeft, .memTemplItemRight, .memTemplParams { + background-color: #F9FAFC; + border: none; + margin: 4px; + padding: 1px 0 0 8px; +} + +.mdescLeft, .mdescRight { + padding: 0px 8px 4px 8px; + color: #555; +} + +.memItemLeft, .memItemRight, .memTemplParams { + border-top: 1px solid #C4CFE5; +} + +.memItemLeft, .memTemplItemLeft { + white-space: nowrap; +} + +.memTemplParams { + color: #4665A2; + white-space: nowrap; +} + +/* @end */ + +/* @group Member Details */ + +/* Styles for detailed member documentation */ + +.memtemplate { + font-size: 80%; + color: #4665A2; + font-weight: normal; + margin-left: 3px; +} + +.memnav { + background-color: #EBEFF6; + border: 1px solid #A3B4D7; + text-align: center; + margin: 2px; + margin-right: 15px; + padding: 2px; +} + +.memitem { + padding: 0; + margin-bottom: 10px; +} + +.memname { + white-space: nowrap; + font-weight: bold; + margin-left: 6px; +} + +.memproto { + border-top: 1px solid #A8B8D9; + border-left: 1px solid #A8B8D9; + border-right: 1px solid #A8B8D9; + padding: 6px 0px 6px 0px; + color: #253555; + font-weight: bold; + text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); + /* firefox specific markup */ + -moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px; + -moz-border-radius-topright: 8px; + -moz-border-radius-topleft: 8px; + /* webkit specific markup */ + -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); + -webkit-border-top-right-radius: 8px; + -webkit-border-top-left-radius: 8px; + background-image:url('nav_f.png'); + background-repeat:repeat-x; + background-color: #E2E8F2; + +} + +.memdoc { + border-bottom: 1px solid #A8B8D9; + border-left: 1px solid #A8B8D9; + border-right: 1px solid #A8B8D9; + padding: 2px 5px; + background-color: #FBFCFD; + border-top-width: 0; + /* firefox specific markup */ + -moz-border-radius-bottomleft: 8px; + -moz-border-radius-bottomright: 8px; + -moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px; + background-image: -moz-linear-gradient(center top, #FFFFFF 0%, #FFFFFF 60%, #F7F8FB 95%, #EEF1F7); + /* webkit specific markup */ + -webkit-border-bottom-left-radius: 8px; + -webkit-border-bottom-right-radius: 8px; + -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); + background-image: -webkit-gradient(linear,center top,center bottom,from(#FFFFFF), color-stop(0.6,#FFFFFF), color-stop(0.60,#FFFFFF), color-stop(0.95,#F7F8FB), to(#EEF1F7)); +} + +.paramkey { + text-align: right; +} + +.paramtype { + white-space: nowrap; +} + +.paramname { + color: #602020; + white-space: nowrap; +} +.paramname em { + font-style: normal; +} + +/* @end */ + +/* @group Directory (tree) */ + +/* for the tree view */ + +.ftvtree { + font-family: sans-serif; + margin: 0px; +} + +/* these are for tree view when used as main index */ + +.directory { + font-size: 9pt; + font-weight: bold; + margin: 5px; +} + +.directory h3 { + margin: 0px; + margin-top: 1em; + font-size: 11pt; +} + +/* +The following two styles can be used to replace the root node title +with an image of your choice. Simply uncomment the next two styles, +specify the name of your image and be sure to set 'height' to the +proper pixel height of your image. +*/ + +/* +.directory h3.swap { + height: 61px; + background-repeat: no-repeat; + background-image: url("yourimage.gif"); +} +.directory h3.swap span { + display: none; +} +*/ + +.directory > h3 { + margin-top: 0; +} + +.directory p { + margin: 0px; + white-space: nowrap; +} + +.directory div { + display: none; + margin: 0px; +} + +.directory img { + vertical-align: -30%; +} + +/* these are for tree view when not used as main index */ + +.directory-alt { + font-size: 100%; + font-weight: bold; +} + +.directory-alt h3 { + margin: 0px; + margin-top: 1em; + font-size: 11pt; +} + +.directory-alt > h3 { + margin-top: 0; +} + +.directory-alt p { + margin: 0px; + white-space: nowrap; +} + +.directory-alt div { + display: none; + margin: 0px; +} + +.directory-alt img { + vertical-align: -30%; +} + +/* @end */ + +div.dynheader { + margin-top: 8px; +} + +address { + font-style: normal; + color: #2A3D61; +} + +table.doxtable { + border-collapse:collapse; +} + +table.doxtable td, table.doxtable th { + border: 1px solid #2D4068; + padding: 3px 7px 2px; +} + +table.doxtable th { + background-color: #374F7F; + color: #FFFFFF; + font-size: 110%; + padding-bottom: 4px; + padding-top: 5px; + text-align:left; +} + +.tabsearch { + top: 0px; + left: 10px; + height: 36px; + background-image: url('tab_b.png'); + z-index: 101; + overflow: hidden; + font-size: 13px; +} + +.navpath ul +{ + font-size: 11px; + background-image:url('tab_b.png'); + background-repeat:repeat-x; + height:30px; + line-height:30px; + color:#8AA0CC; + border:solid 1px #C2CDE4; + overflow:hidden; + margin:0px; + padding:0px; +} + +.navpath li +{ + list-style-type:none; + float:left; + padding-left:10px; + padding-right: 15px; + background-image:url('bc_s.png'); + background-repeat:no-repeat; + background-position:right; + color:#364D7C; +} + +.navpath a +{ + height:32px; + display:block; + text-decoration: none; + outline: none; +} + +.navpath a:hover +{ + color:#6884BD; +} + +div.summary +{ + float: right; + font-size: 8pt; + padding-right: 5px; + width: 50%; + text-align: right; +} + +div.summary a +{ + white-space: nowrap; +} + +div.header +{ + background-image:url('nav_h.png'); + background-repeat:repeat-x; + background-color: #F9FAFC; + margin: 0px; + margin-left: 20em; + border-bottom: 1px solid #C4CFE5; +} + +div.headertitle +{ + padding: 5px 5px 5px 10px; +} + +#content { + /*position: absolute; */ + left:12em; + top:0em; + padding-left:3em; + padding-right:3em; + padding-bottom:2em; + margin-top:1em; + margin-right:2em; +} + +.floatright +{ + float: right; + margin: 0 0 1em 1em; +} + +.timestamp { + text-align:right; + background-color: #DDD; + font-size:75%; +} + + +#MSearchBox +{ + border: 1px solid black; + position: static; + margin: 10px; + display: block; + height: 20px; +} + +#MSearchField +{ + background:none; +} + +/*iframe#MSearchResults +{ + height: 500px; + text-wrap: unrestricted; + border: none; +} +*/ +/* +#MSearchResultsWindow +{ + display: block; + position: fixed; +}*/ + +div.leftbar +{ + text-align:left; + float: left; + border-right: 1px solid #dddddd; + width: 18em; + margin: 5 5 5 5; + padding: 4 4 4 4; + background-color: #ffffff; + position: fixed; + height: 100%; +} + +div.menu { + #display:block; + background:#ffffff; + font-size: 90%; + /*border-top: 2px solid #000000; + border-bottom: 2px solid #000000; +*/ + margin: 0 0 10px 0; +} + +div.menu dl { + margin-top: 0px; + margin-bottom: 5px; +} + +div.menu dt { + font-weight:bold; + padding:0 4px 4px 4px; + font-size: 110%; + text-align: left; + text-decoration:none; +} + +div.menu dd { + font-weight: bold; + margin-left: 0px; + padding-left: 20px; + padding-bottom: 2px; + font-size: 100%; +} + + +div.leftbar img { + border:0; +} + +div.submenu dd { + font-size: 70%; + margin-left: 8px; + padding-left: 10px; + padding-bottom: 3px; +} + +div.submenu dd .secondline { + margin-left: 12px; +} diff --git a/sdformat/doc/footer.html b/sdformat/doc/footer.html new file mode 100644 index 0000000..71d71c4 --- /dev/null +++ b/sdformat/doc/footer.html @@ -0,0 +1 @@ + diff --git a/sdformat/doc/header.html b/sdformat/doc/header.html new file mode 100644 index 0000000..e0cfd8c --- /dev/null +++ b/sdformat/doc/header.html @@ -0,0 +1,67 @@ + + + + + + + SDF: $title + + + + + + + + + + + + +
    +

    + +

    + + + +
    +
    + + + + +
    + +
    + +
    +
    +
    +
    diff --git a/sdformat/doc/mainpage.html b/sdformat/doc/mainpage.html new file mode 100644 index 0000000..11ed373 --- /dev/null +++ b/sdformat/doc/mainpage.html @@ -0,0 +1,33 @@ + +/** \mainpage SDF API Reference + +This documentation provides useful information about the Simulation +Desctiption Format API. The code reference is divided into the groups below. +Should you find problems with this documentation - typos, unclear phrases, +or insufficient detail - please create a new bitbucket issue. +Include sufficient detail to quickly locate the problematic documentation, +and set the issue's fields accordingly: Assignee - blank; Kind - bug; +Priority - minor; Version - blank. + +
    +
    Class
    +
    List - Index of all classes in Gazebo, organized alphabetically
    + +
    Hierarchy - Index of classes, organized hierachically according to their inheritance
    +
    + + +
    +
    Links
    +
    Website: The main SDF website.
    + +
    Specification: Documentation of sdformat elements.
    + +
    Tutorials: Tutorials that describe how to use SDF.
    + +
    Download: How to download and install SDF
    +
    + + +*/ diff --git a/sdformat/doc/sdf.in b/sdformat/doc/sdf.in new file mode 100644 index 0000000..c933a40 --- /dev/null +++ b/sdformat/doc/sdf.in @@ -0,0 +1,1810 @@ +# Doxyfile 1.8.2 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project. +# +# All text after a hash (#) is considered a comment and will be ignored. +# The format is: +# TAG = value [value, ...] +# For lists items can also be appended using: +# TAG += value [value, ...] +# Values that contain spaces should be placed between quotes (" "). + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- + +# This tag specifies the encoding used for all characters in the config file +# that follow. The default is UTF-8 which is also the encoding used for all +# text before the first occurrence of this tag. Doxygen uses libiconv (or the +# iconv built into libc) for the transcoding. See +# http://www.gnu.org/software/libiconv for the list of possible encodings. + +DOXYFILE_ENCODING = UTF-8 + +# The PROJECT_NAME tag is a single word (or sequence of words) that should +# identify the project. Note that if you do not use Doxywizard you need +# to put quotes around the project name if it contains spaces. + +PROJECT_NAME = SDF + +# The PROJECT_NUMBER tag can be used to enter a project or revision number. +# This could be handy for archiving the generated documentation or +# if some version control system is used. + +PROJECT_NUMBER = @SDF_VERSION_FULL@ + +# Using the PROJECT_BRIEF tag one can provide an optional one line description +# for a project that appears at the top of each page and should give viewer +# a quick idea about the purpose of the project. Keep the description short. + +PROJECT_BRIEF = + +# With the PROJECT_LOGO tag one can specify an logo or icon that is +# included in the documentation. The maximum height of the logo should not +# exceed 55 pixels and the maximum width should not exceed 200 pixels. +# Doxygen will copy the logo to the output directory. + +PROJECT_LOGO = + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) +# base path where the generated documentation will be put. +# If a relative path is entered, it will be relative to the location +# where doxygen was started. If left blank the current directory will be used. + +OUTPUT_DIRECTORY = doxygen + +# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create +# 4096 sub-directories (in 2 levels) under the output directory of each output +# format and will distribute the generated files over these directories. +# Enabling this option can be useful when feeding doxygen a huge amount of +# source files, where putting all generated files in the same directory would +# otherwise cause performance problems for the file system. + +CREATE_SUBDIRS = NO + +# The OUTPUT_LANGUAGE tag is used to specify the language in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all constant output in the proper language. +# The default language is English, other supported languages are: +# Afrikaans, Arabic, Brazilian, Catalan, Chinese, Chinese-Traditional, +# Croatian, Czech, Danish, Dutch, Esperanto, Farsi, Finnish, French, German, +# Greek, Hungarian, Italian, Japanese, Japanese-en (Japanese with English +# messages), Korean, Korean-en, Lithuanian, Norwegian, Macedonian, Persian, +# Polish, Portuguese, Romanian, Russian, Serbian, Serbian-Cyrillic, Slovak, +# Slovene, Spanish, Swedish, Ukrainian, and Vietnamese. + +OUTPUT_LANGUAGE = English + +# If the BRIEF_MEMBER_DESC tag is set to YES (the default) Doxygen will +# include brief member descriptions after the members that are listed in +# the file and class documentation (similar to JavaDoc). +# Set to NO to disable this. + +BRIEF_MEMBER_DESC = YES + +# If the REPEAT_BRIEF tag is set to YES (the default) Doxygen will prepend +# the brief description of a member or function before the detailed description. +# Note: if both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the +# brief descriptions will be completely suppressed. + +REPEAT_BRIEF = YES + +# This tag implements a quasi-intelligent brief description abbreviator +# that is used to form the text in various listings. Each string +# in this list, if found as the leading text of the brief description, will be +# stripped from the text and the result after processing the whole list, is +# used as the annotated text. Otherwise, the brief description is used as-is. +# If left blank, the following values are used ("$name" is automatically +# replaced with the name of the entity): "The $name class" "The $name widget" +# "The $name file" "is" "provides" "specifies" "contains" +# "represents" "a" "an" "the" + +ABBREVIATE_BRIEF = + +# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then +# Doxygen will generate a detailed section even if there is only a brief +# description. + +ALWAYS_DETAILED_SEC = YES + +# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all +# inherited members of a class in the documentation of that class as if those +# members were ordinary class members. Constructors, destructors and assignment +# operators of the base classes will not be shown. + +INLINE_INHERITED_MEMB = NO + +# If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full +# path before files name in the file list and in the header files. If set +# to NO the shortest path that makes the file name unique will be used. + +FULL_PATH_NAMES = NO + +# If the FULL_PATH_NAMES tag is set to YES then the STRIP_FROM_PATH tag +# can be used to strip a user-defined part of the path. Stripping is +# only done if one of the specified strings matches the left-hand part of +# the path. The tag can be used to show relative paths in the file list. +# If left blank the directory from which doxygen is run is used as the +# path to strip. Note that you specify absolute paths here, but also +# relative paths, which will be relative from the directory where doxygen is +# started. + +STRIP_FROM_PATH = + +# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of +# the path mentioned in the documentation of a class, which tells +# the reader which header file to include in order to use a class. +# If left blank only the name of the header file containing the class +# definition is used. Otherwise one should specify the include paths that +# are normally passed to the compiler using the -I flag. + +STRIP_FROM_INC_PATH = + +# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter +# (but less readable) file names. This can be useful if your file system +# doesn't support long names like on DOS, Mac, or CD-ROM. + +SHORT_NAMES = NO + +# If the JAVADOC_AUTOBRIEF tag is set to YES then Doxygen +# will interpret the first line (until the first dot) of a JavaDoc-style +# comment as the brief description. If set to NO, the JavaDoc +# comments will behave just like regular Qt-style comments +# (thus requiring an explicit @brief command for a brief description.) + +JAVADOC_AUTOBRIEF = YES + +# If the QT_AUTOBRIEF tag is set to YES then Doxygen will +# interpret the first line (until the first dot) of a Qt-style +# comment as the brief description. If set to NO, the comments +# will behave just like regular Qt-style comments (thus requiring +# an explicit \brief command for a brief description.) + +QT_AUTOBRIEF = NO + +# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make Doxygen +# treat a multi-line C++ special comment block (i.e. a block of //! or /// +# comments) as a brief description. This used to be the default behaviour. +# The new default is to treat a multi-line C++ comment block as a detailed +# description. Set this tag to YES if you prefer the old behaviour instead. + +MULTILINE_CPP_IS_BRIEF = NO + +# If the INHERIT_DOCS tag is set to YES (the default) then an undocumented +# member inherits the documentation from any documented member that it +# re-implements. + +INHERIT_DOCS = YES + +# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce +# a new page for each member. If set to NO, the documentation of a member will +# be part of the file/class/namespace that contains it. + +SEPARATE_MEMBER_PAGES = NO + +# The TAB_SIZE tag can be used to set the number of spaces in a tab. +# Doxygen uses this value to replace tabs by spaces in code fragments. + +TAB_SIZE = 4 + +# This tag can be used to specify a number of aliases that acts +# as commands in the documentation. An alias has the form "name=value". +# For example adding "sideeffect=\par Side Effects:\n" will allow you to +# put the command \sideeffect (or @sideeffect) in the documentation, which +# will result in a user-defined paragraph with heading "Side Effects:". +# You can put \n's in the value part of an alias to insert newlines. + +ALIASES = + +# This tag can be used to specify a number of word-keyword mappings (TCL only). +# A mapping has the form "name=value". For example adding +# "class=itcl::class" will allow you to use the command class in the +# itcl::class meaning. + +TCL_SUBST = + +# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C +# sources only. Doxygen will then generate output that is more tailored for C. +# For instance, some of the names that are used will be different. The list +# of all members will be omitted, etc. + +OPTIMIZE_OUTPUT_FOR_C = NO + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java +# sources only. Doxygen will then generate output that is more tailored for +# Java. For instance, namespaces will be presented as packages, qualified +# scopes will look different, etc. + +OPTIMIZE_OUTPUT_JAVA = NO + +# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran +# sources only. Doxygen will then generate output that is more tailored for +# Fortran. + +OPTIMIZE_FOR_FORTRAN = NO + +# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL +# sources. Doxygen will then generate output that is tailored for +# VHDL. + +OPTIMIZE_OUTPUT_VHDL = NO + +# Doxygen selects the parser to use depending on the extension of the files it +# parses. With this tag you can assign which parser to use for a given +# extension. Doxygen has a built-in mapping, but you can override or extend it +# using this tag. The format is ext=language, where ext is a file extension, +# and language is one of the parsers supported by doxygen: IDL, Java, +# Javascript, CSharp, C, C++, D, PHP, Objective-C, Python, Fortran, VHDL, C, +# C++. For instance to make doxygen treat .inc files as Fortran files (default +# is PHP), and .f files as C (default is Fortran), use: inc=Fortran f=C. Note +# that for custom extensions you also need to set FILE_PATTERNS otherwise the +# files are not read by doxygen. + +EXTENSION_MAPPING = + +# If MARKDOWN_SUPPORT is enabled (the default) then doxygen pre-processes all +# comments according to the Markdown format, which allows for more readable +# documentation. See http://daringfireball.net/projects/markdown/ for details. +# The output of markdown processing is further processed by doxygen, so you +# can mix doxygen, HTML, and XML commands with Markdown formatting. +# Disable only in case of backward compatibilities issues. + +MARKDOWN_SUPPORT = YES + +# When enabled doxygen tries to link words that correspond to documented classes, +# or namespaces to their corresponding documentation. Such a link can be +# prevented in individual cases by by putting a % sign in front of the word or +# globally by setting AUTOLINK_SUPPORT to NO. + +AUTOLINK_SUPPORT = YES + +# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want +# to include (a tag file for) the STL sources as input, then you should +# set this tag to YES in order to let doxygen match functions declarations and +# definitions whose arguments contain STL classes (e.g. func(std::string); v.s. +# func(std::string) {}). This also makes the inheritance and collaboration +# diagrams that involve STL classes more complete and accurate. + +BUILTIN_STL_SUPPORT = YES + +# If you use Microsoft's C++/CLI language, you should set this option to YES to +# enable parsing support. + +CPP_CLI_SUPPORT = NO + +# Set the SIP_SUPPORT tag to YES if your project consists of sip sources only. +# Doxygen will parse them like normal C++ but will assume all classes use public +# instead of private inheritance when no explicit protection keyword is present. + +SIP_SUPPORT = NO + +# For Microsoft's IDL there are propget and propput attributes to indicate getter and setter methods for a property. Setting this option to YES (the default) will make doxygen replace the get and set methods by a property in the documentation. This will only work if the methods are indeed getting or setting a simple type. If this is not the case, or you want to show the methods anyway, you should set this option to NO. + +IDL_PROPERTY_SUPPORT = YES + +# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC +# tag is set to YES, then doxygen will reuse the documentation of the first +# member in the group (if any) for the other members of the group. By default +# all members of a group must be documented explicitly. + +DISTRIBUTE_GROUP_DOC = YES + +# Set the SUBGROUPING tag to YES (the default) to allow class member groups of +# the same type (for instance a group of public functions) to be put as a +# subgroup of that type (e.g. under the Public Functions section). Set it to +# NO to prevent subgrouping. Alternatively, this can be done per class using +# the \nosubgrouping command. + +SUBGROUPING = YES + +# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and +# unions are shown inside the group in which they are included (e.g. using +# @ingroup) instead of on a separate page (for HTML and Man pages) or +# section (for LaTeX and RTF). + +INLINE_GROUPED_CLASSES = NO + +# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and +# unions with only public data fields will be shown inline in the documentation +# of the scope in which they are defined (i.e. file, namespace, or group +# documentation), provided this scope is documented. If set to NO (the default), +# structs, classes, and unions are shown on a separate page (for HTML and Man +# pages) or section (for LaTeX and RTF). + +INLINE_SIMPLE_STRUCTS = NO + +# When TYPEDEF_HIDES_STRUCT is enabled, a typedef of a struct, union, or enum +# is documented as struct, union, or enum with the name of the typedef. So +# typedef struct TypeS {} TypeT, will appear in the documentation as a struct +# with name TypeT. When disabled the typedef will appear as a member of a file, +# namespace, or class. And the struct will be named TypeS. This can typically +# be useful for C code in case the coding convention dictates that all compound +# types are typedef'ed and only the typedef is referenced, never the tag name. + +TYPEDEF_HIDES_STRUCT = NO + +# The SYMBOL_CACHE_SIZE determines the size of the internal cache use to +# determine which symbols to keep in memory and which to flush to disk. +# When the cache is full, less often used symbols will be written to disk. +# For small to medium size projects (<1000 input files) the default value is +# probably good enough. For larger projects a too small cache size can cause +# doxygen to be busy swapping symbols to and from disk most of the time +# causing a significant performance penalty. +# If the system has enough physical memory increasing the cache will improve the +# performance by keeping more symbols in memory. Note that the value works on +# a logarithmic scale so increasing the size by one will roughly double the +# memory usage. The cache size is given by this formula: +# 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0, +# corresponding to a cache size of 2^16 = 65536 symbols. + +SYMBOL_CACHE_SIZE = 0 + +# Similar to the SYMBOL_CACHE_SIZE the size of the symbol lookup cache can be +# set using LOOKUP_CACHE_SIZE. This cache is used to resolve symbols given +# their name and scope. Since this can be an expensive process and often the +# same symbol appear multiple times in the code, doxygen keeps a cache of +# pre-resolved symbols. If the cache is too small doxygen will become slower. +# If the cache is too large, memory is wasted. The cache size is given by this +# formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range is 0..9, the default is 0, +# corresponding to a cache size of 2^16 = 65536 symbols. + +LOOKUP_CACHE_SIZE = 0 + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in +# documentation are documented, even if no documentation was available. +# Private class members and static file members will be hidden unless +# the EXTRACT_PRIVATE and EXTRACT_STATIC tags are set to YES + +EXTRACT_ALL = YES + +# If the EXTRACT_PRIVATE tag is set to YES all private members of a class +# will be included in the documentation. + +EXTRACT_PRIVATE = NO + +# If the EXTRACT_PACKAGE tag is set to YES all members with package or internal +# scope will be included in the documentation. + +EXTRACT_PACKAGE = NO + +# If the EXTRACT_STATIC tag is set to YES all static members of a file +# will be included in the documentation. + +EXTRACT_STATIC = YES + +# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) +# defined locally in source files will be included in the documentation. +# If set to NO only classes defined in header files are included. + +EXTRACT_LOCAL_CLASSES = NO + +# This flag is only useful for Objective-C code. When set to YES local +# methods, which are defined in the implementation section but not in +# the interface are included in the documentation. +# If set to NO (the default) only methods in the interface are included. + +EXTRACT_LOCAL_METHODS = NO + +# If this flag is set to YES, the members of anonymous namespaces will be +# extracted and appear in the documentation as a namespace called +# 'anonymous_namespace{file}', where file will be replaced with the base +# name of the file that contains the anonymous namespace. By default +# anonymous namespaces are hidden. + +EXTRACT_ANON_NSPACES = YES + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, Doxygen will hide all +# undocumented members of documented classes, files or namespaces. +# If set to NO (the default) these members will be included in the +# various overviews, but no documentation section is generated. +# This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_MEMBERS = NO + +# If the HIDE_UNDOC_CLASSES tag is set to YES, Doxygen will hide all +# undocumented classes that are normally visible in the class hierarchy. +# If set to NO (the default) these classes will be included in the various +# overviews. This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_CLASSES = NO + +# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, Doxygen will hide all +# friend (class|struct|union) declarations. +# If set to NO (the default) these declarations will be included in the +# documentation. + +HIDE_FRIEND_COMPOUNDS = YES + +# If the HIDE_IN_BODY_DOCS tag is set to YES, Doxygen will hide any +# documentation blocks found inside the body of a function. +# If set to NO (the default) these blocks will be appended to the +# function's detailed documentation block. + +HIDE_IN_BODY_DOCS = NO + +# The INTERNAL_DOCS tag determines if documentation +# that is typed after a \internal command is included. If the tag is set +# to NO (the default) then the documentation will be excluded. +# Set it to YES to include the internal documentation. + +INTERNAL_DOCS = NO + +# If the CASE_SENSE_NAMES tag is set to NO then Doxygen will only generate +# file names in lower-case letters. If set to YES upper-case letters are also +# allowed. This is useful if you have classes or files whose names only differ +# in case and if your file system supports case sensitive file names. Windows +# and Mac users are advised to set this option to NO. + +CASE_SENSE_NAMES = YES + +# If the HIDE_SCOPE_NAMES tag is set to NO (the default) then Doxygen +# will show members with their full class and namespace scopes in the +# documentation. If set to YES the scope will be hidden. + +HIDE_SCOPE_NAMES = NO + +# If the SHOW_INCLUDE_FILES tag is set to YES (the default) then Doxygen +# will put a list of the files that are included by a file in the documentation +# of that file. + +SHOW_INCLUDE_FILES = YES + +# If the FORCE_LOCAL_INCLUDES tag is set to YES then Doxygen +# will list include files with double quotes in the documentation +# rather than with sharp brackets. + +FORCE_LOCAL_INCLUDES = NO + +# If the INLINE_INFO tag is set to YES (the default) then a tag [inline] +# is inserted in the documentation for inline members. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES (the default) then doxygen +# will sort the (detailed) documentation of file and class members +# alphabetically by member name. If set to NO the members will appear in +# declaration order. + +SORT_MEMBER_DOCS = YES + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the +# brief documentation of file, namespace and class members alphabetically +# by member name. If set to NO (the default) the members will appear in +# declaration order. + +SORT_BRIEF_DOCS = YES + +# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen +# will sort the (brief and detailed) documentation of class members so that +# constructors and destructors are listed first. If set to NO (the default) +# the constructors will appear in the respective orders defined by +# SORT_MEMBER_DOCS and SORT_BRIEF_DOCS. +# This tag will be ignored for brief docs if SORT_BRIEF_DOCS is set to NO +# and ignored for detailed docs if SORT_MEMBER_DOCS is set to NO. + +SORT_MEMBERS_CTORS_1ST = YES + +# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the +# hierarchy of group names into alphabetical order. If set to NO (the default) +# the group names will appear in their defined order. + +SORT_GROUP_NAMES = NO + +# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be +# sorted by fully-qualified names, including namespaces. If set to +# NO (the default), the class list will be sorted only by class name, +# not including the namespace part. +# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. +# Note: This option applies only to the class list, not to the +# alphabetical list. + +SORT_BY_SCOPE_NAME = NO + +# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to +# do proper type resolution of all parameters of a function it will reject a +# match between the prototype and the implementation of a member function even +# if there is only one candidate or it is obvious which candidate to choose +# by doing a simple string match. By disabling STRICT_PROTO_MATCHING doxygen +# will still accept a match between prototype and implementation in such cases. + +STRICT_PROTO_MATCHING = NO + +# The GENERATE_TODOLIST tag can be used to enable (YES) or +# disable (NO) the todo list. This list is created by putting \todo +# commands in the documentation. + +GENERATE_TODOLIST = YES + +# The GENERATE_TESTLIST tag can be used to enable (YES) or +# disable (NO) the test list. This list is created by putting \test +# commands in the documentation. + +GENERATE_TESTLIST = YES + +# The GENERATE_BUGLIST tag can be used to enable (YES) or +# disable (NO) the bug list. This list is created by putting \bug +# commands in the documentation. + +GENERATE_BUGLIST = YES + +# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or +# disable (NO) the deprecated list. This list is created by putting +# \deprecated commands in the documentation. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional +# documentation sections, marked by \if sectionname ... \endif. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines +# the initial value of a variable or macro consists of for it to appear in +# the documentation. If the initializer consists of more lines than specified +# here it will be hidden. Use a value of 0 to hide initializers completely. +# The appearance of the initializer of individual variables and macros in the +# documentation can be controlled using \showinitializer or \hideinitializer +# command in the documentation regardless of this setting. + +MAX_INITIALIZER_LINES = 30 + +# Set the SHOW_USED_FILES tag to NO to disable the list of files generated +# at the bottom of the documentation of classes and structs. If set to YES the +# list will mention the files that were used to generate the documentation. + +SHOW_USED_FILES = YES + +# Set the SHOW_FILES tag to NO to disable the generation of the Files page. +# This will remove the Files entry from the Quick Index and from the +# Folder Tree View (if specified). The default is YES. + +SHOW_FILES = YES + +# Set the SHOW_NAMESPACES tag to NO to disable the generation of the +# Namespaces page. +# This will remove the Namespaces entry from the Quick Index +# and from the Folder Tree View (if specified). The default is YES. + +SHOW_NAMESPACES = YES + +# The FILE_VERSION_FILTER tag can be used to specify a program or script that +# doxygen should invoke to get the current version for each file (typically from +# the version control system). Doxygen will invoke the program by executing (via +# popen()) the command , where is the value of +# the FILE_VERSION_FILTER tag, and is the name of an input file +# provided by doxygen. Whatever the program writes to standard output +# is used as the file version. See the manual for examples. + +FILE_VERSION_FILTER = + +# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed +# by doxygen. The layout file controls the global structure of the generated +# output files in an output format independent way. To create the layout file +# that represents doxygen's defaults, run doxygen with the -l option. +# You can optionally specify a file name after the option, if omitted +# DoxygenLayout.xml will be used as the name of the layout file. + +LAYOUT_FILE = + +# The CITE_BIB_FILES tag can be used to specify one or more bib files +# containing the references data. This must be a list of .bib files. The +# .bib extension is automatically appended if omitted. Using this command +# requires the bibtex tool to be installed. See also +# http://en.wikipedia.org/wiki/BibTeX for more info. For LaTeX the style +# of the bibliography can be controlled using LATEX_BIB_STYLE. To use this +# feature you need bibtex and perl available in the search path. + +CITE_BIB_FILES = + +#--------------------------------------------------------------------------- +# configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated +# by doxygen. Possible values are YES and NO. If left blank NO is used. + +QUIET = NO + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated by doxygen. Possible values are YES and NO. If left blank +# NO is used. + +WARNINGS = YES + +# If WARN_IF_UNDOCUMENTED is set to YES, then doxygen will generate warnings +# for undocumented members. If EXTRACT_ALL is set to YES then this flag will +# automatically be disabled. + +WARN_IF_UNDOCUMENTED = YES + +# If WARN_IF_DOC_ERROR is set to YES, doxygen will generate warnings for +# potential errors in the documentation, such as not documenting some +# parameters in a documented function, or documenting parameters that +# don't exist or using markup commands wrongly. + +WARN_IF_DOC_ERROR = YES + +# The WARN_NO_PARAMDOC option can be enabled to get warnings for +# functions that are documented, but have no documentation for their parameters +# or return value. If set to NO (the default) doxygen will only warn about +# wrong or incomplete parameter documentation, but not about the absence of +# documentation. + +WARN_NO_PARAMDOC = NO + +# The WARN_FORMAT tag determines the format of the warning messages that +# doxygen can produce. The string should contain the $file, $line, and $text +# tags, which will be replaced by the file and line number from which the +# warning originated and the warning text. Optionally the format may contain +# $version, which will be replaced by the version of the file (if it could +# be obtained via FILE_VERSION_FILTER) + +WARN_FORMAT = "$file:$line: $text" + +# The WARN_LOGFILE tag can be used to specify a file to which warning +# and error messages should be written. If left blank the output is written +# to stderr. + +WARN_LOGFILE = /tmp/sdf_dox.warn + +#--------------------------------------------------------------------------- +# configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag can be used to specify the files and/or directories that contain +# documented source files. You may enter file names like "myfile.cpp" or +# directories like "/usr/src/myproject". Separate the files or directories +# with spaces. + +INPUT = @CMAKE_SOURCE_DIR@/doc/mainpage.html \ + @CMAKE_SOURCE_DIR@/include/sdf + +# This tag can be used to specify the character encoding of the source files +# that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is +# also the default input encoding. Doxygen uses libiconv (or the iconv built +# into libc) for the transcoding. See http://www.gnu.org/software/libiconv for +# the list of possible encodings. + +INPUT_ENCODING = UTF-8 + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank the following patterns are tested: +# *.c *.cc *.cxx *.cpp *.c++ *.d *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh +# *.hxx *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.dox *.py +# *.f90 *.f *.for *.vhd *.vhdl + +FILE_PATTERNS = *.hh \ + *.h + +# The RECURSIVE tag can be used to turn specify whether or not subdirectories +# should be searched for input files as well. Possible values are YES and NO. +# If left blank NO is used. + +RECURSIVE = YES + +# The EXCLUDE tag can be used to specify files and/or directories that should be +# excluded from the INPUT source files. This way you can easily exclude a +# subdirectory from a directory tree whose root is specified with the INPUT tag. +# Note that relative paths are relative to the directory from which doxygen is +# run. + +EXCLUDE = + +# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or +# directories that are symbolic links (a Unix file system feature) are excluded +# from the input. + +EXCLUDE_SYMLINKS = NO + +# If the value of the INPUT tag contains directories, you can use the +# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude +# certain files from those directories. Note that the wildcards are matched +# against the file with absolute path, so to exclude all test directories +# for example use the pattern */test/* + +EXCLUDE_PATTERNS = + +# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names +# (namespaces, classes, functions, etc.) that should be excluded from the +# output. The symbol name can be a fully qualified name, a word, or if the +# wildcard * is used, a substring. Examples: ANamespace, AClass, +# AClass::ANamespace, ANamespace::*Test + +EXCLUDE_SYMBOLS = + +# The EXAMPLE_PATH tag can be used to specify one or more files or +# directories that contain example code fragments that are included (see +# the \include command). + +EXAMPLE_PATH = examples + +# If the value of the EXAMPLE_PATH tag contains directories, you can use the +# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank all files are included. + +EXAMPLE_PATTERNS = *.cc *.hh + +# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be +# searched for input files to be used with the \include or \dontinclude +# commands irrespective of the value of the RECURSIVE tag. +# Possible values are YES and NO. If left blank NO is used. + +EXAMPLE_RECURSIVE = YES + +# The IMAGE_PATH tag can be used to specify one or more files or +# directories that contain image that are included in the documentation (see +# the \image command). + +IMAGE_PATH = + +# The INPUT_FILTER tag can be used to specify a program that doxygen should +# invoke to filter for each input file. Doxygen will invoke the filter program +# by executing (via popen()) the command , where +# is the value of the INPUT_FILTER tag, and is the name of an +# input file. Doxygen will then use the output that the filter program writes +# to standard output. +# If FILTER_PATTERNS is specified, this tag will be +# ignored. + +INPUT_FILTER = "sed 's/boost::shared_ptr<\(.*\)>/\1*/'" + +# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern +# basis. +# Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. +# The filters are a list of the form: +# pattern=filter (like *.cpp=my_cpp_filter). See INPUT_FILTER for further +# info on how filters are used. If FILTER_PATTERNS is empty or if +# non of the patterns match the file name, INPUT_FILTER is applied. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER) will be used to filter the input files when producing source +# files to browse (i.e. when SOURCE_BROWSER is set to YES). + +FILTER_SOURCE_FILES = NO + +# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file +# pattern. A pattern will override the setting for FILTER_PATTERN (if any) +# and it is also possible to disable source filtering for a specific pattern +# using *.ext= (so without naming a filter). This option only has effect when +# FILTER_SOURCE_FILES is enabled. + +FILTER_SOURCE_PATTERNS = + +#--------------------------------------------------------------------------- +# configuration options related to source browsing +#--------------------------------------------------------------------------- + +# If the SOURCE_BROWSER tag is set to YES then a list of source files will +# be generated. Documented entities will be cross-referenced with these sources. +# Note: To get rid of all source code in the generated output, make sure also +# VERBATIM_HEADERS is set to NO. + +SOURCE_BROWSER = NO + +# Setting the INLINE_SOURCES tag to YES will include the body +# of functions and classes directly in the documentation. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES (the default) will instruct +# doxygen to hide any special comment blocks from generated source code +# fragments. Normal C, C++ and Fortran comments will always remain visible. + +STRIP_CODE_COMMENTS = YES + +# If the REFERENCED_BY_RELATION tag is set to YES +# then for each documented function all documented +# functions referencing it will be listed. + +REFERENCED_BY_RELATION = YES + +# If the REFERENCES_RELATION tag is set to YES +# then for each documented function all documented entities +# called/used by that function will be listed. + +REFERENCES_RELATION = YES + +# If the REFERENCES_LINK_SOURCE tag is set to YES (the default) +# and SOURCE_BROWSER tag is set to YES, then the hyperlinks from +# functions in REFERENCES_RELATION and REFERENCED_BY_RELATION lists will +# link to the source code. +# Otherwise they will link to the documentation. + +REFERENCES_LINK_SOURCE = YES + +# If the USE_HTAGS tag is set to YES then the references to source code +# will point to the HTML generated by the htags(1) tool instead of doxygen +# built-in source browser. The htags tool is part of GNU's global source +# tagging system (see http://www.gnu.org/software/global/global.html). You +# will need version 4.8.6 or higher. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set to YES (the default) then Doxygen +# will generate a verbatim copy of the header file for each class for +# which an include is specified. Set to NO to disable this. + +VERBATIM_HEADERS = YES + +#--------------------------------------------------------------------------- +# configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index +# of all compounds will be generated. Enable this if the project +# contains a lot of classes, structs, unions or interfaces. + +ALPHABETICAL_INDEX = YES + +# If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then +# the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns +# in which this list will be split (can be a number in the range [1..20]) + +COLS_IN_ALPHA_INDEX = 3 + +# In case all classes in a project start with a common prefix, all +# classes will be put under the same header in the alphabetical index. +# The IGNORE_PREFIX tag can be used to specify one or more prefixes that +# should be ignored while generating the index headers. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES (the default) Doxygen will +# generate HTML output. + +GENERATE_HTML = YES + +# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `html' will be used as the default path. + +HTML_OUTPUT = html + +# The HTML_FILE_EXTENSION tag can be used to specify the file extension for +# each generated HTML page (for example: .htm,.php,.asp). If it is left blank +# doxygen will generate files with .html extension. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a personal HTML header for +# each generated HTML page. If it is left blank doxygen will generate a +# standard header. Note that when using a custom header you are responsible +# for the proper inclusion of any scripts and style sheets that doxygen +# needs, which is dependent on the configuration options used. +# It is advised to generate a default header using "doxygen -w html +# header.html footer.html stylesheet.css YourConfigFile" and then modify +# that header. Note that the header is subject to change so you typically +# have to redo this when upgrading to a newer version of doxygen or when +# changing the value of configuration settings such as GENERATE_TREEVIEW! + +HTML_HEADER = "@CMAKE_SOURCE_DIR@/doc/header.html" + +# The HTML_FOOTER tag can be used to specify a personal HTML footer for +# each generated HTML page. If it is left blank doxygen will generate a +# standard footer. + +HTML_FOOTER = "@CMAKE_SOURCE_DIR@/doc/footer.html" + +# The HTML_STYLESHEET tag can be used to specify a user-defined cascading +# style sheet that is used by each HTML page. It can be used to +# fine-tune the look of the HTML output. If left blank doxygen will +# generate a default style sheet. Note that it is recommended to use +# HTML_EXTRA_STYLESHEET instead of this one, as it is more robust and this +# tag will in the future become obsolete. + +HTML_STYLESHEET = "@CMAKE_SOURCE_DIR@/doc/doxygen.css" + +# The HTML_EXTRA_STYLESHEET tag can be used to specify an additional +# user-defined cascading style sheet that is included after the standard +# style sheets created by doxygen. Using this option one can overrule +# certain style aspects. This is preferred over using HTML_STYLESHEET +# since it does not replace the standard style sheet and is therefor more +# robust against future updates. Doxygen will copy the style sheet file to +# the output directory. + +HTML_EXTRA_STYLESHEET = + +# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or +# other source files which should be copied to the HTML output directory. Note +# that these files will be copied to the base HTML output directory. Use the +# $relpath$ marker in the HTML_HEADER and/or HTML_FOOTER files to load these +# files. In the HTML_STYLESHEET file, use the file name only. Also note that +# the files will be copied as-is; there are no commands or markers available. + +HTML_EXTRA_FILES = + +# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. +# Doxygen will adjust the colors in the style sheet and background images +# according to this color. Hue is specified as an angle on a colorwheel, +# see http://en.wikipedia.org/wiki/Hue for more information. +# For instance the value 0 represents red, 60 is yellow, 120 is green, +# 180 is cyan, 240 is blue, 300 purple, and 360 is red again. +# The allowed range is 0 to 359. + +HTML_COLORSTYLE_HUE = 220 + +# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of +# the colors in the HTML output. For a value of 0 the output will use +# grayscales only. A value of 255 will produce the most vivid colors. + +HTML_COLORSTYLE_SAT = 100 + +# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to +# the luminance component of the colors in the HTML output. Values below +# 100 gradually make the output lighter, whereas values above 100 make +# the output darker. The value divided by 100 is the actual gamma applied, +# so 80 represents a gamma of 0.8, The value 220 represents a gamma of 2.2, +# and 100 does not change the gamma. + +HTML_COLORSTYLE_GAMMA = 80 + +# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML +# page will contain the date and time when the page was generated. Setting +# this to NO can help when comparing the output of multiple runs. + +HTML_TIMESTAMP = YES + +# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML +# documentation will contain sections that can be hidden and shown after the +# page has loaded. + +HTML_DYNAMIC_SECTIONS = NO + +# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of +# entries shown in the various tree structured indices initially; the user +# can expand and collapse entries dynamically later on. Doxygen will expand +# the tree to such a level that at most the specified number of entries are +# visible (unless a fully collapsed tree already exceeds this amount). +# So setting the number of entries 1 will produce a full collapsed tree by +# default. 0 is a special value representing an infinite number of entries +# and will result in a full expanded tree by default. + +HTML_INDEX_NUM_ENTRIES = 100 + +# If the GENERATE_DOCSET tag is set to YES, additional index files +# will be generated that can be used as input for Apple's Xcode 3 +# integrated development environment, introduced with OSX 10.5 (Leopard). +# To create a documentation set, doxygen will generate a Makefile in the +# HTML output directory. Running make will produce the docset in that +# directory and running "make install" will install the docset in +# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find +# it at startup. +# See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html +# for more information. + +GENERATE_DOCSET = NO + +# When GENERATE_DOCSET tag is set to YES, this tag determines the name of the +# feed. A documentation feed provides an umbrella under which multiple +# documentation sets from a single provider (such as a company or product suite) +# can be grouped. + +DOCSET_FEEDNAME = "Gazebo API Documentation" + +# When GENERATE_DOCSET tag is set to YES, this tag specifies a string that +# should uniquely identify the documentation set bundle. This should be a +# reverse domain-name style string, e.g. com.mycompany.MyDocSet. Doxygen +# will append .docset to the name. + +DOCSET_BUNDLE_ID = org.doxygen.Project + +# When GENERATE_PUBLISHER_ID tag specifies a string that should uniquely +# identify the documentation publisher. This should be a reverse domain-name +# style string, e.g. com.mycompany.MyDocSet.documentation. + +DOCSET_PUBLISHER_ID = org.doxygen.Publisher + +# The GENERATE_PUBLISHER_NAME tag identifies the documentation publisher. + +DOCSET_PUBLISHER_NAME = Publisher + +# If the GENERATE_HTMLHELP tag is set to YES, additional index files +# will be generated that can be used as input for tools like the +# Microsoft HTML help workshop to generate a compiled HTML help file (.chm) +# of the generated HTML documentation. + +GENERATE_HTMLHELP = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_FILE tag can +# be used to specify the file name of the resulting .chm file. You +# can add a path in front of the file if the result should not be +# written to the html output directory. + +CHM_FILE = + +# If the GENERATE_HTMLHELP tag is set to YES, the HHC_LOCATION tag can +# be used to specify the location (absolute path including file name) of +# the HTML help compiler (hhc.exe). If non-empty doxygen will try to run +# the HTML help compiler on the generated index.hhp. + +HHC_LOCATION = + +# If the GENERATE_HTMLHELP tag is set to YES, the GENERATE_CHI flag +# controls if a separate .chi index file is generated (YES) or that +# it should be included in the master .chm file (NO). + +GENERATE_CHI = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_INDEX_ENCODING +# is used to encode HtmlHelp index (hhk), content (hhc) and project file +# content. + +CHM_INDEX_ENCODING = + +# If the GENERATE_HTMLHELP tag is set to YES, the BINARY_TOC flag +# controls whether a binary table of contents is generated (YES) or a +# normal table of contents (NO) in the .chm file. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members +# to the contents of the HTML help documentation and to the tree view. + +TOC_EXPAND = NO + +# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and +# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated +# that can be used as input for Qt's qhelpgenerator to generate a +# Qt Compressed Help (.qch) of the generated HTML documentation. + +GENERATE_QHP = NO + +# If the QHG_LOCATION tag is specified, the QCH_FILE tag can +# be used to specify the file name of the resulting .qch file. +# The path specified is relative to the HTML output folder. + +QCH_FILE = + +# The QHP_NAMESPACE tag specifies the namespace to use when generating +# Qt Help Project output. For more information please see +# http://doc.trolltech.com/qthelpproject.html#namespace + +QHP_NAMESPACE = org.doxygen.Project + +# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating +# Qt Help Project output. For more information please see +# http://doc.trolltech.com/qthelpproject.html#virtual-folders + +QHP_VIRTUAL_FOLDER = doc + +# If QHP_CUST_FILTER_NAME is set, it specifies the name of a custom filter to +# add. For more information please see +# http://doc.trolltech.com/qthelpproject.html#custom-filters + +QHP_CUST_FILTER_NAME = + +# The QHP_CUST_FILT_ATTRS tag specifies the list of the attributes of the +# custom filter to add. For more information please see +# +# Qt Help Project / Custom Filters. + +QHP_CUST_FILTER_ATTRS = + +# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this +# project's +# filter section matches. +# +# Qt Help Project / Filter Attributes. + +QHP_SECT_FILTER_ATTRS = + +# If the GENERATE_QHP tag is set to YES, the QHG_LOCATION tag can +# be used to specify the location of Qt's qhelpgenerator. +# If non-empty doxygen will try to run qhelpgenerator on the generated +# .qhp file. + +QHG_LOCATION = + +# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files +# will be generated, which together with the HTML files, form an Eclipse help +# plugin. To install this plugin and make it available under the help contents +# menu in Eclipse, the contents of the directory containing the HTML and XML +# files needs to be copied into the plugins directory of eclipse. The name of +# the directory within the plugins directory should be the same as +# the ECLIPSE_DOC_ID value. After copying Eclipse needs to be restarted before +# the help appears. + +GENERATE_ECLIPSEHELP = NO + +# A unique identifier for the eclipse help plugin. When installing the plugin +# the directory name containing the HTML and XML files should also have +# this name. + +ECLIPSE_DOC_ID = org.doxygen.Project + +# The DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) +# at top of each HTML page. The value NO (the default) enables the index and +# the value YES disables it. Since the tabs have the same information as the +# navigation tree you can set this option to NO if you already set +# GENERATE_TREEVIEW to YES. + +DISABLE_INDEX = YES + +# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index +# structure should be generated to display hierarchical information. +# If the tag value is set to YES, a side panel will be generated +# containing a tree-like index structure (just like the one that +# is generated for HTML Help). For this to work a browser that supports +# JavaScript, DHTML, CSS and frames is required (i.e. any modern browser). +# Windows users are probably better off using the HTML help feature. +# Since the tree basically has the same information as the tab index you +# could consider to set DISABLE_INDEX to NO when enabling this option. + +GENERATE_TREEVIEW = NO + +# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values +# (range [0,1..20]) that doxygen will group on one line in the generated HTML +# documentation. Note that a value of 0 will completely suppress the enum +# values from appearing in the overview section. + +ENUM_VALUES_PER_LINE = 4 + +# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be +# used to set the initial width (in pixels) of the frame in which the tree +# is shown. + +TREEVIEW_WIDTH = 250 + +# When the EXT_LINKS_IN_WINDOW option is set to YES doxygen will open +# links to external symbols imported via tag files in a separate window. + +EXT_LINKS_IN_WINDOW = NO + +# Use this tag to change the font size of Latex formulas included +# as images in the HTML documentation. The default is 10. Note that +# when you change the font size after a successful doxygen run you need +# to manually remove any form_*.png images from the HTML output directory +# to force them to be regenerated. + +FORMULA_FONTSIZE = 10 + +# Use the FORMULA_TRANPARENT tag to determine whether or not the images +# generated for formulas are transparent PNGs. Transparent PNGs are +# not supported properly for IE 6.0, but are supported on all modern browsers. +# Note that when changing this option you need to delete any form_*.png files +# in the HTML output before the changes have effect. + +FORMULA_TRANSPARENT = YES + +# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax +# (see http://www.mathjax.org) which uses client side Javascript for the +# rendering instead of using prerendered bitmaps. Use this if you do not +# have LaTeX installed or if you want to formulas look prettier in the HTML +# output. When enabled you may also need to install MathJax separately and +# configure the path to it using the MATHJAX_RELPATH option. + +USE_MATHJAX = NO + +# When MathJax is enabled you need to specify the location relative to the +# HTML output directory using the MATHJAX_RELPATH option. The destination +# directory should contain the MathJax.js script. For instance, if the mathjax +# directory is located at the same level as the HTML output directory, then +# MATHJAX_RELPATH should be ../mathjax. The default value points to +# the MathJax Content Delivery Network so you can quickly see the result without +# installing MathJax. +# However, it is strongly recommended to install a local +# copy of MathJax from http://www.mathjax.org before deployment. + +MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest + +# The MATHJAX_EXTENSIONS tag can be used to specify one or MathJax extension +# names that should be enabled during MathJax rendering. + +MATHJAX_EXTENSIONS = + +# When the SEARCHENGINE tag is enabled doxygen will generate a search box +# for the HTML output. The underlying search engine uses javascript +# and DHTML and should work on any modern browser. Note that when using +# HTML help (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets +# (GENERATE_DOCSET) there is already a search function so this one should +# typically be disabled. For large projects the javascript based search engine +# can be slow, then enabling SERVER_BASED_SEARCH may provide a better solution. + +SEARCHENGINE = YES + +# When the SERVER_BASED_SEARCH tag is enabled the search engine will be +# implemented using a PHP enabled web server instead of at the web client +# using Javascript. Doxygen will generate the search PHP script and index +# file to put on the web server. The advantage of the server +# based approach is that it scales better to large projects and allows +# full text search. The disadvantages are that it is more difficult to setup +# and does not have live searching capabilities. + +SERVER_BASED_SEARCH = NO + +#--------------------------------------------------------------------------- +# configuration options related to the LaTeX output +#--------------------------------------------------------------------------- + +# If the GENERATE_LATEX tag is set to YES (the default) Doxygen will +# generate Latex output. + +GENERATE_LATEX = YES + +# The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `latex' will be used as the default path. + +LATEX_OUTPUT = latex + +# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be +# invoked. If left blank `latex' will be used as the default command name. +# Note that when enabling USE_PDFLATEX this option is only used for +# generating bitmaps for formulas in the HTML output, but not in the +# Makefile that is written to the output directory. + +LATEX_CMD_NAME = latex + +# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to +# generate index for LaTeX. If left blank `makeindex' will be used as the +# default command name. + +MAKEINDEX_CMD_NAME = makeindex + +# If the COMPACT_LATEX tag is set to YES Doxygen generates more compact +# LaTeX documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_LATEX = NO + +# The PAPER_TYPE tag can be used to set the paper type that is used +# by the printer. Possible values are: a4, letter, legal and +# executive. If left blank a4wide will be used. + +PAPER_TYPE = letter + +# The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX +# packages that should be included in the LaTeX output. + +EXTRA_PACKAGES = + +# The LATEX_HEADER tag can be used to specify a personal LaTeX header for +# the generated latex document. The header should contain everything until +# the first chapter. If it is left blank doxygen will generate a +# standard header. Notice: only use this tag if you know what you are doing! + +LATEX_HEADER = + +# The LATEX_FOOTER tag can be used to specify a personal LaTeX footer for +# the generated latex document. The footer should contain everything after +# the last chapter. If it is left blank doxygen will generate a +# standard footer. Notice: only use this tag if you know what you are doing! + +LATEX_FOOTER = + +# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated +# is prepared for conversion to pdf (using ps2pdf). The pdf file will +# contain links (just like the HTML output) instead of page references +# This makes the output suitable for online browsing using a pdf viewer. + +PDF_HYPERLINKS = NO + +# If the USE_PDFLATEX tag is set to YES, pdflatex will be used instead of +# plain latex in the generated Makefile. Set this option to YES to get a +# higher quality PDF documentation. + +USE_PDFLATEX = YES + +# If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\batchmode. +# command to the generated LaTeX files. This will instruct LaTeX to keep +# running if errors occur, instead of asking the user for help. +# This option is also used when generating formulas in HTML. + +LATEX_BATCHMODE = NO + +# If LATEX_HIDE_INDICES is set to YES then doxygen will not +# include the index chapters (such as File Index, Compound Index, etc.) +# in the output. + +LATEX_HIDE_INDICES = NO + +# If LATEX_SOURCE_CODE is set to YES then doxygen will include +# source code with syntax highlighting in the LaTeX output. +# Note that which sources are shown also depends on other settings +# such as SOURCE_BROWSER. + +LATEX_SOURCE_CODE = NO + +# The LATEX_BIB_STYLE tag can be used to specify the style to use for the +# bibliography, e.g. plainnat, or ieeetr. The default style is "plain". See +# http://en.wikipedia.org/wiki/BibTeX for more info. + +LATEX_BIB_STYLE = plain + +#--------------------------------------------------------------------------- +# configuration options related to the RTF output +#--------------------------------------------------------------------------- + +# If the GENERATE_RTF tag is set to YES Doxygen will generate RTF output +# The RTF output is optimized for Word 97 and may not look very pretty with +# other RTF readers or editors. + +GENERATE_RTF = NO + +# The RTF_OUTPUT tag is used to specify where the RTF docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `rtf' will be used as the default path. + +RTF_OUTPUT = rtf + +# If the COMPACT_RTF tag is set to YES Doxygen generates more compact +# RTF documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_RTF = NO + +# If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated +# will contain hyperlink fields. The RTF file will +# contain links (just like the HTML output) instead of page references. +# This makes the output suitable for online browsing using WORD or other +# programs which support those fields. +# Note: wordpad (write) and others do not support links. + +RTF_HYPERLINKS = NO + +# Load style sheet definitions from file. Syntax is similar to doxygen's +# config file, i.e. a series of assignments. You only have to provide +# replacements, missing definitions are set to their default value. + +RTF_STYLESHEET_FILE = + +# Set optional variables used in the generation of an rtf document. +# Syntax is similar to doxygen's config file. + +RTF_EXTENSIONS_FILE = + +#--------------------------------------------------------------------------- +# configuration options related to the man page output +#--------------------------------------------------------------------------- + +# If the GENERATE_MAN tag is set to YES (the default) Doxygen will +# generate man pages + +GENERATE_MAN = NO + +# The MAN_OUTPUT tag is used to specify where the man pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `man' will be used as the default path. + +MAN_OUTPUT = man + +# The MAN_EXTENSION tag determines the extension that is added to +# the generated man pages (default is the subroutine's section .3) + +MAN_EXTENSION = .3 + +# If the MAN_LINKS tag is set to YES and Doxygen generates man output, +# then it will generate one additional man file for each entity +# documented in the real man page(s). These additional files +# only source the real man page, but without them the man command +# would be unable to find the correct page. The default is NO. + +MAN_LINKS = NO + +#--------------------------------------------------------------------------- +# configuration options related to the XML output +#--------------------------------------------------------------------------- + +# If the GENERATE_XML tag is set to YES Doxygen will +# generate an XML file that captures the structure of +# the code including all documentation. + +GENERATE_XML = NO + +# The XML_OUTPUT tag is used to specify where the XML pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `xml' will be used as the default path. + +XML_OUTPUT = xml + +# The XML_SCHEMA tag can be used to specify an XML schema, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_SCHEMA = + +# The XML_DTD tag can be used to specify an XML DTD, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_DTD = + +# If the XML_PROGRAMLISTING tag is set to YES Doxygen will +# dump the program listings (including syntax highlighting +# and cross-referencing information) to the XML output. Note that +# enabling this will significantly increase the size of the XML output. + +XML_PROGRAMLISTING = YES + +#--------------------------------------------------------------------------- +# configuration options for the AutoGen Definitions output +#--------------------------------------------------------------------------- + +# If the GENERATE_AUTOGEN_DEF tag is set to YES Doxygen will +# generate an AutoGen Definitions (see autogen.sf.net) file +# that captures the structure of the code including all +# documentation. Note that this feature is still experimental +# and incomplete at the moment. + +GENERATE_AUTOGEN_DEF = NO + +#--------------------------------------------------------------------------- +# configuration options related to the Perl module output +#--------------------------------------------------------------------------- + +# If the GENERATE_PERLMOD tag is set to YES Doxygen will +# generate a Perl module file that captures the structure of +# the code including all documentation. Note that this +# feature is still experimental and incomplete at the +# moment. + +GENERATE_PERLMOD = NO + +# If the PERLMOD_LATEX tag is set to YES Doxygen will generate +# the necessary Makefile rules, Perl scripts and LaTeX code to be able +# to generate PDF and DVI output from the Perl module output. + +PERLMOD_LATEX = NO + +# If the PERLMOD_PRETTY tag is set to YES the Perl module output will be +# nicely formatted so it can be parsed by a human reader. +# This is useful +# if you want to understand what is going on. +# On the other hand, if this +# tag is set to NO the size of the Perl module output will be much smaller +# and Perl will parse it just the same. + +PERLMOD_PRETTY = YES + +# The names of the make variables in the generated doxyrules.make file +# are prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX. +# This is useful so different doxyrules.make files included by the same +# Makefile don't overwrite each other's variables. + +PERLMOD_MAKEVAR_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the preprocessor +#--------------------------------------------------------------------------- + +# If the ENABLE_PREPROCESSING tag is set to YES (the default) Doxygen will +# evaluate all C-preprocessor directives found in the sources and include +# files. + +ENABLE_PREPROCESSING = YES + +# If the MACRO_EXPANSION tag is set to YES Doxygen will expand all macro +# names in the source code. If set to NO (the default) only conditional +# compilation will be performed. Macro expansion can be done in a controlled +# way by setting EXPAND_ONLY_PREDEF to YES. + +MACRO_EXPANSION = YES + +# If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES +# then the macro expansion is limited to the macros specified with the +# PREDEFINED and EXPAND_AS_DEFINED tags. + +EXPAND_ONLY_PREDEF = NO + +# If the SEARCH_INCLUDES tag is set to YES (the default) the includes files +# pointed to by INCLUDE_PATH will be searched when a #include is found. + +SEARCH_INCLUDES = YES + +# The INCLUDE_PATH tag can be used to specify one or more directories that +# contain include files that are not input files but should be processed by +# the preprocessor. + +INCLUDE_PATH = . + +# You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard +# patterns (like *.h and *.hpp) to filter out the header-files in the +# directories. If left blank, the patterns specified with FILE_PATTERNS will +# be used. + +INCLUDE_FILE_PATTERNS = + +# The PREDEFINED tag can be used to specify one or more macro names that +# are defined before the preprocessor is started (similar to the -D option of +# gcc). The argument of the tag is a list of macros of the form: name +# or name=definition (no spaces). If the definition and the = are +# omitted =1 is assumed. To prevent a macro definition from being +# undefined via #undef or recursively expanded use the := operator +# instead of the = operator. + +PREDEFINED = + +# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then +# this tag can be used to specify a list of macro names that should be expanded. +# The macro definition that is found in the sources will be used. +# Use the PREDEFINED tag if you want to use a different macro definition that +# overrules the definition found in the source code. + +EXPAND_AS_DEFINED = + +# If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then +# doxygen's preprocessor will remove all references to function-like macros +# that are alone on a line, have an all uppercase name, and do not end with a +# semicolon, because these will confuse the parser if not removed. + +SKIP_FUNCTION_MACROS = NO + +#--------------------------------------------------------------------------- +# Configuration::additions related to external references +#--------------------------------------------------------------------------- + +# The TAGFILES option can be used to specify one or more tagfiles. For each +# tag file the location of the external documentation should be added. The +# format of a tag file without this location is as follows: +# +# TAGFILES = file1 file2 ... +# Adding location for the tag files is done as follows: +# +# TAGFILES = file1=loc1 "file2 = loc2" ... +# where "loc1" and "loc2" can be relative or absolute paths +# or URLs. Note that each tag file must have a unique name (where the name does +# NOT include the path). If a tag file is not located in the directory in which +# doxygen is run, you must also specify the path to the tagfile here. + +TAGFILES = + +# When a file name is specified after GENERATE_TAGFILE, doxygen will create +# a tag file that is based on the input files it reads. + +GENERATE_TAGFILE = + +# If the ALLEXTERNALS tag is set to YES all external classes will be listed +# in the class index. If set to NO only the inherited external classes +# will be listed. + +ALLEXTERNALS = NO + +# If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed +# in the modules index. If set to NO, only the current project's groups will +# be listed. + +EXTERNAL_GROUPS = NO + +# The PERL_PATH should be the absolute path and name of the perl script +# interpreter (i.e. the result of `which perl'). + +PERL_PATH = /usr/bin/perl + +#--------------------------------------------------------------------------- +# Configuration options related to the dot tool +#--------------------------------------------------------------------------- + +# If the CLASS_DIAGRAMS tag is set to YES (the default) Doxygen will +# generate a inheritance diagram (in HTML, RTF and LaTeX) for classes with base +# or super classes. Setting the tag to NO turns the diagrams off. Note that +# this option also works with HAVE_DOT disabled, but it is recommended to +# install and use dot, since it yields more powerful graphs. + +CLASS_DIAGRAMS = YES + +# You can define message sequence charts within doxygen comments using the \msc +# command. Doxygen will then run the mscgen tool (see +# http://www.mcternan.me.uk/mscgen/) to produce the chart and insert it in the +# documentation. The MSCGEN_PATH tag allows you to specify the directory where +# the mscgen tool resides. If left empty the tool is assumed to be found in the +# default search path. + +MSCGEN_PATH = + +# If set to YES, the inheritance and collaboration graphs will hide +# inheritance and usage relations if the target is undocumented +# or is not a class. + +HIDE_UNDOC_RELATIONS = YES + +# If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is +# available from the path. This tool is part of Graphviz, a graph visualization +# toolkit from AT&T and Lucent Bell Labs. The other options in this section +# have no effect if this option is set to NO (the default) + +HAVE_DOT = YES + +# The DOT_NUM_THREADS specifies the number of dot invocations doxygen is +# allowed to run in parallel. When set to 0 (the default) doxygen will +# base this on the number of processors available in the system. You can set it +# explicitly to a value larger than 0 to get control over the balance +# between CPU load and processing speed. + +DOT_NUM_THREADS = 0 + +# By default doxygen will use the Helvetica font for all dot files that +# doxygen generates. When you want a differently looking font you can specify +# the font name using DOT_FONTNAME. You need to make sure dot is able to find +# the font, which can be done by putting it in a standard location or by setting +# the DOTFONTPATH environment variable or by setting DOT_FONTPATH to the +# directory containing the font. + +DOT_FONTNAME = FreeSans.ttf + +# The DOT_FONTSIZE tag can be used to set the size of the font of dot graphs. +# The default size is 10pt. + +DOT_FONTSIZE = 10 + +# By default doxygen will tell dot to use the Helvetica font. +# If you specify a different font using DOT_FONTNAME you can use DOT_FONTPATH to +# set the path where dot can find it. + +DOT_FONTPATH = + +# If the CLASS_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect inheritance relations. Setting this tag to YES will force the +# CLASS_DIAGRAMS tag to NO. + +CLASS_GRAPH = YES + +# If the COLLABORATION_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect implementation dependencies (inheritance, containment, and +# class references variables) of the class with other documented classes. + +COLLABORATION_GRAPH = NO + +# If the GROUP_GRAPHS and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for groups, showing the direct groups dependencies + +GROUP_GRAPHS = YES + +# If the UML_LOOK tag is set to YES doxygen will generate inheritance and +# collaboration diagrams in a style similar to the OMG's Unified Modeling +# Language. + +UML_LOOK = NO + +# If the UML_LOOK tag is enabled, the fields and methods are shown inside +# the class node. If there are many fields or methods and many nodes the +# graph may become too big to be useful. The UML_LIMIT_NUM_FIELDS +# threshold limits the number of items for each type to make the size more +# managable. Set this to 0 for no limit. Note that the threshold may be +# exceeded by 50% before the limit is enforced. + +UML_LIMIT_NUM_FIELDS = 10 + +# If set to YES, the inheritance and collaboration graphs will show the +# relations between templates and their instances. + +TEMPLATE_RELATIONS = NO + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDE_GRAPH, and HAVE_DOT +# tags are set to YES then doxygen will generate a graph for each documented +# file showing the direct and indirect include dependencies of the file with +# other documented files. + +INCLUDE_GRAPH = YES + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDED_BY_GRAPH, and +# HAVE_DOT tags are set to YES then doxygen will generate a graph for each +# documented header file showing the documented files that directly or +# indirectly include this file. + +INCLUDED_BY_GRAPH = YES + +# If the CALL_GRAPH and HAVE_DOT options are set to YES then +# doxygen will generate a call dependency graph for every global function +# or class method. Note that enabling this option will significantly increase +# the time of a run. So in most cases it will be better to enable call graphs +# for selected functions only using the \callgraph command. + +CALL_GRAPH = NO + +# If the CALLER_GRAPH and HAVE_DOT tags are set to YES then +# doxygen will generate a caller dependency graph for every global function +# or class method. Note that enabling this option will significantly increase +# the time of a run. So in most cases it will be better to enable caller +# graphs for selected functions only using the \callergraph command. + +CALLER_GRAPH = NO + +# If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen +# will generate a graphical hierarchy of all classes instead of a textual one. + +GRAPHICAL_HIERARCHY = YES + +# If the DIRECTORY_GRAPH and HAVE_DOT tags are set to YES +# then doxygen will show the dependencies a directory has on other directories +# in a graphical way. The dependency relations are determined by the #include +# relations between the files in the directories. + +DIRECTORY_GRAPH = YES + +# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images +# generated by dot. Possible values are svg, png, jpg, or gif. +# If left blank png will be used. If you choose svg you need to set +# HTML_FILE_EXTENSION to xhtml in order to make the SVG files +# visible in IE 9+ (other browsers do not have this requirement). + +DOT_IMAGE_FORMAT = png + +# If DOT_IMAGE_FORMAT is set to svg, then this option can be set to YES to +# enable generation of interactive SVG images that allow zooming and panning. +# Note that this requires a modern browser other than Internet Explorer. +# Tested and working are Firefox, Chrome, Safari, and Opera. For IE 9+ you +# need to set HTML_FILE_EXTENSION to xhtml in order to make the SVG files +# visible. Older versions of IE do not have SVG support. + +INTERACTIVE_SVG = NO + +# The tag DOT_PATH can be used to specify the path where the dot tool can be +# found. If left blank, it is assumed the dot tool can be found in the path. + +DOT_PATH = + +# The DOTFILE_DIRS tag can be used to specify one or more directories that +# contain dot files that are included in the documentation (see the +# \dotfile command). + +DOTFILE_DIRS = + +# The MSCFILE_DIRS tag can be used to specify one or more directories that +# contain msc files that are included in the documentation (see the +# \mscfile command). + +MSCFILE_DIRS = + +# The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of +# nodes that will be shown in the graph. If the number of nodes in a graph +# becomes larger than this value, doxygen will truncate the graph, which is +# visualized by representing a node as a red box. Note that doxygen if the +# number of direct children of the root node in a graph is already larger than +# DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note +# that the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH. + +DOT_GRAPH_MAX_NODES = 50 + +# The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the +# graphs generated by dot. A depth value of 3 means that only nodes reachable +# from the root by following a path via at most 3 edges will be shown. Nodes +# that lay further from the root node will be omitted. Note that setting this +# option to 1 or 2 may greatly reduce the computation time needed for large +# code bases. Also note that the size of a graph can be further restricted by +# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction. + +MAX_DOT_GRAPH_DEPTH = 0 + +# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent +# background. This is disabled by default, because dot on Windows does not +# seem to support this out of the box. Warning: Depending on the platform used, +# enabling this option may lead to badly anti-aliased labels on the edges of +# a graph (i.e. they become hard to read). + +DOT_TRANSPARENT = NO + +# Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output +# files in one run (i.e. multiple -o and -T options on the command line). This +# makes dot run faster, but since only newer versions of dot (>1.8.10) +# support this, this feature is disabled by default. + +DOT_MULTI_TARGETS = NO + +# If the GENERATE_LEGEND tag is set to YES (the default) Doxygen will +# generate a legend page explaining the meaning of the various boxes and +# arrows in the dot generated graphs. + +GENERATE_LEGEND = YES + +# If the DOT_CLEANUP tag is set to YES (the default) Doxygen will +# remove the intermediate dot files that are used to generate +# the various graphs. + +DOT_CLEANUP = YES diff --git a/sdformat/doc/sdf_logo.png b/sdformat/doc/sdf_logo.png new file mode 100644 index 0000000..09d36a2 Binary files /dev/null and b/sdformat/doc/sdf_logo.png differ diff --git a/sdformat/doc/sdf_logo.svg b/sdformat/doc/sdf_logo.svg new file mode 100644 index 0000000..613ee18 --- /dev/null +++ b/sdformat/doc/sdf_logo.svg @@ -0,0 +1,68 @@ + + + + + + + + + + image/svg+xml + + + + + + + + + diff --git a/sdformat/doc/search.js b/sdformat/doc/search.js new file mode 100644 index 0000000..b01927e --- /dev/null +++ b/sdformat/doc/search.js @@ -0,0 +1,817 @@ +// Search script generated by doxygen +// Copyright (C) 2009 by Dimitri van Heesch. + +// The code in this file is loosly based on main.js, part of Natural Docs, +// which is Copyright (C) 2003-2008 Greg Valure +// Natural Docs is licensed under the GPL. + +var indexSectionsWithContent = +{ + 0: "0000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000111111111111111111111111110001000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000", + 1: "0000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000111111111111111111111110000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000", + 2: "0000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000100000000000101000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000", + 3: "0000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000011000000000101101110000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000", + 4: "0000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000111111111111111111111110000001000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000", + 5: "0000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000111111101111111101110111110000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000", + 6: "0000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000001000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000", + 7: "0000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000100010010000000101000100000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000", + 8: "0000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000111010010101100101111110000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000", + 9: "0000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000001000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000", + 10: "0000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000011010100000101001110000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000", + 11: "0000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000100000000000010000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000" +}; + +var indexSectionNames = +{ + 0: "all", + 1: "classes", + 2: "namespaces", + 3: "files", + 4: "functions", + 5: "variables", + 6: "typedefs", + 7: "enums", + 8: "enumvalues", + 9: "related", + 10: "groups", + 11: "pages" +}; + +function convertToId(search) +{ + var result = ''; + for (i=0;i do a search + { + this.Search(); + } + } + + this.OnSearchSelectKey = function(evt) + { + var e = (evt) ? evt : window.event; // for IE + if (e.keyCode==40 && this.searchIndex0) // Up + { + this.searchIndex--; + this.OnSelectItem(this.searchIndex); + } + else if (e.keyCode==13 || e.keyCode==27) + { + this.OnSelectItem(this.searchIndex); + this.CloseSelectionWindow(); + this.DOMSearchField().focus(); + } + return false; + } + + // --------- Actions + + // Closes the results window. + this.CloseResultsWindow = function() + { + this.DOMPopupSearchResultsWindow().style.display = 'none'; + this.DOMSearchClose().style.display = 'none'; + this.Activate(false); + } + + this.CloseSelectionWindow = function() + { + this.DOMSearchSelectWindow().style.display = 'none'; + } + + // Performs a search. + this.Search = function() + { + this.keyTimeout = 0; + + // strip leading whitespace + var searchValue = this.DOMSearchField().value.replace(/^ +/, ""); + + var code = searchValue.toLowerCase().charCodeAt(0); + var hexCode; + if (code<16) + { + hexCode="0"+code.toString(16); + } + else + { + hexCode=code.toString(16); + } + + var resultsPage; + var resultsPageWithSearch; + var hasResultsPage; + + if (indexSectionsWithContent[this.searchIndex].charAt(code) == '1') + { + resultsPage = this.resultsPath + '/' + indexSectionNames[this.searchIndex] + '_' + hexCode + '.html'; + resultsPageWithSearch = resultsPage+'?'+escape(searchValue); + hasResultsPage = true; + } + else // nothing available for this search term + { + resultsPage = this.resultsPath + '/nomatches.html'; + resultsPageWithSearch = resultsPage; + hasResultsPage = false; + } + + window.frames.MSearchResults.location = resultsPageWithSearch; + var domPopupSearchResultsWindow = this.DOMPopupSearchResultsWindow(); + + if (domPopupSearchResultsWindow.style.display!='block') + { + var domSearchBox = this.DOMSearchBox(); + this.DOMSearchClose().style.display = 'inline'; + if (this.insideFrame) + { + var domPopupSearchResults = this.DOMPopupSearchResults(); + domPopupSearchResultsWindow.style.position = 'relative'; + domPopupSearchResultsWindow.style.display = 'block'; + var width = document.body.clientWidth - 8; // the -8 is for IE :-( + domPopupSearchResultsWindow.style.width = width + 'px'; + domPopupSearchResults.style.width = width + 'px'; + } + else + { + var domPopupSearchResults = this.DOMPopupSearchResults(); + var left = getXPos(domSearchBox) + 150; // domSearchBox.offsetWidth; + var top = getYPos(domSearchBox) + 20; // domSearchBox.offsetHeight + 1; + domPopupSearchResultsWindow.style.display = 'block'; + left -= domPopupSearchResults.offsetWidth; + domPopupSearchResultsWindow.style.top = top + 'px'; + domPopupSearchResultsWindow.style.left = left + 'px'; + } + } + + this.lastSearchValue = searchValue; + this.lastResultsPage = resultsPage; + } + + // -------- Activation Functions + + // Activates or deactivates the search panel, resetting things to + // their default values if necessary. + this.Activate = function(isActive) + { + if (isActive || // open it + this.DOMPopupSearchResultsWindow().style.display == 'block' + ) + { + this.DOMSearchBox().className = 'MSearchBoxActive'; + + var searchField = this.DOMSearchField(); + + if (searchField.value == this.searchLabel) // clear "Search" term upon entry + { + searchField.value = ''; + this.searchActive = true; + } + } + else if (!isActive) // directly remove the panel + { + this.DOMSearchBox().className = 'MSearchBoxInactive'; + this.DOMSearchField().value = this.searchLabel; + this.searchActive = false; + this.lastSearchValue = '' + this.lastResultsPage = ''; + } + } +} + +// ----------------------------------------------------------------------- + +// The class that handles everything on the search results page. +function SearchResults(name) +{ + // The number of matches from the last run of . + this.lastMatchCount = 0; + this.lastKey = 0; + this.repeatOn = false; + + // Toggles the visibility of the passed element ID. + this.FindChildElement = function(id) + { + var parentElement = document.getElementById(id); + var element = parentElement.firstChild; + + while (element && element!=parentElement) + { + if (element.nodeName == 'DIV' && element.className == 'SRChildren') + { + return element; + } + + if (element.nodeName == 'DIV' && element.hasChildNodes()) + { + element = element.firstChild; + } + else if (element.nextSibling) + { + element = element.nextSibling; + } + else + { + do + { + element = element.parentNode; + } + while (element && element!=parentElement && !element.nextSibling); + + if (element && element!=parentElement) + { + element = element.nextSibling; + } + } + } + } + + this.Toggle = function(id) + { + var element = this.FindChildElement(id); + if (element) + { + if (element.style.display == 'block') + { + element.style.display = 'none'; + } + else + { + element.style.display = 'block'; + } + } + } + + // Searches for the passed string. If there is no parameter, + // it takes it from the URL query. + // + // Always returns true, since other documents may try to call it + // and that may or may not be possible. + this.Search = function(search) + { + if (!search) // get search word from URL + { + search = window.location.search; + search = search.substring(1); // Remove the leading '?' + search = unescape(search); + } + + search = search.replace(/^ +/, ""); // strip leading spaces + search = search.replace(/ +$/, ""); // strip trailing spaces + search = search.toLowerCase(); + search = convertToId(search); + + var resultRows = document.getElementsByTagName("div"); + var matches = 0; + + var i = 0; + while (i < resultRows.length) + { + var row = resultRows.item(i); + if (row.className == "SRResult") + { + var rowMatchName = row.id.toLowerCase(); + rowMatchName = rowMatchName.replace(/^sr\d*_/, ''); // strip 'sr123_' + + if (search.length<=rowMatchName.length && + rowMatchName.substr(0, search.length)==search) + { + row.style.display = 'block'; + matches++; + } + else + { + row.style.display = 'none'; + } + } + i++; + } + document.getElementById("Searching").style.display='none'; + if (matches == 0) // no results + { + document.getElementById("NoMatches").style.display='block'; + } + else // at least one result + { + document.getElementById("NoMatches").style.display='none'; + } + this.lastMatchCount = matches; + return true; + } + + // return the first item with index index or higher that is visible + this.NavNext = function(index) + { + var focusItem; + while (1) + { + var focusName = 'Item'+index; + focusItem = document.getElementById(focusName); + if (focusItem && focusItem.parentNode.parentNode.style.display=='block') + { + break; + } + else if (!focusItem) // last element + { + break; + } + focusItem=null; + index++; + } + return focusItem; + } + + this.NavPrev = function(index) + { + var focusItem; + while (1) + { + var focusName = 'Item'+index; + focusItem = document.getElementById(focusName); + if (focusItem && focusItem.parentNode.parentNode.style.display=='block') + { + break; + } + else if (!focusItem) // last element + { + break; + } + focusItem=null; + index--; + } + return focusItem; + } + + this.ProcessKeys = function(e) + { + if (e.type == "keydown") + { + this.repeatOn = false; + this.lastKey = e.keyCode; + } + else if (e.type == "keypress") + { + if (!this.repeatOn) + { + if (this.lastKey) this.repeatOn = true; + return false; // ignore first keypress after keydown + } + } + else if (e.type == "keyup") + { + this.lastKey = 0; + this.repeatOn = false; + } + return this.lastKey!=0; + } + + this.Nav = function(evt,itemIndex) + { + var e = (evt) ? evt : window.event; // for IE + if (e.keyCode==13) return true; + if (!this.ProcessKeys(e)) return false; + + if (this.lastKey==38) // Up + { + var newIndex = itemIndex-1; + var focusItem = this.NavPrev(newIndex); + if (focusItem) + { + var child = this.FindChildElement(focusItem.parentNode.parentNode.id); + if (child && child.style.display == 'block') // children visible + { + var n=0; + var tmpElem; + while (1) // search for last child + { + tmpElem = document.getElementById('Item'+newIndex+'_c'+n); + if (tmpElem) + { + focusItem = tmpElem; + } + else // found it! + { + break; + } + n++; + } + } + } + if (focusItem) + { + focusItem.focus(); + } + else // return focus to search field + { + parent.document.getElementById("MSearchField").focus(); + } + } + else if (this.lastKey==40) // Down + { + var newIndex = itemIndex+1; + var focusItem; + var item = document.getElementById('Item'+itemIndex); + var elem = this.FindChildElement(item.parentNode.parentNode.id); + if (elem && elem.style.display == 'block') // children visible + { + focusItem = document.getElementById('Item'+itemIndex+'_c0'); + } + if (!focusItem) focusItem = this.NavNext(newIndex); + if (focusItem) focusItem.focus(); + } + else if (this.lastKey==39) // Right + { + var item = document.getElementById('Item'+itemIndex); + var elem = this.FindChildElement(item.parentNode.parentNode.id); + if (elem) elem.style.display = 'block'; + } + else if (this.lastKey==37) // Left + { + var item = document.getElementById('Item'+itemIndex); + var elem = this.FindChildElement(item.parentNode.parentNode.id); + if (elem) elem.style.display = 'none'; + } + else if (this.lastKey==27) // Escape + { + parent.searchBox.CloseResultsWindow(); + parent.document.getElementById("MSearchField").focus(); + } + else if (this.lastKey==13) // Enter + { + return true; + } + return false; + } + + this.NavChild = function(evt,itemIndex,childIndex) + { + var e = (evt) ? evt : window.event; // for IE + if (e.keyCode==13) return true; + if (!this.ProcessKeys(e)) return false; + + if (this.lastKey==38) // Up + { + if (childIndex>0) + { + var newIndex = childIndex-1; + document.getElementById('Item'+itemIndex+'_c'+newIndex).focus(); + } + else // already at first child, jump to parent + { + document.getElementById('Item'+itemIndex).focus(); + } + } + else if (this.lastKey==40) // Down + { + var newIndex = childIndex+1; + var elem = document.getElementById('Item'+itemIndex+'_c'+newIndex); + if (!elem) // last child, jump to parent next parent + { + elem = this.NavNext(itemIndex+1); + } + if (elem) + { + elem.focus(); + } + } + else if (this.lastKey==27) // Escape + { + parent.searchBox.CloseResultsWindow(); + parent.document.getElementById("MSearchField").focus(); + } + else if (this.lastKey==13) // Enter + { + return true; + } + return false; + } +} + +function setKeyActions(elem,action) +{ + elem.setAttribute('onkeydown',action); + elem.setAttribute('onkeypress',action); + elem.setAttribute('onkeyup',action); +} + +function setClassAttr(elem,attr) +{ + elem.setAttribute('class',attr); + elem.setAttribute('className',attr); +} + +function createResults() +{ + var results = document.getElementById("SRResults"); + for (var e=0; e + +/// \brief This macro define the standard way of launching an exception +/// inside gazebo. +#define SDF_ASSERT(_expr, _msg) BOOST_ASSERT_MSG(_expr, _msg) + +#endif diff --git a/sdformat/include/sdf/CMakeLists.txt b/sdformat/include/sdf/CMakeLists.txt new file mode 100644 index 0000000..7e32833 --- /dev/null +++ b/sdformat/include/sdf/CMakeLists.txt @@ -0,0 +1,25 @@ +include (${sdf_cmake_dir}/SDFUtils.cmake) + +set (headers + Assert.hh + Console.hh + Converter.hh + Element.hh + Exception.hh + Param.hh + parser.hh + SDFImpl.hh + Types.hh + system_util.hh +) + +set (sdf_headers "" CACHE INTERNAL "SDF headers" FORCE) +foreach (hdr ${headers}) + APPEND_TO_CACHED_STRING(sdf_headers + "SDF Headers" "#include \n") +endforeach() +configure_file (${CMAKE_CURRENT_SOURCE_DIR}/sdf.hh.in + ${CMAKE_CURRENT_BINARY_DIR}/sdf.hh) + +sdf_install_includes("" ${headers} parser_urdf.hh + ${CMAKE_CURRENT_BINARY_DIR}/sdf.hh) diff --git a/sdformat/include/sdf/Console.hh b/sdformat/include/sdf/Console.hh new file mode 100644 index 0000000..5679ce7 --- /dev/null +++ b/sdformat/include/sdf/Console.hh @@ -0,0 +1,170 @@ +/* + * Copyright 2011 Nate Koenig + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#ifndef _SDF_CONSOLE_HH_ +#define _SDF_CONSOLE_HH_ + +#include +#include +#include + +#include + +#include "sdf/system_util.hh" + +#ifdef _WIN32 +// Disable warning C4251 which is triggered by +// std::unique_ptr +#pragma warning(push) +#pragma warning(disable: 4251) +#endif + +namespace sdf +{ + /// \addtogroup sdf SDF + /// \{ + + /// \brief Output a debug message + #define sdfdbg (sdf::Console::Instance()->Log("Dbg", \ + __FILE__, __LINE__)) + + /// \brief Output a message + #define sdfmsg (sdf::Console::Instance()->ColorMsg("Msg", \ + __FILE__, __LINE__, 32)) + + /// \brief Output a warning message + #define sdfwarn (sdf::Console::Instance()->ColorMsg("Warning", \ + __FILE__, __LINE__, 33)) + + /// \brief Output an error message + #define sdferr (sdf::Console::Instance()->ColorMsg("Error", \ + __FILE__, __LINE__, 31)) + + class ConsolePrivate; + class Console; + + /// \def ConsolePtr + /// \brief Shared pointer to a Console Element + typedef std::shared_ptr ConsolePtr; + + /// \brief Message, error, warning, and logging functionality + class SDFORMAT_VISIBLE Console + { + /// \brief An ostream-like class that we'll use for logging. + public: class SDFORMAT_VISIBLE ConsoleStream + { + /// \brief Constructor. + /// \param[in] _stream Pointer to an output stream operator. Can bee + /// NULL. + public: ConsoleStream(std::ostream *_stream) : + stream(_stream) {} + + /// \brief Redirect whatever is passed in to both our ostream + /// (if non-NULL) and the log file (if open). + /// \param[in] _rhs Content to be logged. + /// \return Reference to myself. + public: template + ConsoleStream &operator<<(const T &_rhs); + + /// \brief Print a prefix to both terminal and log file. + /// \param[in] _lbl Text label + /// \param[in] _file File containing the error + /// \param[in] _line Line containing the error + /// \param[in] _color Color to make the label. Used only on terminal. + public: void Prefix(const std::string &_lbl, + const std::string &_file, + unsigned int _line, int _color); + + /// \brief The ostream to log to; can be NULL. + private: std::ostream *stream; + }; + + /// \brief Default constructor + private: Console(); + + /// \brief Destructor + public: virtual ~Console(); + + /// \brief Return an instance to this class. + public: static ConsolePtr Instance(); + + /// \brief Set quiet output + /// \param[in] q True to prevent warning + public: void SetQuiet(bool _q); + + /// \brief Use this to output a colored message to the terminal + /// \param[in] _lbl Text label + /// \param[in] _file File containing the error + /// \param[in] _line Line containing the error + /// \param[in] _color Color to make the label + /// \return Reference to an output stream + public: ConsoleStream &ColorMsg(const std::string &lbl, + const std::string &file, + unsigned int line, int color); + + /// \brief Use this to output a message to a log file + /// \return Reference to output stream + public: ConsoleStream &Log(const std::string &lbl, + const std::string &file, + unsigned int line); + + /// \internal + /// \brief Pointer to private data. + private: std::unique_ptr dataPtr; + }; + + /// \internal + /// \brief Private data for Console + class ConsolePrivate + { + /// \brief Constructor + public: ConsolePrivate() : msgStream(&std::cerr), logStream(NULL) {} + + /// \brief message stream + public: Console::ConsoleStream msgStream; + + /// \brief log stream + public: Console::ConsoleStream logStream; + + /// \brief logfile stream + public: std::ofstream logFileStream; + }; + + /////////////////////////////////////////////// + template + Console::ConsoleStream &Console::ConsoleStream::operator<<(const T &_rhs) + { + if (this->stream) + *this->stream << _rhs; + + if (Console::Instance()->dataPtr->logFileStream.is_open()) + { + Console::Instance()->dataPtr->logFileStream << _rhs; + Console::Instance()->dataPtr->logFileStream.flush(); + } + + return *this; + } + + /// \} +} + +#ifdef _WIN32 +#pragma warning(pop) +#endif + +#endif diff --git a/sdformat/include/sdf/Converter.hh b/sdformat/include/sdf/Converter.hh new file mode 100644 index 0000000..3c8c87c --- /dev/null +++ b/sdformat/include/sdf/Converter.hh @@ -0,0 +1,89 @@ +/* + * Copyright 2012 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef _SDF_CONVERTER_HH_ +#define _SDF_CONVERTER_HH_ + +#include +#include + +#include "sdf/system_util.hh" + +namespace sdf +{ + /// \brief Convert from one version of SDF to another + class SDFORMAT_VISIBLE Converter + { + /// \brief Convert SDF to the specified version. + /// \param[in] _doc SDF xml doc + /// \param[in] _toVersion Version number in string format + /// \param[in] _quiet False to be more verbose + public: static bool Convert(TiXmlDocument *_doc, + const std::string &_toVersion, + bool _quiet = false); + + /// \cond + /// This is an internal function. + /// \brief Generic convert function that converts the SDF based on the + /// given Convert file. + /// \param[in] _doc SDF xml doc + /// \param[in] _convertDoc Convert xml doc + public: static void Convert(TiXmlDocument *_doc, + TiXmlDocument *_convertDoc); + /// \endcond + + private: static void ConvertImpl(TiXmlElement *_elem, + TiXmlElement *_convert); + + /// \brief Rename an element or attribute. + /// \param[in] _elem The element to be renamed, or the element which + /// has the attribute to be renamed. + /// \param[in] _renameElem A 'convert' element that describes the rename + /// operation. + private: static void Rename(TiXmlElement *_elem, + TiXmlElement *_renameElem); + + /// \brief Move an element or attribute within a common ancestor element. + /// \param[in] _elem Ancestor element of the element or attribute to + /// be moved. + /// \param[in] _moveElem A 'convert' element that describes the move + /// operation. + /// \param[in] _copy True to copy the element + private: static void Move(TiXmlElement *_elem, + TiXmlElement *_moveElem, + const bool _copy); + + /// \brief Add an element or attribute to an element. + /// \param[in] _elem The element to receive the value. + /// \param[in] _addElem A 'convert' element that describes the add + /// operation. + private: static void Add(TiXmlElement *_elem, + TiXmlElement *_addElem); + + /// \brief Remove an element. + /// \param[in] _elem The element that has the _removeElem child. + /// \param[in] _removeElem The element to remove. + private: static void Remove(TiXmlElement *_elem, TiXmlElement *_removeElem); + + private: static const char *GetValue(const char *_valueElem, + const char *_valueAttr, + TiXmlElement *_elem); + + private: static void CheckDeprecation(TiXmlElement *_elem, + TiXmlElement *_convert); + }; +} +#endif diff --git a/sdformat/include/sdf/Element.hh b/sdformat/include/sdf/Element.hh new file mode 100644 index 0000000..ea0286d --- /dev/null +++ b/sdformat/include/sdf/Element.hh @@ -0,0 +1,383 @@ +/* + * Copyright 2015 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef _SDF_ELEMENT_HH_ +#define _SDF_ELEMENT_HH_ + +#include +#include +#include + +#include "sdf/Param.hh" +#include "sdf/system_util.hh" + +/// \todo Remove this diagnositic push/pop in version 5 +#ifndef _WIN32 +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif +#include "sdf/Types.hh" +#ifndef _WIN32 +#pragma GCC diagnostic pop +#endif + +#ifdef _WIN32 +// Disable warning C4251 which is triggered by +// std::enable_shared_from_this +#pragma warning(push) +#pragma warning(disable: 4251) +#endif + +/// \ingroup sdf_parser +/// \brief namespace for Simulation Description Format parser +namespace sdf +{ + class ElementPrivate; + class SDFORMAT_VISIBLE Element; + + /// \def ElementPtr + /// \brief Shared pointer to an SDF Element + typedef std::shared_ptr ElementPtr; + + /// \def ElementWeakPtr + /// \brief Weak pointer to an SDF Element + typedef std::weak_ptr ElementWeakPtr; + + /// \def ElementPtr_V + /// \brief Vector of ElementPtr + typedef std::vector ElementPtr_V; + + /// \addtogroup sdf + /// \{ + + /// \class Element Element.hh sdf/sdf.hh + /// \brief SDF Element class + class SDFORMAT_VISIBLE Element : + public std::enable_shared_from_this + { + /// \brief Constructor. + public: Element(); + + /// \brief Destructor. + public: virtual ~Element(); + + /// \brief Create a copy of this Element. + /// \return A copy of this Element. + public: ElementPtr Clone() const; + + /// \brief Copy values from an Element. + /// \param[in] _elem Element to copy value from. + public: void Copy(const ElementPtr _elem); + + /// \brief Get a pointer to this Element's parent. + /// \return Pointer to this Element's parent, NULL if there is no + /// parent. + public: ElementPtr GetParent() const; + + /// \brief Set the parent of this Element. + /// \param[in] _parent Paren for this element. + public: void SetParent(const ElementPtr _parent); + + /// \brief Set the name of the Element. + /// \param[in] _name The new name for this Element. + public: void SetName(const std::string &_name); + + /// \brief Get the Element's name. + /// \return The name of this Element. + public: const std::string &GetName() const; + + /// \brief Set the requirement type. + /// \param[in] _req Requirement type for this element: + /// 0: Not required + /// 1: Exactly one element is required + /// +: One or more elements are required + /// *: Zero or more elements are required. + public: void SetRequired(const std::string &_req); + + /// \brief Get the requirement string. + /// \return The requirement string. + /// \sa Element::SetRequired + public: const std::string &GetRequired() const; + + /// \brief Set whether this element should copy its child elements + /// during parsing. + /// \param[in] _value True to copy Element's children. + public: void SetCopyChildren(bool _value); + + /// \brief Return true if this Element's child elements should be copied + /// during parsing. + /// \return True to copy child elements during parsing. + public: bool GetCopyChildren() const; + + /// \brief Set reference SDF element. + /// \param[in] _value Name of the reference sdf element. + public: void SetReferenceSDF(const std::string &_value); + + /// \brief Get the name of the reference SDF element. + /// \return Name of the reference SDF element. + public: std::string ReferenceSDF() const; + + /// \brief Output Element's description to stdout. + /// \param[in] _prefix String value to prefix to the output. + public: void PrintDescription(const std::string &_prefix); + + /// \brief Output Element's values to stdout. + /// \param[in] _prefix String value to prefix to the output. + public: void PrintValues(std::string _prefix); + + public: void PrintWiki(std::string _prefix); + + /// \brief Helper function for SDF::PrintDoc + /// + /// This generates the SDF html documentation. + /// \param[out] _html Accumulated HTML for output. + /// \param[in] _spacing Amount of spacing for this element. + /// \param[in] _index Unique index for this element. + public: void PrintDocLeftPane(std::string &_html, + int _spacing, int &_index); + + /// \brief Helper function for SDF::PrintDoc + /// + /// This generates the SDF html documentation. + /// \param[out] _html Accumulated HTML for output + /// \param[in] _spacing Amount of spacing for this element. + public: void PrintDocRightPane(std::string &_html, + int _spacing, int &_index); + + /// \brief Convert the element values to a string representation. + /// \param[in] _prefix String value to prefix to the output. + /// \return The string representation. + public: std::string ToString(const std::string &_prefix) const; + + /// \brief Add an attribute value. + /// \param[in] _key Key value. + /// \param[in] _type Type of data the attribute will hold. + /// \param[in] _defaultValue Default value for the attribute. + /// \param[in] _required Requirement string. \as Element::SetRequired. + /// \param[in] _description A text description of the attribute. + public: void AddAttribute(const std::string &_key, + const std::string &_type, + const std::string &_defaultvalue, + bool _required, + const std::string &_description=""); + + /// \brief Add a value to this Element. + /// \param[in] _type Type of data the attribute will hold. + /// \param[in] _defaultValue Default value for the attribute. + /// \param[in] _required Requirement string. \as Element::SetRequired. + /// \param[in] _description A text description of the attribute. + public: void AddValue(const std::string &_type, + const std::string &_defaultValue, bool _required, + const std::string &_description=""); + + /// \brief Get the param of an attribute. + /// \param[in] _key the name of the attribute + /// \return The parameter attribute value. NULL if the key is invalid. + public: ParamPtr GetAttribute(const std::string &_key); + + /// \brief Get the number of attributes + public: size_t GetAttributeCount() const; + + /// \brief Get an attribute using an index + public: ParamPtr GetAttribute(unsigned int _index) const; + + /// \brief Get the number of element descriptions + public: size_t GetElementDescriptionCount() const; + + /// \brief Get an element description using an index + public: ElementPtr GetElementDescription(unsigned int _index) const; + + /// \brief Get an element descriptio using a key + public: ElementPtr GetElementDescription(const std::string &_key) const; + + /// \brief Return true if an element description exists + public: bool HasElementDescription(const std::string &_name); + + public: bool HasAttribute(const std::string &_key); + + /// \brief Return true if the attribute was set (i.e. not default value) + public: bool GetAttributeSet(const std::string &_key); + + /// \brief Get the param of the elements value + public: ParamPtr GetValue(); + + /// \brief Get the element value/attribute as a boost::any. + /// \param[in] _key The key of the attribute. If empty, get the value of + /// the element. Defaults to empty. + /// \return The element as a boost::any. + public: boost::any GetAny(const std::string &_key = ""); + + public: template + T Get(const std::string &_key = ""); + + public: template + bool Set(const T &_value); + + public: bool HasElement(const std::string &_name) const; + + public: ElementPtr GetElement(const std::string &_name) const; + + /// \brief Get the first child element + /// \returns A smart pointer to the first child of this element, or + /// sdf::ElementPtr(nullptr) if there are no children + public: ElementPtr GetFirstElement() const; + + /// \brief Get the next sibling of this element + /// \param[in] _name if given then filter siblings by their xml tag + /// \remarks This function does not alter or store any state + /// Repeated calls to "GetNextElement()" with the same string will + /// always return a pointer to the same element. + /// \returns the next sibling element or sdf::ElementPtr(nullptr) + /// + /// This can be used in combination with GetFirstElement() to walk the SDF + /// tree. First call parent->GetFirstElement() to get the first child. Call + /// child = child->GetNextElement() to iterate through the children. + public: ElementPtr GetNextElement(const std::string &_name = "") const; + + /// \brief Return a pointer to the child element with the provided name. + /// + /// A new child element, with the provided name, is added to this element + /// if there is no existing child element. + /// \remarks If there are multiple elements with the given tag, it returns + /// the first one. + /// \param[in] _name Name of the child element to retreive. + /// \return Pointer to the existing child element, or a new child + /// element if an existing child element did not exist. + public: ElementPtr GetElement(const std::string &_name); + + public: ElementPtr AddElement(const std::string &_name); + public: void InsertElement(ElementPtr _elem); + + /// \brief Remove this element from its parent. + public: void RemoveFromParent(); + + /// \brief Remove a child element. + /// \param[in] _child Pointer to the child to remove. + public: void RemoveChild(ElementPtr _child); + + /// \brief Remove all child elements. + public: void ClearElements(); + + public: void Update(); + public: void Reset(); + + public: void SetInclude(const std::string &_filename); + public: std::string GetInclude() const; + + /// \brief Get a text description of the element + public: std::string GetDescription() const; + + /// \brief Set a text description for the element + public: void SetDescription(const std::string &_desc); + + /// \brief Add a new element description + public: void AddElementDescription(ElementPtr _elem); + + public: ElementPtr GetElementImpl(const std::string &_name) const; + + private: void ToString(const std::string &_prefix, + std::ostringstream &_out) const; + + + private: ParamPtr CreateParam(const std::string &_key, + const std::string &_type, const std::string &_defaultValue, + bool _required, const std::string &_description=""); + + + /// \brief Private data pointer + private: ElementPrivate *dataPtr; + }; + + /// \internal + /// \brief Private data for Element + class ElementPrivate + { + /// \brief Element name + public: std::string name; + + /// \brief True if element is required + public: std::string required; + + /// \brief Element description + public: std::string description; + + /// \brief True if element's children should be copied. + public: bool copyChildren; + + /// \brief Element's parent + public: ElementWeakPtr parent; + + // Attributes of this element + public: Param_V attributes; + + // Value of this element + public: ParamPtr value; + + // The existing child elements + public: ElementPtr_V elements; + + // The possible child elements + public: ElementPtr_V elementDescriptions; + + /// name of the include file that was used to create this element + public: std::string includeFilename; + + /// \brief Name of reference sdf. + public: std::string referenceSDF; + }; + + /////////////////////////////////////////////// + template + T Element::Get(const std::string &_key) + { + T result = T(); + + if (_key.empty() && this->dataPtr->value) + this->dataPtr->value->Get(result); + else if (!_key.empty()) + { + ParamPtr param = this->GetAttribute(_key); + if (param) + param->Get(result); + else if (this->HasElement(_key)) + result = this->GetElementImpl(_key)->Get(); + else if (this->HasElementDescription(_key)) + result = this->GetElementDescription(_key)->Get(); + else + sdferr << "Unable to find value for key[" << _key << "]\n"; + } + return result; + } + + /////////////////////////////////////////////// + template + bool Element::Set(const T &_value) + { + if (this->dataPtr->value) + { + this->dataPtr->value->Set(_value); + return true; + } + return false; + } + /// \} +} + +#ifdef _WIN32 +#pragma warning(pop) +#endif + +#endif diff --git a/sdformat/include/sdf/Exception.hh b/sdformat/include/sdf/Exception.hh new file mode 100644 index 0000000..1ddfb94 --- /dev/null +++ b/sdformat/include/sdf/Exception.hh @@ -0,0 +1,133 @@ +/* + * Copyright 2012 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#ifndef _SDF_EXCEPTION_HH_ +#define _SDF_EXCEPTION_HH_ + +#include +#include +#include +#include + +#include "sdf/system_util.hh" + +namespace sdf +{ + /// \addtogroup sdf + /// \{ + + /// \brief This macro logs an error to the throw stream and throws + /// an exception that contains the file name and line number. + #define sdfthrow(msg) {std::ostringstream throwStream;\ + throwStream << msg << std::endl << std::flush;\ + throw sdf::Exception(__FILE__, __LINE__, throwStream.str()); } + + class ExceptionPrivate; + + /// \class Exception Exception.hh common/common.hh + /// \brief Class for generating exceptions + class SDFORMAT_VISIBLE Exception + { + /// \brief Constructor + public: Exception(); + + /// \brief Default constructor + /// \param[in] _file File name + /// \param[in] _line Line number where the error occurred + /// \param[in] _msg Error message + public: Exception(const char *_file, + int64_t _line, + std::string _msg); + + /// \brief Copy constructor + /// \param[in] _e Exception to copy. + public: Exception(const Exception &_e); + + /// \brief Destructor + public: virtual ~Exception(); + + /// \brief Return the error function + /// \return The error function name + public: std::string GetErrorFile() const; + + /// \brief Return the error string + /// \return The error string + public: std::string GetErrorStr() const; + + /// \brief Print the exception to std out. + public: void Print() const; + + + /// \brief stream insertion operator for Gazebo Error + /// \param[in] _out the output stream + /// \param[in] _err the exception + public: friend std::ostream &operator<<(std::ostream& _out, + const sdf::Exception &_err) + { + return _out << _err.GetErrorStr(); + } + + /// \brief Private data pointer. + private: ExceptionPrivate *dataPtr; + }; + + /// \class InternalError Exception.hh common/common.hh + /// \brief Class for generating Internal Gazebo Errors: + /// those errors which should never happend and + /// represent programming bugs. + class SDFORMAT_VISIBLE InternalError : public Exception + { + /// \brief Constructor + public: InternalError(); + + /// \brief Default constructor + /// \param[in] _file File name + /// \param[in] _line Line number where the error occurred + /// \param[in] _msg Error message + public: InternalError(const char *_file, int64_t _line, + const std::string _msg); + + /// \brief Destructor + public: virtual ~InternalError(); + }; + + /// \class AssertionInternalError Exception.hh common/common.hh + /// \brief Class for generating Exceptions which come from + /// sdf assertions. They include information about the + /// assertion expression violated, function where problem + /// appeared and assertion debug message. + class SDFORMAT_VISIBLE AssertionInternalError : public InternalError + { + /// \brief Constructor for assertions + /// \param[in] _file File name + /// \param[in] _line Line number where the error occurred + /// \param[in] _expr Assertion expression failed resulting in an + /// internal error + /// \param[in] _function Function where assertion failed + /// \param[in] _msg Function where assertion failed + public: AssertionInternalError(const char *_file, + int64_t _line, + const std::string _expr, + const std::string _function, + const std::string _msg = ""); + /// \brief Destructor + public: virtual ~AssertionInternalError(); + }; + /// \} +} + +#endif diff --git a/sdformat/include/sdf/ExceptionPrivate.hh b/sdformat/include/sdf/ExceptionPrivate.hh new file mode 100644 index 0000000..99981e2 --- /dev/null +++ b/sdformat/include/sdf/ExceptionPrivate.hh @@ -0,0 +1,41 @@ +/* + * Copyright 2015 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifndef _SDF_EXCEPTION_PRIVATE_HH_ +#define _SDF_EXCEPTION_PRIVATE_HH_ + +#include +#include + +namespace sdf +{ + /// \internal + /// \brief Private data for Exception + class ExceptionPrivate + { + /// \brief The error function + public: std::string file; + + /// \brief Line the error occured on + public: int64_t line; + + /// \brief The error string + public: std::string str; + }; +} +#endif + diff --git a/sdformat/include/sdf/Param.hh b/sdformat/include/sdf/Param.hh new file mode 100644 index 0000000..e451e0a --- /dev/null +++ b/sdformat/include/sdf/Param.hh @@ -0,0 +1,377 @@ +/* + * Copyright 2012 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#ifndef _SDF_PARAM_HH_ +#define _SDF_PARAM_HH_ + +// See: https://bugreports.qt-project.org/browse/QTBUG-22829 +#ifndef Q_MOC_RUN + #include + #include + #include + #include +#endif + +#include +#include +#include +#include +#include +#include +#include + +#include "sdf/Console.hh" +#include "sdf/system_util.hh" + +/// \todo Remove this diagnositic push/pop in version 5 +#ifndef _WIN32 +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif +#include "sdf/Types.hh" +#ifndef _WIN32 +#pragma GCC diagnostic pop +#endif + +namespace sdf +{ + class SDFORMAT_VISIBLE Param; + + /// \def ParamPtr + /// \brief Shared pointer to a Param + typedef std::shared_ptr ParamPtr; + + /// \def Param_V + /// \brief vector of shared pointers to a Param + typedef std::vector Param_V; + + /// \internal + class ParamPrivate; + + /// \class Param Param.hh sdf/sdf.hh + /// \brief A parameter class + class SDFORMAT_VISIBLE Param + { + /// \brief Constructor. + /// \param[in] _key Key for the parameter. + /// \param[in] _typeName String name for the value type (double, + /// int,...). + /// \param[in] _default Default value. + /// \param[in] _required True if the parameter is required to be set. + /// \param[in] _description Description of the parameter. + public: Param(const std::string &_key, const std::string &_typeName, + const std::string &_default, bool _required, + const std::string &_description = ""); + + /// \brief Destructor + public: virtual ~Param(); + + /// \brief Get the value as a string. + /// \return String containing the value of the parameter. + public: std::string GetAsString() const; + + /// \brief Get the default value as a string. + /// \return String containing the default value of the parameter. + public: std::string GetDefaultAsString() const; + + /// \brief Set the parameter value from a string. + /// \param[in] _value New value for the parameter in string form. + public: bool SetFromString(const std::string &_value); + + /// \brief Reset the parameter to the default value. + public: void Reset(); + + /// \brief Get the key value. + /// \return The key. + public: const std::string &GetKey() const; + + /// \brief Get the type of the value stored. + /// \return The std::type_info. + /// \deprecated GetType is unstable. Use IsType(). + /// \sa IsType + public: const std::type_info &GetType() const SDF_DEPRECATED(4.0); + + /// \brief Return true if the param is a particular type + /// \return True if the type held by this Param matches the Type + /// template parameter. + public: template + bool IsType() const; + + /// \brief Get the type name value. + /// \return The type name. + public: const std::string &GetTypeName() const; + + /// \brief Return whether the parameter is required. + /// \return True if the parameter is required. + public: bool GetRequired() const; + + /// \brief Return true if the parameter has been set. + /// \return True if the parameter has been set. + public: bool GetSet() const; + + /// \brief Clone the parameter. + /// \return A new parameter that is the clone of this. + public: ParamPtr Clone() const; + + /// \brief Set the update function. The updateFunc will be used to + /// set the parameter's value when Param::Update is called. + /// \param[in] _updateFunc Function pointer to an update function. + public: template + void SetUpdateFunc(T _updateFunc); + + /// \brief Set the parameter's value using the updateFunc. + /// \sa Param::SetUpdateFunc + public: void Update(); + + /// \brief Set the parameter's value. + /// + /// The passed in value must conform to the boost::lexical_cast spec. + /// This means the value must have an input and output stream operator. + /// \param[in] _value The value to set the parameter to. + /// \return True if the value was successfully set. + public: template + bool Set(const T &_value); + + /// \brief Get the value of the parameter as a boost::any. + /// \param[out] _anyVal The boost::any object to set. + /// \return True if successfully set _anyVal, false otherwise. + public: bool GetAny(boost::any &_anyVal) const; + + /// \brief Get the value of the parameter. + /// \param[out] _value The value of the parameter. + /// \return True if parameter was successfully cast to the value type + /// passed in. + public: template + bool Get(T &_value) const; + + /// \brief Get the default value of the parameter. + /// \param[out] _value The default value of the parameter. + /// \return True if parameter was successfully cast to the value type + /// passed in. + public: template + bool GetDefault(T &_value) const; + + /// \brief Equal operator. Set's the value and default value from the + /// provided Param. + /// \param[in] _param The parameter to set values from. + /// \return *This + public: Param &operator=(const Param &_param); + + /// \brief Set the description of the parameter. + /// \param[in] _desc New description for the parameter. + public: void SetDescription(const std::string &_desc); + + /// \brief Get the description of the parameter. + /// \return The description of the parameter. + public: std::string GetDescription() const; + + /// \brief Ostream operator. Outputs the parameter's value. + /// \param[in] _out Output stream. + /// \param[in] _p The parameter to output. + /// \return The output stream. + public: friend std::ostream &operator<<(std::ostream &_out, + const Param &_p) + { + _out << _p.GetAsString(); + return _out; + } + + /// \brief Initialize the value. This is called from the constructor. + /// \param[in] _value Value to set the parameter to. + private: template + void Init(const std::string &_value); + + /// \brief Private data + private: ParamPrivate *dataPtr; + }; + + /// \internal + /// \brief Private data for the param class + class ParamPrivate + { + /// \brief Key value + public: std::string key; + + /// \brief True if the parameter is required. + public: bool required; + + /// \brief True if the parameter is set. + public: bool set; + + //// \brief Name of the type. + public: std::string typeName; + + /// \brief Description of the parameter. + public: std::string description; + + /// \brief Update function pointer. + public: std::function updateFunc; + +/// \todo Remove this diagnositic push/pop in version 5 +#ifndef _WIN32 +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif + /// \def ParamVariant + /// \briead Variant type def. + public: typedef boost::variant ParamVariant; +#ifndef _WIN32 +#pragma GCC diagnostic pop +#endif + + /// \brief This parameter's value + public: ParamVariant value; + + /// \brief This parameter's default value + public: ParamVariant defaultValue; + }; + + /////////////////////////////////////////////// + template + void Param::SetUpdateFunc(T _updateFunc) + { + this->dataPtr->updateFunc = _updateFunc; + } + + /////////////////////////////////////////////// + template + bool Param::Set(const T &_value) + { + try + { + this->SetFromString(boost::lexical_cast(_value)); + } + catch(...) + { + sdferr << "Unable to set parameter[" + << this->dataPtr->key << "]." + << "Type type used must have a stream input and output" + << "operator, which allow boost::lexical_cast to" + << "function properly.\n"; + return false; + } + return true; + } + + /////////////////////////////////////////////// + template + bool Param::Get(T &_value) const + { + try + { + if (typeid(T) == typeid(bool) && + this->dataPtr->typeName == "string") + { + std::string strValue = + boost::lexical_cast(this->dataPtr->value); + std::transform(strValue.begin(), strValue.end(), + strValue.begin(), ::tolower); + if (strValue == "true" || strValue == "1") + _value = boost::lexical_cast("1"); + else + _value = boost::lexical_cast("0"); + } + else if (typeid(T) == this->dataPtr->value.type()) + { +#if BOOST_VERSION < 105800 + _value = boost::get(this->dataPtr->value); +#else + _value = boost::relaxed_get(this->dataPtr->value); +#endif + } + else + { + _value = boost::lexical_cast(this->dataPtr->value); + } + } + catch(...) + { + sdferr << "Unable to convert parameter[" + << this->dataPtr->key << "] " + << "whose type is[" + << this->dataPtr->typeName << "], to " + << "type[" << typeid(T).name() << "]\n"; + return false; + } + return true; + } + + /////////////////////////////////////////////// + template + bool Param::GetDefault(T &_value) const + { + try + { + _value = boost::lexical_cast(this->dataPtr->defaultValue); + } + catch(...) + { + sdferr << "Unable to convert parameter[" + << this->dataPtr->key << "] " + << "whose type is[" + << this->dataPtr->typeName << "], to " + << "type[" << typeid(T).name() << "]\n"; + return false; + } + return true; + } + + /////////////////////////////////////////////// + template + void Param::Init(const std::string &_value) + { + try + { + this->dataPtr->value = boost::lexical_cast(_value); + } + catch(...) + { + if (this->dataPtr->typeName == "bool") + { + std::string strValue = _value; + std::transform(strValue.begin(), strValue.end(), + strValue.begin(), ::tolower); + if (strValue == "true" || strValue == "1") + this->dataPtr->value = true; + else + this->dataPtr->value = false; + } + else + { + sdferr << "Unable to init parameter value from string[" + << _value << "]\n"; + } + } + + this->dataPtr->defaultValue = this->dataPtr->value; + this->dataPtr->set = false; + } + + /////////////////////////////////////////////// + template + bool Param::IsType() const + { + return this->dataPtr->value.type() == typeid(Type); + } +} +#endif diff --git a/sdformat/include/sdf/SDFExtension.hh b/sdformat/include/sdf/SDFExtension.hh new file mode 100644 index 0000000..3ae467b --- /dev/null +++ b/sdformat/include/sdf/SDFExtension.hh @@ -0,0 +1,129 @@ +/* + * Copyright 2015 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#ifndef _SDFORMAT_SDFEXTENSION_HH_ +#define _SDFORMAT_SDFEXTENSION_HH_ + +#include +#include +#include +#include +#include + +/// \todo Remove this diagnositic push/pop in version 5 +#ifndef _WIN32 +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif +#include "sdf/Types.hh" +#ifndef _WIN32 +#pragma GCC diagnostic pop +#endif + +namespace sdf +{ + /// \internal + /// \brief A class for holding sdf extension elements in urdf + class SDFExtension + { + /// \brief Constructor + public: SDFExtension(); + + /// \brief Copy constructor + /// \param[in] _ge SDFExtension to copy. + public: SDFExtension(const SDFExtension &_ge); + + /// \brief Destructor + public: virtual ~SDFExtension() = default; + + // for reducing fixed joints and removing links + public: std::string oldLinkName; + public: ignition::math::Pose3d reductionTransform; + + // visual material + public: std::string material; + + /// \brief blobs of xml to be copied into the visual sdf element + public: std::vector > visual_blobs; + + /// \brief blobs of xml to be copied into the collision sdf element + /// An example might be: + /// + /// + /// 10 + /// + /// + /// + /// 1e+06 + /// 100 + /// 100 + /// 0.001 + /// + /// + /// + /// + /// 1 + /// 1 + /// + /// + /// + /// + /// + /// where all the contents of `` element is copied into the + /// resulting collision sdf. + public: std::vector > collision_blobs; + + // body, default off + public: bool setStaticFlag; + public: bool gravity; + public: bool isDampingFactor; + public: double dampingFactor; + public: bool isMaxContacts; + public: int maxContacts; + public: bool isMaxVel; + public: double maxVel; + public: bool isMinDepth; + public: double minDepth; + public: bool isSelfCollide; + public: bool selfCollide; + + // geom, contact dynamics + public: bool isMu1, isMu2, isKp, isKd; + public: double mu1, mu2, kp, kd; + public: std::string fdir1; + public: bool isLaserRetro; + public: double laserRetro; + + // joint, joint limit dynamics + public: bool isStopCfm, isStopErp, isInitialJointPosition, isFudgeFactor; + public: double stopCfm, stopErp, initialJointPosition, fudgeFactor; + public: bool isSpringReference, isSpringStiffness; + public: double springReference, springStiffness; + public: bool isProvideFeedback; + public: bool provideFeedback; + public: bool isImplicitSpringDamper; + public: bool implicitSpringDamper; + public: bool isStopKp, isStopKd; + public: double stopKp, stopKd; + + // blobs into body or robot + public: std::vector > blobs; + + friend class SDFORMAT_VISIBLE URDF2SDF; + }; +} +#endif diff --git a/sdformat/include/sdf/SDFImpl.hh b/sdformat/include/sdf/SDFImpl.hh new file mode 100644 index 0000000..96963a2 --- /dev/null +++ b/sdformat/include/sdf/SDFImpl.hh @@ -0,0 +1,130 @@ +/* + * Copyright 2012 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef _SDFIMPL_HH_ +#define _SDFIMPL_HH_ + +#include +#include +#include + +#include "sdf/Param.hh" +#include "sdf/Element.hh" +#include "sdf/system_util.hh" + +/// \todo Remove this diagnositic push/pop in version 5 +#ifndef _WIN32 +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif +#include "sdf/Types.hh" +#ifndef _WIN32 +#pragma GCC diagnostic pop +#endif + +/// \ingroup sdf_parser +/// \brief namespace for Simulation Description Format parser +namespace sdf +{ + class SDFORMAT_VISIBLE SDF; + + /// \def SDFPtr + /// \brief Shared pointer to SDF + typedef std::shared_ptr SDFPtr; + + /// \addtogroup sdf + /// \{ + + /// \brief Find the absolute path of a file. + /// \param[in] _filename Name of the file to find. + /// \param[in] _searchLocalPath True to search for the file in the current + /// working directory. + /// \param[in] _useCallback True to find a file based on a registered + /// callback if the file is not found via the normal mechanism. + SDFORMAT_VISIBLE + std::string findFile(const std::string &_filename, + bool _searchLocalPath = true, + bool _useCallback = false); + + /// \brief Associate paths to a URI. + /// Example paramters: "model://", "/usr/share/models:~/.gazebo/models" + /// \param[in] _uri URI that will be mapped to _path + /// \param[in] _path Colon separated set of paths. + SDFORMAT_VISIBLE + void addURIPath(const std::string &_uri, const std::string &_path); + + /// \brief Set the callback to use when SDF can't find a file. + /// The callback should return a complete path to the requested file, or + /// and empty string if the file was not found in the callback. + /// \param[in] _cb The callback function. + SDFORMAT_VISIBLE + void setFindCallback(std::function _cb); + + /// \brief Base SDF class + class SDFORMAT_VISIBLE SDF + { + public: SDF(); + /// \brief Destructor + public: ~SDF(); + public: void PrintDescription(); + public: void PrintValues(); + public: void PrintWiki(); + public: void PrintDoc(); + public: void Write(const std::string &_filename); + public: std::string ToString() const; + + /// \brief Set SDF values from a string + public: void SetFromString(const std::string &_sdfData); + + /// \brief Get a pointer to the root element + /// \return Pointer to the root element + public: ElementPtr Root() const; + + /// \brief Set the root pointer + /// \param[in] _root Root element + public: void Root(const ElementPtr _root); + + /// \brief Get the version + /// \return The version as a string + public: static std::string Version(); + + /// \brief Set the version string + /// \param[in] _version SDF version string. + public: static void Version(const std::string &_version); + +// \todo Remove this warning push/pop after sdformat 4.0 +#ifdef _MSC_VER +#pragma warning(push) +#pragma warning(disable : 4251) +#endif + + /// \brief Deprecated. + /// \sa ElementPtr Root() + /// \sa void Root(const ElementPtr _root) + public: ElementPtr root SDF_DEPRECATED(4.0); + + /// \brief Deprecated. + /// \sa std::string Version() + /// \sa Version(const std::string &_version) + public: static std::string version SDF_DEPRECATED(4.0); + +#ifdef _MSC_VER +#pragma warning(pop) +#endif + }; + /// \} +} +#endif diff --git a/sdformat/include/sdf/Types.hh b/sdformat/include/sdf/Types.hh new file mode 100644 index 0000000..b800329 --- /dev/null +++ b/sdformat/include/sdf/Types.hh @@ -0,0 +1,757 @@ +/* + * Copyright 2011 Nate Koenig + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#ifndef _SDF_TYPES_HH_ +#define _SDF_TYPES_HH_ + +#include +#include +#include +#include +#include + +#include "sdf/system_util.hh" + +#if defined(__GNUC__) +#define SDF_DEPRECATED(version) __attribute__((deprecated)) +#define SDF_FORCEINLINE __attribute__((always_inline)) +#elif defined(MSVC) +#define SDF_DEPRECATED(version) +#define SDF_FORCEINLINE __forceinline +#else +#define SDF_DEPRECATED(version) +#define SDF_FORCEINLINE +#endif + +namespace sdf +{ + /// \brief Windows equivalent of getEnv. + /// Should only be called when using windows. + /// \param[in] _name Name of the environment variable to get. + /// \return Environment variable contents, or NULL on error. + SDFORMAT_VISIBLE + const char *winGetEnv(const char *_name); + + /// \brief check if two values are equal, within a tolerance + /// \param[in] _a the first value + /// \param[in] _b the second value + /// \param[in] _epsilon the tolerance + template + inline bool equal(const T &_a, const T &_b, + const T &_epsilon = 1e-6) + { + return std::fabs(_a - _b) <= _epsilon; + } + + /// \brief Defines a color + class SDFORMAT_VISIBLE Color + { + /// \brief Constructor + /// \param[in] _r Red value (range 0 to 1) + /// \param[in] _g Green value (range 0 to 1 + /// \param[in] _b Blue value (range 0 to 1 + /// \param[in] _a Alpha value (0=transparent, 1=opaque) + public: Color(float _r = 0.0f, float _g = 0.0f, + float _b = 0.0f, float _a = 1.0f) + : r(_r), g(_g), b(_b), a(_a) {} + + /// \brief Stream insertion operator + /// \param[in] _out the output stream + /// \param[in] _pt the color + /// \return the output stream + public: friend std::ostream &operator<< (std::ostream &_out, + const Color &_pt) + { + _out << _pt.r << " " << _pt.g << " " << _pt.b << " " << _pt.a; + return _out; + } + + /// \brief Stream insertion operator + /// \param[in] _in the input stream + /// \param[in] _pt + public: friend std::istream &operator>> (std::istream &_in, Color &_pt) + { + // Skip white spaces + _in.setf(std::ios_base::skipws); + _in >> _pt.r >> _pt.g >> _pt.b >> _pt.a; + return _in; + } + + /// \brief Equality operator + /// \param[in] _clr The color to check for equality + /// \return True if the this color equals _clf + public: bool operator ==(const Color &_clr) const + { + return equal(this->r, _clr.r) && + equal(this->g, _clr.g) && + equal(this->b, _clr.b) && + equal(this->a, _clr.a); + } + + /// \brief Red value + public: float r; + + /// \brief Green value + public: float g; + + /// \brief Blue value + public: float b; + + /// \brief Alpha value + public: float a; + }; + + /// \deprecated Use ignition::math::Vector2i + /// \brief Generic integer x, y vector + class SDFORMAT_VISIBLE Vector2i + { + /// \brief Constructor + /// \param[in] _x value along x + /// \param[in] _y value along y + public: Vector2i(int _x = 0, int _y = 0) + : x(_x), y(_y) {} + + /// \brief Stream insertion operator + /// \param[in] _out output stream + /// \param[in] pt Vector2i to output + /// \return the stream + public: friend std::ostream &operator<<(std::ostream &_out, + const Vector2i &_pt) + { + _out << _pt.x << " " << _pt.y; + return _out; + } + + /// \brief Stream extraction operator + /// \param[in] _in input stream + /// \param[in] _pt Vector2i to read values into + /// \return The stream + public: friend std::istream &operator>>(std::istream &_in, + Vector2i &_pt) + { + // Skip white spaces + _in.setf(std::ios_base::skipws); + _in >> _pt.x >> _pt.y; + return _in; + } + + /// \brief Equality operator + /// \param _pt The vector to compare with + /// \return True if component have the same values, false otherwise + public: bool operator ==(const Vector2i &_pt) const + { + return this->x == _pt.x && this->y == _pt.y; + } + + /// \brief x data + public: int x; + + /// \brief y data + public: int y; + } SDF_DEPRECATED(4.0); + + /// \deprecated Use ignition::math::Vector2d + /// \brief Generic double x, y vector + class SDFORMAT_VISIBLE Vector2d + { + /// \brief Constructor + /// \param[in] _x value along x + /// \param[in] _y value along y + public: Vector2d(double _x = 0.0, double _y = 0.0) + : x(_x), y(_y) {} + + /// \brief Stream extraction operator + /// \param[in] _out output stream + /// \param[in] _pt Vector2d to output + /// \return The stream + public: friend std::ostream &operator<<(std::ostream &_out, + const Vector2d &_pt) + { + _out << _pt.x << " " << _pt.y; + return _out; + } + + /// \brief Stream extraction operator + /// \param[in] _in input stream + /// \param[in] _pt Vector2d to read values into + /// \return The stream + public: friend std::istream &operator>>(std::istream &_in, + Vector2d &_pt) + { + // Skip white spaces + _in.setf(std::ios_base::skipws); + _in >> _pt.x >> _pt.y; + return _in; + } + + /// \brief Equal to operator + /// \param[in] _v the vector to compare to + /// \return true if the elements of the 2 vectors are equal within + /// a tolerence (1e-6) + public: bool operator ==(const Vector2d &_pt) const + { + return equal(this->x, _pt.x) && equal(this->y, _pt.y); + } + + + /// \brief x data + public: double x; + + /// \brief y data + public: double y; + } SDF_DEPRECATED(4.0); + + /// \deprecated Use ignition::math::Vector3d + /// \brief The Vector3 class represents the generic vector containing 3 + /// elements. Since it's commonly used to keep coordinate system + /// related information, its elements are labeled by x, y, z. + class SDFORMAT_VISIBLE Vector3 + { + /// \brief Copy constructor + /// \param[in] _v a vector + public: Vector3(const Vector3 &_v) + : x(_v.x), y(_v.y), z(_v.z) {} + + /// \brief Constructor + /// \param[in] _x value along x + /// \param[in] _y value along y + /// \param[in] _z value along z + public: Vector3(double _x = 0.0, double _y = 0.0, double _z = 0.0) + : x(_x), y(_y), z(_z) {} + + /// \brief Addition operator + /// \param[in] _v vector to add + /// \return the sum vector + public: Vector3 operator+(const Vector3 &_v) const + { + return Vector3(this->x + _v.x, this->y + _v.y, this->z + _v.z); + } + + /// \brief Return the cross product of this vector and pt + /// \return the product + public: Vector3 Cross(const Vector3 &_pt) const + { + Vector3 c(0, 0, 0); + + c.x = this->y * _pt.z - this->z * _pt.y; + c.y = this->z * _pt.x - this->x * _pt.z; + c.z = this->x * _pt.y - this->y * _pt.x; + + return c; + } + + /// \brief Multiplication operator + /// \remarks this is an element wise multiplication, not a cross product + /// \param[in] _v + public: Vector3 operator*(double _v) const + { + return Vector3(this->x * _v, this->y * _v, this->z * _v); + } + + /// \brief Stream insertion operator + /// \param _out output stream + /// \param _pt Vector3 to output + /// \return the stream + public: friend std::ostream &operator<<(std::ostream &_out, + const Vector3 &_pt) + { + _out << _pt.x << " " << _pt.y << " " << _pt.z; + return _out; + } + + /// \brief Multiplication by a double + /// \param[in] _v A double + /// \return this + public: const Vector3 &operator*=(double _v) + { + this->x *= _v; + this->y *= _v; + this->z *= _v; + + return *this; + } + + /// \brief Equal to operator + /// \param[in] _pt The vector to compare against + /// \return true if each component is equal within a + /// tolerence (1e-3), false otherwise + public: bool operator==(const sdf::Vector3 &_pt) const + { + return equal(this->x, _pt.x, 0.001) && + equal(this->y, _pt.y, 0.001) && + equal(this->z, _pt.z, 0.001); + } + + /// \brief Stream extraction operator + /// \param _in input stream + /// \param _pt vector3 to read values into + /// \return the stream + public: friend std::istream &operator>>(std::istream &_in, + Vector3 &_pt) + { + // Skip white spaces + _in.setf(std::ios_base::skipws); + _in >> _pt.x >> _pt.y >> _pt.z; + return _in; + } + + /// \brief x Data + public: double x; + + /// \brief y Data + public: double y; + + /// \brief z Data + public: double z; + } SDF_DEPRECATED(4.0); + + /// \deprecated Use ignition::math::Quaterniond + /// \brief A quaternion class + class SDFORMAT_VISIBLE Quaternion + { + /// \brief Default Constructor + public: Quaternion() : x(0), y(0), z(0), w(1) + {} + + /// \brief Copy constructor + /// \param[in] _q Quaternion to copy + public: Quaternion(const Quaternion &_q) + : x(_q.x), y(_q.y), z(_q.z), w(_q.w) {} + + public: Quaternion(const double &_roll, const double &_pitch, + const double &_yaw) + { + this->SetFromEuler(Vector3(_roll, _pitch, _yaw)); + } + + /// \brief Constructor + /// \param[in] _w W param + /// \param[in] _x X param + /// \param[in] _y Y param + /// \param[in] _z Z param + public: Quaternion(double _w, double _x, double _y, double _z) + : x(_x), y(_y), z(_z), w(_w) {} + + /// \brief Convert euler angles to quatern. + /// \param[in] _x rotation along x + /// \param[in] _y rotation along y + /// \param[in] _z rotation along z + public: static Quaternion EulerToQuaternion(double _x, double _y, double _z) + { + return EulerToQuaternion(Vector3(_x, _y, _z)); + } + + /// \brief Convert euler angles to quatern. + /// \param[in] _vec Vector of Euler angles + public: static Quaternion EulerToQuaternion(const Vector3 &_vec) + { + Quaternion result; + result.SetFromEuler(_vec); + return result; + } + + /// \brief Equal operator + /// \param[in] _qt Quaternion to copy + public: Quaternion &operator =(const Quaternion &_qt) + { + this->w = _qt.w; + this->x = _qt.x; + this->y = _qt.y; + this->z = _qt.z; + + return *this; + } + + /// \brief Multiplication operator + /// \param[in] _qt Quaternion for multiplication + /// \return This quaternion multiplied by the parameter + public: inline Quaternion operator*(const Quaternion &_q) const + { + return Quaternion( + this->w*_q.w - this->x*_q.x - this->y*_q.y - this->z*_q.z, + this->w*_q.x + this->x*_q.w + this->y*_q.z - this->z*_q.y, + this->w*_q.y - this->x*_q.z + this->y*_q.w + this->z*_q.x, + this->w*_q.z + this->x*_q.y - this->y*_q.x + this->z*_q.w); + } + + /// \brief Get the inverse of this quaternion + /// \return Inverse quarenion + public: inline Quaternion GetInverse() const + { + double s = 0; + Quaternion q(this->w, this->x, this->y, this->z); + + // use s to test if quaternion is valid + s = q.w * q.w + q.x * q.x + q.y * q.y + q.z * q.z; + + if (equal(s, 0.0)) + { + q.w = 1.0; + q.x = 0.0; + q.y = 0.0; + q.z = 0.0; + } + else + { + // deal with non-normalized quaternion + // div by s so q * qinv = identity + q.w = q.w / s; + q.x = -q.x / s; + q.y = -q.y / s; + q.z = -q.z / s; + } + return q; + } + + /// \brief Return the rotation in Euler angles + /// \return This quaternion as an Euler vector + public: Vector3 GetAsEuler() const + { + Vector3 vec; + + Quaternion copy = *this; + double squ; + double sqx; + double sqy; + double sqz; + + copy.Normalize(); + + squ = copy.w * copy.w; + sqx = copy.x * copy.x; + sqy = copy.y * copy.y; + sqz = copy.z * copy.z; + + // Roll + vec.x = atan2(2 * (copy.y*copy.z + copy.w*copy.x), + squ - sqx - sqy + sqz); + + // Pitch + double sarg = -2 * (copy.x*copy.z - copy.w * copy.y); + vec.y = sarg <= -1.0 ? -0.5*M_PI : + (sarg >= 1.0 ? 0.5*M_PI : asin(sarg)); + + // Yaw + vec.z = atan2(2 * (copy.x*copy.y + copy.w*copy.z), + squ + sqx - sqy - sqz); + + return vec; + } + + /// \brief Set the quaternion from Euler angles + /// \param[in] _vec Euler angle + public: void SetFromEuler(const Vector3 &_vec) + { + double phi, the, psi; + + phi = _vec.x / 2.0; + the = _vec.y / 2.0; + psi = _vec.z / 2.0; + + this->w = cos(phi) * cos(the) * cos(psi) + sin(phi) * + sin(the) * sin(psi); + this->x = sin(phi) * cos(the) * cos(psi) - cos(phi) * + sin(the) * sin(psi); + this->y = cos(phi) * sin(the) * cos(psi) + sin(phi) * + cos(the) * sin(psi); + this->z = cos(phi) * cos(the) * sin(psi) - sin(phi) * + sin(the) * cos(psi); + + this->Normalize(); + } + + /// \brief Normalize the quaternion + public: void Normalize() + { + double s = 0; + + s = sqrt(this->w * this->w + this->x * this->x + + this->y * this->y + + this->z * this->z); + + if (equal(s, 0.0)) + { + this->w = 1.0; + this->x = 0.0; + this->y = 0.0; + this->z = 0.0; + } + else + { + this->w /= s; + this->x /= s; + this->y /= s; + this->z /= s; + } + } + + /// \brief Rotate a vector using the quaternion + /// \param[in] _vec vector to rotate + /// \return the rotated vector + public: inline Vector3 RotateVector(const Vector3 &_vec) const + { + Quaternion tmp(0.0, _vec.x, _vec.y, _vec.z); + tmp = (*this) * (tmp * this->GetInverse()); + return Vector3(tmp.x, tmp.y, tmp.z); + } + + /// \brief Stream insertion operator + /// \param[in] _out output stream + /// \param[in] _q quaternion to output + /// \return the stream + public: friend std::ostream &operator<<(std::ostream &_out, + const Quaternion &_q) + { + Vector3 v(_q.GetAsEuler()); + _out << v.x << " " << v.y << " " << v.z; + return _out; + } + + /// \brief Vector3 multiplication operator + /// \param[in] _v vector to multiply + public: Vector3 operator*(const Vector3 &_v) const + { + Vector3 uv, uuv; + Vector3 qvec(this->x, this->y, this->z); + uv = qvec.Cross(_v); + uuv = qvec.Cross(uv); + uv *= (2.0f * this->w); + uuv *= 2.0f; + + return _v + uv + uuv; + } + + /// \brief Stream extraction operator + /// \param[in] _in input stream + /// \param[in] _q Quaternion to read values into + /// \return The istream + public: friend std::istream &operator>>(std::istream &_in, + Quaternion &_q) + { + double roll, pitch, yaw; + + // Skip white spaces + _in.setf(std::ios_base::skipws); + _in >> roll >> pitch >> yaw; + + _q.SetFromEuler(Vector3(roll, pitch, yaw)); + + return _in; + } + + /// \brief Equal to operator + /// \param[in] _qt Quaternion for comparison + /// \return True if equal + public: bool operator ==(const Quaternion &_qt) const + { + return this->GetAsEuler() == _qt.GetAsEuler(); + } + + public: inline void Correct() + { + if (!std::isfinite(this->x)) + this->x = 0; + if (!std::isfinite(this->y)) + this->y = 0; + if (!std::isfinite(this->z)) + this->z = 0; + if (!std::isfinite(this->w)) + this->w = 1; + + if (equal(this->w, 0.0) && equal(this->x, 0.0) && + equal(this->y, 0.0) && equal(this->z, 0.0)) + { + this->w = 1; + } + } + + /// \brief x data + public: double x; + + /// \brief y data + public: double y; + + /// \brief z data + public: double z; + + /// \brief w data + public: double w; + } SDF_DEPRECATED(4.0); + + /// \deprecated Use ignition::math::Pose3d + /// \brief Encapsulates a position and rotation in three space + class SDFORMAT_VISIBLE Pose + { + /// \brief Constructor + public: Pose() + :pos(0, 0, 0), rot(1, 0, 0, 0) + {} + + /// \brief Constructor + /// \param[in] _pos A position + /// \param[in] _rot A rotation + public: Pose(Vector3 _pos, Quaternion _rot) + : pos(_pos), rot(_rot) {} + + /// \brief Constructor + /// \param[in] _x x position in meters. + /// \param[in] _y y position in meters. + /// \param[in] _z z position in meters. + /// \param[in] _roll Roll (rotation about X-axis) in radians. + /// \param[in] _pitch Pitch (rotation about y-axis) in radians. + /// \param[in] _yaw Yaw (rotation about z-axis) in radians. + public: Pose(double _x, double _y, double _z, + double _roll, double _pitch, double _yaw) + : pos(_x, _y, _z), rot(_roll, _pitch, _yaw) + { + rot.Correct(); + } + + /// \brief Stream insertion operator + /// \param out output stream + /// \param pose pose to output + /// \return the stream + public: friend std::ostream &operator<<(std::ostream &_out, + const Pose &_pose) + { + _out << _pose.pos << " " << _pose.rot; + return _out; + } + + /// \brief Stream extraction operator + /// \param[in] _in the input stream + /// \param[in] _pose the pose + /// \return the stream + public: friend std::istream &operator>>(std::istream &_in, + Pose &_pose) + { + // Skip white spaces + _in.setf(std::ios_base::skipws); + _in >> _pose.pos >> _pose.rot; + return _in; + } + + /// \brief Multiplication operator + /// \param[in] _pose the other pose + /// \return itself + public: Pose operator*(const Pose &pose) + { + return Pose(this->CoordPositionAdd(pose), pose.rot * this->rot); + } + + /// \brief Add one point to another: result = this + pose + /// \param[in] _pose The Pose to add + /// \return The resulting position + public: Vector3 CoordPositionAdd(const Pose &_pose) const + { + Quaternion tmp; + Vector3 result; + + // result = _pose.rot + _pose.rot * this->pos * _pose.rot! + tmp.w = 0.0; + tmp.x = this->pos.x; + tmp.y = this->pos.y; + tmp.z = this->pos.z; + + tmp = _pose.rot * (tmp * _pose.rot.GetInverse()); + + result.x = _pose.pos.x + tmp.x; + result.y = _pose.pos.y + tmp.y; + result.z = _pose.pos.z + tmp.z; + + return result; + } + + /// \brief Equality operator + /// \param[in] _pose Pose for comparison + /// \return True if equal + public: bool operator ==(const Pose &_pose) const + { + return this->pos == _pose.pos && this->rot == _pose.rot; + } + + /// \brief Position data + public: Vector3 pos; + + /// \brief Orientation data + public: Quaternion rot; + } SDF_DEPRECATED(4.0); + + /// \brief A Time class, can be used to hold wall- or sim-time. + /// stored as sec and nano-sec. + class SDFORMAT_VISIBLE Time + { + /// \brief Constructor + public: Time() + : sec(0), nsec(0) + { + } + + /// \brief Constructor + /// \param[in] _sec Seconds + /// \param[in] _nsec Nanoseconds + public: Time(int32_t _sec, int32_t _nsec) + : sec(_sec), nsec(_nsec) + { + } + + /// \brief Stream insertion operator + /// \param[in] _out the output stream + /// \param[in] _time time to write to the stream + /// \return the output stream + public: friend std::ostream &operator<<(std::ostream &_out, + const Time &_time) + { + _out << _time.sec << " " << _time.nsec; + return _out; + } + + /// \brief Stream extraction operator + /// \param[in] _in the input stream + /// \param[in] _time time to read from to the stream + /// \return the input stream + public: friend std::istream &operator>>(std::istream &_in, + Time &_time) + { + // Skip white spaces + _in.setf(std::ios_base::skipws); + _in >> _time.sec >> _time.nsec; + return _in; + } + + /// \brief Equal to operator. + /// \param[in] _time the time to compare to. + /// \return true if values are the same, false otherwise. + public: bool operator ==(const Time &_time) const + { + return this->sec == _time.sec && this->nsec == _time.nsec; + } + + /// \brief Seconds. + public: int32_t sec; + + /// \brief Nanoseconds. + public: int32_t nsec; + }; + + /// \brief A class for inertial information about a link. + class SDFORMAT_VISIBLE Inertia + { + public: double mass; + }; +} +#endif diff --git a/sdformat/include/sdf/parser.hh b/sdformat/include/sdf/parser.hh new file mode 100644 index 0000000..2d1c889 --- /dev/null +++ b/sdformat/include/sdf/parser.hh @@ -0,0 +1,122 @@ +/* + * Copyright 2012 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef _SDF_PARSER_HH_ +#define _SDF_PARSER_HH_ + +#include +#include + +#include "sdf/SDFImpl.hh" +#include "sdf/system_util.hh" + +/// \ingroup sdf_parser +/// \brief namespace for Simulation Description Format parser +namespace sdf +{ + /// \brief Init based on the installed sdf_format.xml file + SDFORMAT_VISIBLE + bool init(SDFPtr _sdf); + + // \brief Initialize the SDF interface using a file + SDFORMAT_VISIBLE + bool initFile(const std::string &_filename, SDFPtr _sdf); + + // \brief Initialize and SDFElement interface using a file + SDFORMAT_VISIBLE + bool initFile(const std::string &_filename, ElementPtr _sdf); + + // \brief Initialize the SDF interface using a string + SDFORMAT_VISIBLE + bool initString(const std::string &_xmlString, SDFPtr _sdf); + + // \brief Initialize the SDF interface using a TinyXML document + SDFORMAT_VISIBLE + bool initDoc(TiXmlDocument *_xmlDoc, SDFPtr _sdf); + + // \brief Initialize and SDF Element using a TinyXML document + SDFORMAT_VISIBLE + bool initDoc(TiXmlDocument *_xmlDoc, ElementPtr _sdf); + + // \brief For internal use only. Do not use this function. + SDFORMAT_VISIBLE + bool initXml(TiXmlElement *_xml, ElementPtr _sdf); + + /// \brief Populate the SDF values from a file + SDFORMAT_VISIBLE + bool readFile(const std::string &_filename, SDFPtr _sdf); + + /// \brief Populate the SDF values from a string + SDFORMAT_VISIBLE + bool readString(const std::string &_xmlString, SDFPtr _sdf); + + SDFORMAT_VISIBLE + bool readString(const std::string &_xmlString, ElementPtr _sdf); + + /// \brief Populate the SDF values from a TinyXML document + SDFORMAT_VISIBLE + bool readDoc(TiXmlDocument *_xmlDoc, SDFPtr _sdf, const std::string &_source); + + SDFORMAT_VISIBLE + bool readDoc(TiXmlDocument *_xmlDoc, ElementPtr _sdf, + const std::string &_source); + + // \brief For internal use only. Do not use this function. + SDFORMAT_VISIBLE + bool readXml(TiXmlElement *_xml, ElementPtr _sdf); + + /// \brief Get the best SDF version from models supported by this sdformat + /// \param[in] _modelXML XML element from config file pointing to the + /// model XML tag + /// \param[out] _modelFileName file name of the best model file + /// \return string with the best SDF version supported + SDFORMAT_VISIBLE + std::string getBestSupportedModelVersion(TiXmlElement *_modelXML, + std::string &_modelFileName); + + /// \brief Get the file path to the model file + /// \param[in] _modelDirPath directory system path of the model + /// \return string with the full filesystem path to the best version (greater + /// SDF protocol supported by this sdformat version) of the .sdf + /// model files hosted by _modelDirPath. + SDFORMAT_VISIBLE + std::string getModelFilePath(const std::string &_modelDirPath); + + SDFORMAT_VISIBLE + void copyChildren(ElementPtr _sdf, TiXmlElement *_xml); + + SDFORMAT_VISIBLE + void addNestedModel(ElementPtr _sdf, ElementPtr _includeSDF); + + /// \brief Convert an SDF file to a specific SDF version. + /// \param[in] _filename Name of the SDF file to convert. + /// \param[in] _version Version to convert _filename to. + /// \param[out] _sdf Pointer to the converted SDF document. + /// \return True on success. + SDFORMAT_VISIBLE + bool convertFile(const std::string &_filename, const std::string &_version, + SDFPtr _sdf); + + /// \brief Convert an SDF string to a specific SDF version. + /// \param[in] _sdfString The SDF string to convert. + /// \param[in] _version Version to convert _filename to. + /// \param[out] _sdf Pointer to the converted SDF document. + /// \return True on success. + SDFORMAT_VISIBLE + bool convertString(const std::string &_sdfString, + const std::string &_version, SDFPtr _sdf); +} +#endif diff --git a/sdformat/include/sdf/parser_urdf.hh b/sdformat/include/sdf/parser_urdf.hh new file mode 100644 index 0000000..3e6f519 --- /dev/null +++ b/sdformat/include/sdf/parser_urdf.hh @@ -0,0 +1,66 @@ +/* + * Copyright 2012 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef _SDFORMAT_URDF2SDF_HH_ +#define _SDFORMAT_URDF2SDF_HH_ + +#include +#include + +#include "sdf/Console.hh" +#include "sdf/system_util.hh" + +namespace sdf +{ + /// \brief URDF to SDF converter + class SDFORMAT_VISIBLE URDF2SDF + { + /// \brief constructor + public: URDF2SDF(); + + /// \brief destructor + public: ~URDF2SDF(); + + /// \brief convert urdf xml document string to sdf xml document + /// \param[in] _xmlDoc a tinyxml document containing the urdf model + /// \return a tinyxml document containing sdf of the model + public: TiXmlDocument InitModelDoc(TiXmlDocument* _xmlDoc); + + /// \brief convert urdf file to sdf xml document + /// \param[in] _urdfStr a string containing filename of the urdf model + /// \return a tinyxml document containing sdf of the model + public: TiXmlDocument InitModelFile(const std::string &_filename); + + /// \brief convert urdf string to sdf xml document, with option to enforce + /// limits. + /// \param[in] _urdfStr a string containing model urdf + /// \param[in] _enforceLimits option to enforce joint limits + /// \return a tinyxml document containing sdf of the model + public: TiXmlDocument InitModelString(const std::string &_urdfStr, + bool _enforceLimits = true); + + /// things that do not belong in urdf but should be mapped into sdf + /// @todo: do this using sdf definitions, not hard coded stuff + private: void ParseSDFExtension(TiXmlDocument &_urdfXml); + + /// list extensions for debugging + private: void ListSDFExtensions(); + + /// list extensions for debugging + private: void ListSDFExtensions(const std::string &_reference); + }; +} +#endif diff --git a/sdformat/include/sdf/sdf.hh.in b/sdformat/include/sdf/sdf.hh.in new file mode 100644 index 0000000..11fb7d6 --- /dev/null +++ b/sdformat/include/sdf/sdf.hh.in @@ -0,0 +1,3 @@ +// Automatically generated +${sdf_headers} +#include diff --git a/sdformat/include/sdf/system_util.hh b/sdformat/include/sdf/system_util.hh new file mode 100644 index 0000000..783416d --- /dev/null +++ b/sdformat/include/sdf/system_util.hh @@ -0,0 +1,53 @@ +/* + * Copyright 2013 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef _SDF_VISIBLE_HH_ +#define _SDF_VISIBLE_HH_ + +/** \def SDFORMAT_VISIBLE + * Use to represent "symbol visible" if supported + */ + +/** \def SDFORMAT_HIDDEN + * Use to represent "symbol hidden" if supported + */ + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef BUILDING_DLL + #ifdef __GNUC__ + #define SDFORMAT_VISIBLE __attribute__ ((dllexport)) + #else + #define SDFORMAT_VISIBLE __declspec(dllexport) + #endif + #else + #ifdef __GNUC__ + #define SDFORMAT_VISIBLE __attribute__ ((dllimport)) + #else + #define SDFORMAT_VISIBLE __declspec(dllimport) + #endif + #endif + #define SDFORMAT_HIDDEN +#else + #if __GNUC__ >= 4 + #define SDFORMAT_VISIBLE __attribute__ ((visibility ("default"))) + #define SDFORMAT_HIDDEN __attribute__ ((visibility ("hidden"))) + #else + #define SDFORMAT_VISIBLE + #define SDFORMAT_HIDDEN + #endif +#endif + +#endif /* SDFORMAT_VISIBLE_HH */ diff --git a/sdformat/sdf/1.0/CMakeLists.txt b/sdformat/sdf/1.0/CMakeLists.txt new file mode 100644 index 0000000..fb1b5fb --- /dev/null +++ b/sdformat/sdf/1.0/CMakeLists.txt @@ -0,0 +1,30 @@ +set (sdfs + actor.sdf + camera.sdf + collision.sdf + contact.sdf + gazebo.sdf + geometry.sdf + gripper.sdf + gui.sdf + inertial.sdf + joint.sdf + light.sdf + link.sdf + model.sdf + physics.sdf + plugin.sdf + projector.sdf + ray.sdf + rfidtag.sdf + rfid.sdf + road.sdf + scene.sdf + sensor.sdf + state.sdf + surface.sdf + visual.sdf + world.sdf +) + +install(FILES ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat/1.0/) diff --git a/sdformat/sdf/1.0/actor.sdf b/sdformat/sdf/1.0/actor.sdf new file mode 100644 index 0000000..6f76da4 --- /dev/null +++ b/sdformat/sdf/1.0/actor.sdf @@ -0,0 +1,40 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/camera.sdf b/sdformat/sdf/1.0/camera.sdf new file mode 100644 index 0000000..d369d97 --- /dev/null +++ b/sdformat/sdf/1.0/camera.sdf @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/collision.sdf b/sdformat/sdf/1.0/collision.sdf new file mode 100644 index 0000000..37bc58b --- /dev/null +++ b/sdformat/sdf/1.0/collision.sdf @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/contact.sdf b/sdformat/sdf/1.0/contact.sdf new file mode 100644 index 0000000..5446e31 --- /dev/null +++ b/sdformat/sdf/1.0/contact.sdf @@ -0,0 +1,6 @@ + + + + + + diff --git a/sdformat/sdf/1.0/distribution.sdf b/sdformat/sdf/1.0/distribution.sdf new file mode 100644 index 0000000..924c2f5 --- /dev/null +++ b/sdformat/sdf/1.0/distribution.sdf @@ -0,0 +1,19 @@ + + + The distribution tag specifies the local ID of this gazebo and port of the remote server. + + + The ID of the gazebo. + + + + The flag of the remote server. + + + + the port of the remote port + + + + + diff --git a/sdformat/sdf/1.0/event.sdf b/sdformat/sdf/1.0/event.sdf new file mode 100644 index 0000000..16d5c20 --- /dev/null +++ b/sdformat/sdf/1.0/event.sdf @@ -0,0 +1,21 @@ + + + The parallel tag specifies the numbers of threads and tbb size of the block. + + + The type of parallel. + + + + The numbers of the threads. + + + + the size of block to tbb thread + + + + the type to block partion + + + diff --git a/sdformat/sdf/1.0/gazebo.sdf b/sdformat/sdf/1.0/gazebo.sdf new file mode 100644 index 0000000..bec9cc5 --- /dev/null +++ b/sdformat/sdf/1.0/gazebo.sdf @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/sdformat/sdf/1.0/gazeboid.sdf b/sdformat/sdf/1.0/gazeboid.sdf new file mode 100644 index 0000000..4cb7ae3 --- /dev/null +++ b/sdformat/sdf/1.0/gazeboid.sdf @@ -0,0 +1,17 @@ + + + The distributed tag specifies the ip and ID of the local gazebo. + + + The type of the distribution(0:client or 1:server). + + + + The ip of the local gazebo. + + + + model name in the local gazebo. + + + diff --git a/sdformat/sdf/1.0/geometry.sdf b/sdformat/sdf/1.0/geometry.sdf new file mode 100644 index 0000000..f4d376f --- /dev/null +++ b/sdformat/sdf/1.0/geometry.sdf @@ -0,0 +1,43 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/gripper.sdf b/sdformat/sdf/1.0/gripper.sdf new file mode 100644 index 0000000..e000759 --- /dev/null +++ b/sdformat/sdf/1.0/gripper.sdf @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/gui.sdf b/sdformat/sdf/1.0/gui.sdf new file mode 100644 index 0000000..c99d556 --- /dev/null +++ b/sdformat/sdf/1.0/gui.sdf @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/inertial.sdf b/sdformat/sdf/1.0/inertial.sdf new file mode 100644 index 0000000..ff424c9 --- /dev/null +++ b/sdformat/sdf/1.0/inertial.sdf @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/joint.sdf b/sdformat/sdf/1.0/joint.sdf new file mode 100644 index 0000000..5dcc7d5 --- /dev/null +++ b/sdformat/sdf/1.0/joint.sdf @@ -0,0 +1,63 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/light.sdf b/sdformat/sdf/1.0/light.sdf new file mode 100644 index 0000000..7e48c52 --- /dev/null +++ b/sdformat/sdf/1.0/light.sdf @@ -0,0 +1,37 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/link.sdf b/sdformat/sdf/1.0/link.sdf new file mode 100644 index 0000000..c07ffe9 --- /dev/null +++ b/sdformat/sdf/1.0/link.sdf @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/model.sdf b/sdformat/sdf/1.0/model.sdf new file mode 100644 index 0000000..f6ef09b --- /dev/null +++ b/sdformat/sdf/1.0/model.sdf @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/physics.sdf b/sdformat/sdf/1.0/physics.sdf new file mode 100644 index 0000000..4dba912 --- /dev/null +++ b/sdformat/sdf/1.0/physics.sdf @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/plugin.sdf b/sdformat/sdf/1.0/plugin.sdf new file mode 100644 index 0000000..f2c835d --- /dev/null +++ b/sdformat/sdf/1.0/plugin.sdf @@ -0,0 +1,6 @@ + + + + + + diff --git a/sdformat/sdf/1.0/projector.sdf b/sdformat/sdf/1.0/projector.sdf new file mode 100644 index 0000000..e951f5a --- /dev/null +++ b/sdformat/sdf/1.0/projector.sdf @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/sdformat/sdf/1.0/ray.sdf b/sdformat/sdf/1.0/ray.sdf new file mode 100644 index 0000000..10475e2 --- /dev/null +++ b/sdformat/sdf/1.0/ray.sdf @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/rfid.sdf b/sdformat/sdf/1.0/rfid.sdf new file mode 100644 index 0000000..61351dd --- /dev/null +++ b/sdformat/sdf/1.0/rfid.sdf @@ -0,0 +1,2 @@ + + diff --git a/sdformat/sdf/1.0/rfidtag.sdf b/sdformat/sdf/1.0/rfidtag.sdf new file mode 100644 index 0000000..55699dc --- /dev/null +++ b/sdformat/sdf/1.0/rfidtag.sdf @@ -0,0 +1,2 @@ + + diff --git a/sdformat/sdf/1.0/road.sdf b/sdformat/sdf/1.0/road.sdf new file mode 100644 index 0000000..877c43c --- /dev/null +++ b/sdformat/sdf/1.0/road.sdf @@ -0,0 +1,6 @@ + + + + + + diff --git a/sdformat/sdf/1.0/scene.sdf b/sdformat/sdf/1.0/scene.sdf new file mode 100644 index 0000000..1e921a2 --- /dev/null +++ b/sdformat/sdf/1.0/scene.sdf @@ -0,0 +1,29 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/sensor.sdf b/sdformat/sdf/1.0/sensor.sdf new file mode 100644 index 0000000..f30fa55 --- /dev/null +++ b/sdformat/sdf/1.0/sensor.sdf @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/state.sdf b/sdformat/sdf/1.0/state.sdf new file mode 100644 index 0000000..b2145a4 --- /dev/null +++ b/sdformat/sdf/1.0/state.sdf @@ -0,0 +1,28 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/surface.sdf b/sdformat/sdf/1.0/surface.sdf new file mode 100644 index 0000000..256443c --- /dev/null +++ b/sdformat/sdf/1.0/surface.sdf @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/visual.sdf b/sdformat/sdf/1.0/visual.sdf new file mode 100644 index 0000000..502c9f6 --- /dev/null +++ b/sdformat/sdf/1.0/visual.sdf @@ -0,0 +1,35 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.0/world.sdf b/sdformat/sdf/1.0/world.sdf new file mode 100644 index 0000000..a0223ad --- /dev/null +++ b/sdformat/sdf/1.0/world.sdf @@ -0,0 +1,66 @@ + + The world element encapsulates an entire world description including: models, scene, physics, joints, and plugins + + + Unique name of the world + + + + Global audio properties. + + + Device to use for audio playback. A value of "default" will use the system's default audio device. Otherwise, specify a an audio device file" + + + + + The wind tag specifies the type and properties of the wind. + + + Linear velocity of the wind. + + + + + Include resources from a URI + + URI to a resource, such as a model + + + + Override the name of the included model. + + + + Override the static value of the included model. + + + + + + + The gravity vector in m/s^2, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + The magnetic vector in Tesla, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.2/1_0.convert b/sdformat/sdf/1.2/1_0.convert new file mode 100644 index 0000000..6bc4cff --- /dev/null +++ b/sdformat/sdf/1.2/1_0.convert @@ -0,0 +1,1462 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + background/sky/rgba + background/sky/material + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.2/CMakeLists.txt b/sdformat/sdf/1.2/CMakeLists.txt new file mode 100644 index 0000000..e4a15b3 --- /dev/null +++ b/sdformat/sdf/1.2/CMakeLists.txt @@ -0,0 +1,31 @@ +set (sdfs + 1_0.convert + actor.sdf + camera.sdf + collision.sdf + contact.sdf + gazebo.sdf + geometry.sdf + gripper.sdf + gui.sdf + inertial.sdf + joint.sdf + light.sdf + link.sdf + model.sdf + physics.sdf + plugin.sdf + projector.sdf + ray.sdf + rfidtag.sdf + rfid.sdf + road.sdf + scene.sdf + sensor.sdf + state.sdf + surface.sdf + visual.sdf + world.sdf +) + +install(FILES ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat/1.2) diff --git a/sdformat/sdf/1.2/actor.sdf b/sdformat/sdf/1.2/actor.sdf new file mode 100644 index 0000000..d90c523 --- /dev/null +++ b/sdformat/sdf/1.2/actor.sdf @@ -0,0 +1,88 @@ + + + + + + + + + + + + + + Origin of the actor + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.2/camera.sdf b/sdformat/sdf/1.2/camera.sdf new file mode 100644 index 0000000..0de2b24 --- /dev/null +++ b/sdformat/sdf/1.2/camera.sdf @@ -0,0 +1,50 @@ + + These elements are specific to camera sensors. + + + Horizontal field of view + + + + The image size in pixels and format. + + Width in pixels + + + Height in pixels + + + (L8|R8G8B8|B8G8R8|BAYER_RGGB8|BAYER_BGGR8|BAYER_GBRG8|BAYER_GRBG8) + + + + + The near and far clip planes. Objects closer or farther than these planes are not rendered. + + + Near clipping plane + + + + Far clipping plane + + + + + Enable or disable saving of camera frames. + + True = saving enabled + + + The path name which will hold the frame data. If path name is relative, then directory is relative to current working directory. + + + + + Depth camera parameters + + Type of output + + + + diff --git a/sdformat/sdf/1.2/collision.sdf b/sdformat/sdf/1.2/collision.sdf new file mode 100644 index 0000000..051732d --- /dev/null +++ b/sdformat/sdf/1.2/collision.sdf @@ -0,0 +1,24 @@ + + + The collision properties of a link. Note that this can be different from the visual properties of a link, for example, simpler collision models are often used to reduce computation time. + + + Unique name for the collision element within the scope of the parent link. + + + + intensity value returned by laser sensor. + + + + Maximum number of contacts allowed between two entities. This value overrides the max_contacts element defined in physics. + + + + The reference frame of the collision element, relative to the reference frame of the link. + + + + + + diff --git a/sdformat/sdf/1.2/contact.sdf b/sdformat/sdf/1.2/contact.sdf new file mode 100644 index 0000000..d1cde50 --- /dev/null +++ b/sdformat/sdf/1.2/contact.sdf @@ -0,0 +1,12 @@ + + These elements are specific to the contact sensor. + + + name of the collision element within a link that acts as the contact sensor. + + + + Topic on which contact data is published. + + + diff --git a/sdformat/sdf/1.2/distribution.sdf b/sdformat/sdf/1.2/distribution.sdf new file mode 100644 index 0000000..924c2f5 --- /dev/null +++ b/sdformat/sdf/1.2/distribution.sdf @@ -0,0 +1,19 @@ + + + The distribution tag specifies the local ID of this gazebo and port of the remote server. + + + The ID of the gazebo. + + + + The flag of the remote server. + + + + the port of the remote port + + + + + diff --git a/sdformat/sdf/1.2/event.sdf b/sdformat/sdf/1.2/event.sdf new file mode 100644 index 0000000..16d5c20 --- /dev/null +++ b/sdformat/sdf/1.2/event.sdf @@ -0,0 +1,21 @@ + + + The parallel tag specifies the numbers of threads and tbb size of the block. + + + The type of parallel. + + + + The numbers of the threads. + + + + the size of block to tbb thread + + + + the type to block partion + + + diff --git a/sdformat/sdf/1.2/gazebo.sdf b/sdformat/sdf/1.2/gazebo.sdf new file mode 100644 index 0000000..b4a7b71 --- /dev/null +++ b/sdformat/sdf/1.2/gazebo.sdf @@ -0,0 +1,13 @@ + + Gazebo SDF base element. + + + Version number of the SDF format. + + + + + + + + diff --git a/sdformat/sdf/1.2/gazeboid.sdf b/sdformat/sdf/1.2/gazeboid.sdf new file mode 100644 index 0000000..4cb7ae3 --- /dev/null +++ b/sdformat/sdf/1.2/gazeboid.sdf @@ -0,0 +1,17 @@ + + + The distributed tag specifies the ip and ID of the local gazebo. + + + The type of the distribution(0:client or 1:server). + + + + The ip of the local gazebo. + + + + model name in the local gazebo. + + + diff --git a/sdformat/sdf/1.2/geometry.sdf b/sdformat/sdf/1.2/geometry.sdf new file mode 100644 index 0000000..e47b142 --- /dev/null +++ b/sdformat/sdf/1.2/geometry.sdf @@ -0,0 +1,105 @@ + + + The shape of the visual or collision object. + + + Box shape + + The three side lengths of the box. The origin of the box is in its geometric center (inside the center of the box). + + + + + Sphere shape + + radius of the sphere + + + + + Cylinder shape + + Radius of the cylinder + + + Length of the cylinder + + + + + Mesh shape + + Mesh filename. DEPRECATED + + + Mesh uri + + + Scaling factor applied to the mesh + + + + + Plane shape + + Normal direction for the plane + + + Length of each side of the plane + + + + + Extrude a set of boxes from a grayscale image. + + URI of the grayscale image file + + + Scaling factor applied to the image + + + Grayscale threshold + + + Height of the extruded boxes + + + The amount of error in the model + + + + + A heightmap based on a 2d grayscale image. + + URI to a grayscale image file + + + The size of the heightmap in world units + + + A position offset. + + + + The heightmap can contain multiple textures. The order of the texture matters. The first texture will appear at the lowest height, and the last texture at the highest height. Use blend to control the height thresholds and fade between textures. + + Size of the applied texture in meters. + + + Diffuse texture image filename + + + Normalmap texture image filename + + + + The blend tag controls how two adjacent textures are mixed. The number of blend elements should equal one less than the number of textures. + + Min height of a blend layer + + + Distance over which the blend occurs + + + + diff --git a/sdformat/sdf/1.2/gripper.sdf b/sdformat/sdf/1.2/gripper.sdf new file mode 100644 index 0000000..12fd0b3 --- /dev/null +++ b/sdformat/sdf/1.2/gripper.sdf @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.2/gui.sdf b/sdformat/sdf/1.2/gui.sdf new file mode 100644 index 0000000..8300090 --- /dev/null +++ b/sdformat/sdf/1.2/gui.sdf @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.2/inertial.sdf b/sdformat/sdf/1.2/inertial.sdf new file mode 100644 index 0000000..417489f --- /dev/null +++ b/sdformat/sdf/1.2/inertial.sdf @@ -0,0 +1,34 @@ + + + The inertial properties of the link. + + + The mass of the link. + + + + This is the pose of the inertial reference frame, relative to the link reference frame. The origin of the inertial reference frame needs to be at the center of gravity. The axes of the inertial reference frame do not need to be aligned with the principal axes of the inertia. + + + + The 3x3 rotational inertia matrix. Because the rotational inertia matrix is symmetric, only 6 above-diagonal elements of this matrix are specified here, using the attributes ixx, ixy, ixz, iyy, iyz, izz. + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.2/joint.sdf b/sdformat/sdf/1.2/joint.sdf new file mode 100644 index 0000000..8caedcb --- /dev/null +++ b/sdformat/sdf/1.2/joint.sdf @@ -0,0 +1,133 @@ + + + A joint connections two links with kinematic and dynamic properties. + + + A unique name for the joint within the scope of the model. + + + + The type of joint, which must be one of the following: (revolute) a hinge joint that rotates on a single axis with either a fixed or continuous range of motion, (revolute2) same as two revolute joints connected in series, (prismatic) a sliding joint that slides along an axis with a limited range specified by upper and lower limits, (ball) a ball and socket joint, (universal), like a ball joint, but constrains one degree of freedom, (piston) similar to a Slider joint except that rotation around the translation axis is possible. + + + + Name of the parent link + + + + Name of the child link + + + + offset from child link origin in child link frame. + + + + + + + + The joint axis specified in the model frame. This is the axis of rotation for revolute joints, the axis of translation for prismatic joints. The axis is currently specified in the model frame of reference, but this will be changed to the joint frame in future version of sdf (see gazebo issue #494). + + Represents the x,y,z components of a vector. The vector should be normalized. + + + An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation. + + The physical velocity dependent viscous damping coefficient of the joint. + + + The physical static friction value of the joint. + + + + specifies the limits of this joint + + An attribute specifying the lower joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute specifying the upper joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + (not implemented) An attribute for enforcing the maximum joint effort. + + + (not implemented) An attribute for enforcing the maximum joint velocity. + + + + + + The second joint axis specified in the model frame. This is the second axis of rotation for revolute2 joints and universal joints. The axis is currently specified in the model frame of reference, but this will be changed to the joint frame in future version of sdf (see gazebo issue #494). + + Represents the x,y,z components of a vector. The vector should be normalized. + + + An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation. + + The physical velocity dependent viscous damping coefficient of the joint. + + + The physical static friction value of the joint. + + + + + + + An attribute specifying the lower joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute specifying the upper joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + (not implemented) An attribute for enforcing the maximum joint effort. + + + (not implemented) An attribute for enforcing the maximum joint velocity. + + + + + + Parameters that are specific to a certain physics engine. + + ODE specific parameters + + Scale the excess for in a joint motor at joint limits. Should be between zero and one. + + + Constraint force mixing used when not at a stop + + + Bounciness of the limits + + + Maximum force or torque used to reach the desired velocity. + + + The desired velocity of the joint. Should only be set if you want the joint to move on load. + + + + + + Constraint force mixing parameter used by the joint stop + + + Error reduction parameter used by the joint stop + + + + + + + Suspension constraint force mixing parameter + + + Suspension error reduction parameter + + + + + diff --git a/sdformat/sdf/1.2/light.sdf b/sdformat/sdf/1.2/light.sdf new file mode 100644 index 0000000..745308c --- /dev/null +++ b/sdformat/sdf/1.2/light.sdf @@ -0,0 +1,61 @@ + + + The light element describes a light source. + + + A unique name for the light. + + + + The light type: point, directional, spot. + + + + When true, the light will cast shadows. + + + + A position and orientation in the global coordinate frame for the light. + + + + Diffuse light color + + + Specular light color + + + + Light attenuation + + Range of the light + + + The linear attenuation factor: 1 means attenuate evenly over the distance. + + + The constant attenuation factor: 1.0 means never attenuate, 0.0 is complete attenutation. + + + The quadratic attenuation factor: adds a curvature to the attenuation. + + + + + Direction of the light, only applicable for spot and directional lights. + + + + Spot light parameters + + Angle covered by the bright inner cone + + + Angle covered by the outer cone + + + The rate of falloff between the inner and outer cones. 1.0 means a linear falloff, less means slower falloff, higher means faster falloff. + + + + diff --git a/sdformat/sdf/1.2/link.sdf b/sdformat/sdf/1.2/link.sdf new file mode 100644 index 0000000..24f7a3c --- /dev/null +++ b/sdformat/sdf/1.2/link.sdf @@ -0,0 +1,41 @@ + + + A physical link with inertia, collision, and visual properties. A link must be a child of a model, and any number of links may exist in a model. + + + A unique name for the link within the scope of the model. + + + + If true, the link is affected by gravity. + + + + If true, the link can collide with other links in the model. + + + + If true, the link is kinematic only + + + + This is the pose of the link reference frame, relative to the model reference frame. + + + + Exponential damping of the link's velocity. + + Linear damping + + + Angular damping + + + + + + + + + + diff --git a/sdformat/sdf/1.2/model.sdf b/sdformat/sdf/1.2/model.sdf new file mode 100644 index 0000000..2ec8b59 --- /dev/null +++ b/sdformat/sdf/1.2/model.sdf @@ -0,0 +1,26 @@ + + + The model element defines a complete robot or any other physical object. + + + A unique name for the model. This name must not match another model in the world. + + + + If set to true, the model is immovable. Otherwise the model is simulated in the dynamics engine. + + + + Allows a model to auto-disable, which is means the physics engine can skip updating the model when the model is at rest. This parameter is only used by models with no joints. + + + + A position and orientation in the global coordinate frame for the model. Position(x,y,z) and rotation (roll, pitch yaw) in the global coordinate frame. + + + + + + + + diff --git a/sdformat/sdf/1.2/physics.sdf b/sdformat/sdf/1.2/physics.sdf new file mode 100644 index 0000000..5db00e7 --- /dev/null +++ b/sdformat/sdf/1.2/physics.sdf @@ -0,0 +1,65 @@ + + + The physics tag specifies the type and properties of the dynamics engine. + + + The type of the dynamics engine. Currently must be set to ode + + + + Rate at which to update the physics engine + + + + Maximum number of contacts allowed between two entities. This value can be over ridden by a max_contacts element in a collision element. + + + + The gravity vector + + + + Bullet specific physics properties + + Time step + + + + + ODE specific physics properties + + + + One of the following types: world, quick + + + The time duration which advances with each iteration of the dynamics engine. + + + Number of iterations for each step. A higher number produces greater accuracy at a performance cost. + + + + + + Set the successive over-relaxation parameter. + + + + + + + Constraint force mixing parameter. See the ODE page for more information. + + + Error reduction parameter. See the ODE page for more information. + + + The maximum correcting velocities allowed when resolving contacts. + + + The depth of the surface layer around all geometry objects. Contacts are allowed to sink into the surface layer up to the given depth before coming to rest. The default value is zero. Increasing this to some small value (e.g. 0.001) can help prevent jittering problems due to contacts being repeatedly made and broken. + + + + diff --git a/sdformat/sdf/1.2/plugin.sdf b/sdformat/sdf/1.2/plugin.sdf new file mode 100644 index 0000000..26405ff --- /dev/null +++ b/sdformat/sdf/1.2/plugin.sdf @@ -0,0 +1,13 @@ + + + A plugin is a dynamically loaded chunk of code. It can exist as a child of world, model, and sensor. + + A unique name for the plugin, scoped to its parent. + + + Name of the shared library to load. If the filename is not a full path name, the file will be searched for in the configuration paths. + + + This is a special element that should not be specified in an SDF file. It automatically copies child elements into the SDF element so that a plugin can access the data. + + diff --git a/sdformat/sdf/1.2/projector.sdf b/sdformat/sdf/1.2/projector.sdf new file mode 100644 index 0000000..9eabca9 --- /dev/null +++ b/sdformat/sdf/1.2/projector.sdf @@ -0,0 +1,32 @@ + + + + Name of the projector + + + + Texture name + + + + Pose of the projector + + + + + Field of view + + + + + Near clip distance + + + + + far clip distance + + + + + diff --git a/sdformat/sdf/1.2/ray.sdf b/sdformat/sdf/1.2/ray.sdf new file mode 100644 index 0000000..c56c993 --- /dev/null +++ b/sdformat/sdf/1.2/ray.sdf @@ -0,0 +1,60 @@ + + These elements are specific to the ray (laser) sensor. + + + + + + + + The number of simulated rays to generate per complete laser sweep cycle. + + + + This number is multiplied by samples to determine the number of range data points returned. If resolution is less than one, range data is interpolated. If resolution is greater than one, range data is averaged. + + + + + + + + Must be greater or equal to min_angle + + + + + + + + The number of simulated rays to generate per complete laser sweep cycle. + + + + This number is multiplied by samples to determine the number of range data points returned. If resolution is less than one, range data is interpolated. If resolution is greater than one, range data is averaged. + + + + + + + + Must be greater or equal to min_angle + + + + + + + specifies range properties of each simulated ray + + The minimum distance for each ray. + + + The maximum distance for each ray. + + + Linear resolution of each ray. + + + diff --git a/sdformat/sdf/1.2/rfid.sdf b/sdformat/sdf/1.2/rfid.sdf new file mode 100644 index 0000000..61351dd --- /dev/null +++ b/sdformat/sdf/1.2/rfid.sdf @@ -0,0 +1,2 @@ + + diff --git a/sdformat/sdf/1.2/rfidtag.sdf b/sdformat/sdf/1.2/rfidtag.sdf new file mode 100644 index 0000000..55699dc --- /dev/null +++ b/sdformat/sdf/1.2/rfidtag.sdf @@ -0,0 +1,2 @@ + + diff --git a/sdformat/sdf/1.2/road.sdf b/sdformat/sdf/1.2/road.sdf new file mode 100644 index 0000000..3549b24 --- /dev/null +++ b/sdformat/sdf/1.2/road.sdf @@ -0,0 +1,15 @@ + + + + Name of the road + + + + Width of the road + + + + A series of points define the path of the road. + + + diff --git a/sdformat/sdf/1.2/scene.sdf b/sdformat/sdf/1.2/scene.sdf new file mode 100644 index 0000000..7fc76ec --- /dev/null +++ b/sdformat/sdf/1.2/scene.sdf @@ -0,0 +1,78 @@ + + + Specifies the look of the environment. + + + Color of the ambient light. + + + + Color of the background. + + + + Properties for the sky + + Time of day [0..24] + + + Sunrise time [0..24] + + + Sunset time [0..24] + + + + Sunset time [0..24] + + Speed of the clouds + + + + Direction of the cloud movement + + + Density of clouds + + + + Average size of the clouds + + + + Ambient cloud color + + + + + + Enable/disable shadows + + + + Controls fog + + Fog color + + + Fog type: constant, linear, quadratic + + + Distance to start of fog + + + Distance to end of fog + + + Density of fog + + + + + Enable/disable the grid + + + diff --git a/sdformat/sdf/1.2/sensor.sdf b/sdformat/sdf/1.2/sensor.sdf new file mode 100644 index 0000000..75dafc4 --- /dev/null +++ b/sdformat/sdf/1.2/sensor.sdf @@ -0,0 +1,40 @@ + + + The sensor tag describes the type and properties of a sensor. + + + A unique name for the sensor. This name must not match another model in the model. + + + + The type name of the sensor. By default, gazebo supports types camera, depth, stereocamera, contact, imu, ir and ray. + + + + If true the sensor will always be updated according to the update rate. + + + + The frequency at which the sensor data is generated. If left unspecified, the sensor will generate data every cycle. + + + + If true, the sensor is visualized in the GUI + + + + This is the pose of the sensor, relative to the parent link reference frame. + + + + Name of the topic on which data is published. This is necessary for visualization + + + + + + + + + + diff --git a/sdformat/sdf/1.2/server.sdf b/sdformat/sdf/1.2/server.sdf new file mode 100644 index 0000000..47d1606 --- /dev/null +++ b/sdformat/sdf/1.2/server.sdf @@ -0,0 +1,29 @@ + + + The distributed tag specifies the ip and port of the remote server. + + + The type of the distribution(0:client or 1:server). + + + + The ip of the remote server. + + + + The flag of the remote server. + + + + the port of the remote port + + + + the port of the remote port + + + + the port of the remote port + + + diff --git a/sdformat/sdf/1.2/state.sdf b/sdformat/sdf/1.2/state.sdf new file mode 100644 index 0000000..912898b --- /dev/null +++ b/sdformat/sdf/1.2/state.sdf @@ -0,0 +1,53 @@ + + + + + Name of the world this state applies to + + + + Time stamp of the state [seconds nanoseconds] + + + + + Model state + + + Name of the model + + + + Pose of the model + + + + + Link state + + + Name of the link + + + + Pose of the link relative to the model + + + + Velocity of the link + + + + + Force applied to the link + + Position of the force. + + + Magnitude of the force. + + + + + + diff --git a/sdformat/sdf/1.2/surface.sdf b/sdformat/sdf/1.2/surface.sdf new file mode 100644 index 0000000..7dcbfb0 --- /dev/null +++ b/sdformat/sdf/1.2/surface.sdf @@ -0,0 +1,59 @@ + + The surface parameters + + + + Bounciness coefficient of restitution, from [0...1], where 0=no bounciness. + + + Bounce velocity threshold, below which effective coefficient of restitution is 0. + + + + + + + ODE friction parameters + + Coefficient of friction in the range of [0..1]. + + + Second coefficient of friction in the range of [0..1] + + + 3-tuple specifying direction of mu1 in the collision local reference frame. + + + Force dependent slip direction 1 in collision local frame, between the range of [0..1]. + + + Force dependent slip direction 2 in collision local frame, between the range of [0..1]. + + + + + + + + ODE contact parameters + + Soft constraint force mixing. + + + Soft error reduction parameter + + + dynamically "stiffness"-equivalent coefficient for contact joints + + + dynamically "damping"-equivalent coefficient for contact joints + + + maximum contact correction velocity truncation term. + + + minimum allowable depth before contact correction impulse is applied + + + + diff --git a/sdformat/sdf/1.2/urdf.sdf b/sdformat/sdf/1.2/urdf.sdf new file mode 100644 index 0000000..6068d5c --- /dev/null +++ b/sdformat/sdf/1.2/urdf.sdf @@ -0,0 +1,19 @@ + + + The robot element defines a complete robot or any other physical object using URDF. + + + A unique name for the model. This name must not match another model in the world. + + + + A position and orientation in the global coordinate frame for the model. Position(x,y,z) and rotation (roll, pitch yaw) in the global coordinate frame. + + + + + + + + + diff --git a/sdformat/sdf/1.2/visual.sdf b/sdformat/sdf/1.2/visual.sdf new file mode 100644 index 0000000..475dfb4 --- /dev/null +++ b/sdformat/sdf/1.2/visual.sdf @@ -0,0 +1,70 @@ + + + The visual properties of the link. This element specifies the shape of the object (box, cylinder, etc.) for visualization purposes. + + + Unique name for the visual element within the scope of the parent link. + + + + If true the visual will cast shadows. + + + + will be implemented in the future release. + + + + The amount of transparency( 0=opaque, 1 = fully transparent) + + + + Origin of the visual relative to its parent. + + + + The material of the visual element. + + + Name of material from an installed script file. This will override the color element if the script exists. + + + URI of the material script file + + + + Name of the script within the script file + + + + + + + + vertex, pixel, normal_map_objectspace, normal_map_tangentspace + + + + filename of the normal map + + + + + The ambient color of a material specified by set of four numbers representing red/green/blue, each in the range of [0,1]. + + + + The diffuse color of a material specified by set of four numbers representing red/green/blue/alpha, each in the range of [0,1]. + + + + The specular color of a material specified by set of four numbers representing red/green/blue/alpha, each in the range of [0,1]. + + + + The emissive color of a material specified by set of four numbers representing red/green/blue, each in the range of [0,1]. + + + + + diff --git a/sdformat/sdf/1.2/world.sdf b/sdformat/sdf/1.2/world.sdf new file mode 100644 index 0000000..a0223ad --- /dev/null +++ b/sdformat/sdf/1.2/world.sdf @@ -0,0 +1,66 @@ + + The world element encapsulates an entire world description including: models, scene, physics, joints, and plugins + + + Unique name of the world + + + + Global audio properties. + + + Device to use for audio playback. A value of "default" will use the system's default audio device. Otherwise, specify a an audio device file" + + + + + The wind tag specifies the type and properties of the wind. + + + Linear velocity of the wind. + + + + + Include resources from a URI + + URI to a resource, such as a model + + + + Override the name of the included model. + + + + Override the static value of the included model. + + + + + + + The gravity vector in m/s^2, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + The magnetic vector in Tesla, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.3/1_2.convert b/sdformat/sdf/1.3/1_2.convert new file mode 100644 index 0000000..7eae5f7 --- /dev/null +++ b/sdformat/sdf/1.3/1_2.convert @@ -0,0 +1,2 @@ + + diff --git a/sdformat/sdf/1.3/CMakeLists.txt b/sdformat/sdf/1.3/CMakeLists.txt new file mode 100644 index 0000000..6eecf92 --- /dev/null +++ b/sdformat/sdf/1.3/CMakeLists.txt @@ -0,0 +1,32 @@ +set (sdfs + 1_2.convert + actor.sdf + camera.sdf + collision.sdf + contact.sdf + geometry.sdf + gripper.sdf + gui.sdf + imu.sdf + inertial.sdf + joint.sdf + light.sdf + link.sdf + model.sdf + physics.sdf + plugin.sdf + projector.sdf + ray.sdf + rfidtag.sdf + rfid.sdf + road.sdf + root.sdf + scene.sdf + sensor.sdf + state.sdf + surface.sdf + visual.sdf + world.sdf +) + +install(FILES ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat/1.3) diff --git a/sdformat/sdf/1.3/actor.sdf b/sdformat/sdf/1.3/actor.sdf new file mode 100644 index 0000000..d90c523 --- /dev/null +++ b/sdformat/sdf/1.3/actor.sdf @@ -0,0 +1,88 @@ + + + + + + + + + + + + + + Origin of the actor + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.3/camera.sdf b/sdformat/sdf/1.3/camera.sdf new file mode 100644 index 0000000..0983c8b --- /dev/null +++ b/sdformat/sdf/1.3/camera.sdf @@ -0,0 +1,58 @@ + + These elements are specific to camera sensors. + + + An optional name for the camera. + + + + A position and orientation in the parent coordinate frame for the camera. + + + + Horizontal field of view + + + + The image size in pixels and format. + + Width in pixels + + + Height in pixels + + + (L8|R8G8B8|B8G8R8|BAYER_RGGB8|BAYER_BGGR8|BAYER_GBRG8|BAYER_GRBG8) + + + + + The near and far clip planes. Objects closer or farther than these planes are not rendered. + + + Near clipping plane + + + + Far clipping plane + + + + + Enable or disable saving of camera frames. + + True = saving enabled + + + The path name which will hold the frame data. If path name is relative, then directory is relative to current working directory. + + + + + Depth camera parameters + + Type of output + + + + diff --git a/sdformat/sdf/1.3/collision.sdf b/sdformat/sdf/1.3/collision.sdf new file mode 100644 index 0000000..051732d --- /dev/null +++ b/sdformat/sdf/1.3/collision.sdf @@ -0,0 +1,24 @@ + + + The collision properties of a link. Note that this can be different from the visual properties of a link, for example, simpler collision models are often used to reduce computation time. + + + Unique name for the collision element within the scope of the parent link. + + + + intensity value returned by laser sensor. + + + + Maximum number of contacts allowed between two entities. This value overrides the max_contacts element defined in physics. + + + + The reference frame of the collision element, relative to the reference frame of the link. + + + + + + diff --git a/sdformat/sdf/1.3/contact.sdf b/sdformat/sdf/1.3/contact.sdf new file mode 100644 index 0000000..d1cde50 --- /dev/null +++ b/sdformat/sdf/1.3/contact.sdf @@ -0,0 +1,12 @@ + + These elements are specific to the contact sensor. + + + name of the collision element within a link that acts as the contact sensor. + + + + Topic on which contact data is published. + + + diff --git a/sdformat/sdf/1.3/distribution.sdf b/sdformat/sdf/1.3/distribution.sdf new file mode 100644 index 0000000..924c2f5 --- /dev/null +++ b/sdformat/sdf/1.3/distribution.sdf @@ -0,0 +1,19 @@ + + + The distribution tag specifies the local ID of this gazebo and port of the remote server. + + + The ID of the gazebo. + + + + The flag of the remote server. + + + + the port of the remote port + + + + + diff --git a/sdformat/sdf/1.3/event.sdf b/sdformat/sdf/1.3/event.sdf new file mode 100644 index 0000000..16d5c20 --- /dev/null +++ b/sdformat/sdf/1.3/event.sdf @@ -0,0 +1,21 @@ + + + The parallel tag specifies the numbers of threads and tbb size of the block. + + + The type of parallel. + + + + The numbers of the threads. + + + + the size of block to tbb thread + + + + the type to block partion + + + diff --git a/sdformat/sdf/1.3/gazeboid.sdf b/sdformat/sdf/1.3/gazeboid.sdf new file mode 100644 index 0000000..4cb7ae3 --- /dev/null +++ b/sdformat/sdf/1.3/gazeboid.sdf @@ -0,0 +1,17 @@ + + + The distributed tag specifies the ip and ID of the local gazebo. + + + The type of the distribution(0:client or 1:server). + + + + The ip of the local gazebo. + + + + model name in the local gazebo. + + + diff --git a/sdformat/sdf/1.3/geometry.sdf b/sdformat/sdf/1.3/geometry.sdf new file mode 100644 index 0000000..1d510cc --- /dev/null +++ b/sdformat/sdf/1.3/geometry.sdf @@ -0,0 +1,116 @@ + + + The shape of the visual or collision object. + + + Box shape + + The three side lengths of the box. The origin of the box is in its geometric center (inside the center of the box). + + + + + Sphere shape + + radius of the sphere + + + + + Cylinder shape + + Radius of the cylinder + + + Length of the cylinder + + + + + Mesh shape + + Mesh uri + + + + Use a named submesh. The submesh must exist in the mesh specified by the uri + + Name of the submesh within the parent mesh + + + Set to true to center the vertices of the submesh at 0,0,0. This will effectively remove any transformations on the submesh before the poses from parent links and models are applied. + + + + + Scaling factor applied to the mesh + + + + + Plane shape + + Normal direction for the plane + + + Length of each side of the plane + + + + + Extrude a set of boxes from a grayscale image. + + URI of the grayscale image file + + + Scaling factor applied to the image + + + Grayscale threshold + + + Height of the extruded boxes + + + The amount of error in the model + + + + + A heightmap based on a 2d grayscale image. + + URI to a grayscale image file + + + The size of the heightmap in world units + + + A position offset. + + + + The heightmap can contain multiple textures. The order of the texture matters. The first texture will appear at the lowest height, and the last texture at the highest height. Use blend to control the height thresholds and fade between textures. + + Size of the applied texture in meters. + + + Diffuse texture image filename + + + Normalmap texture image filename + + + + The blend tag controls how two adjacent textures are mixed. The number of blend elements should equal one less than the number of textures. + + Min height of a blend layer + + + Distance over which the blend occurs + + + + + You can use the empty tag to make empty geometries. + + diff --git a/sdformat/sdf/1.3/gripper.sdf b/sdformat/sdf/1.3/gripper.sdf new file mode 100644 index 0000000..12fd0b3 --- /dev/null +++ b/sdformat/sdf/1.3/gripper.sdf @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.3/gui.sdf b/sdformat/sdf/1.3/gui.sdf new file mode 100644 index 0000000..8300090 --- /dev/null +++ b/sdformat/sdf/1.3/gui.sdf @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.3/imu.sdf b/sdformat/sdf/1.3/imu.sdf new file mode 100644 index 0000000..0f9f507 --- /dev/null +++ b/sdformat/sdf/1.3/imu.sdf @@ -0,0 +1,8 @@ + + These elements are specific to the IMU sensor. + + + Topic on which data is published. + + + diff --git a/sdformat/sdf/1.3/inertial.sdf b/sdformat/sdf/1.3/inertial.sdf new file mode 100644 index 0000000..417489f --- /dev/null +++ b/sdformat/sdf/1.3/inertial.sdf @@ -0,0 +1,34 @@ + + + The inertial properties of the link. + + + The mass of the link. + + + + This is the pose of the inertial reference frame, relative to the link reference frame. The origin of the inertial reference frame needs to be at the center of gravity. The axes of the inertial reference frame do not need to be aligned with the principal axes of the inertia. + + + + The 3x3 rotational inertia matrix. Because the rotational inertia matrix is symmetric, only 6 above-diagonal elements of this matrix are specified here, using the attributes ixx, ixy, ixz, iyy, iyz, izz. + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.3/joint.sdf b/sdformat/sdf/1.3/joint.sdf new file mode 100644 index 0000000..64ff831 --- /dev/null +++ b/sdformat/sdf/1.3/joint.sdf @@ -0,0 +1,141 @@ + + + A joint connections two links with kinematic and dynamic properties. + + + A unique name for the joint within the scope of the model. + + + + The type of joint, which must be one of the following: (revolute) a hinge joint that rotates on a single axis with either a fixed or continuous range of motion, (revolute2) same as two revolute joints connected in series, (prismatic) a sliding joint that slides along an axis with a limited range specified by upper and lower limits, (ball) a ball and socket joint, (universal), like a ball joint, but constrains one degree of freedom, (piston) similar to a Slider joint except that rotation around the translation axis is possible. + + + + Name of the parent link + + + + Name of the child link + + + + offset from child link origin in child link frame. + + + + + + + + The joint axis specified in the model frame. This is the axis of rotation for revolute joints, the axis of translation for prismatic joints. The axis is currently specified in the model frame of reference, but this will be changed to the joint frame in future version of sdf (see gazebo issue #494). + + Represents the x,y,z components of a vector. The vector should be normalized. + + + An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation. + + The physical velocity dependent viscous damping coefficient of the joint. + + + The physical static friction value of the joint. + + + + specifies the limits of this joint + + An attribute specifying the lower joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute specifying the upper joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute for enforcing the maximum joint effort applied by Joint::SetForce. Limit is not enforced if value is negative. + + + (not implemented) An attribute for enforcing the maximum joint velocity. + + + + + + The second joint axis specified in the model frame. This is the second axis of rotation for revolute2 joints and universal joints. The axis is currently specified in the model frame of reference, but this will be changed to the joint frame in future version of sdf (see gazebo issue #494). + + Represents the x,y,z components of a vector. The vector should be normalized. + + + An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation. + + The physical velocity dependent viscous damping coefficient of the joint. + + + The physical static friction value of the joint. + + + + + + + An attribute specifying the lower joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute specifying the upper joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute for enforcing the maximum joint effort applied by Joint::SetForce. Limit is not enforced if value is negative. + + + (not implemented) An attribute for enforcing the maximum joint velocity. + + + + + + Parameters that are specific to a certain physics engine. + + ODE specific parameters + + If provide feedback is set to true, ODE will compute the constraint forces at this joint. + + + + If cfm damping is set to true, ODE will use CFM to simulate damping, allows for infinite damping, and one additional constraint row (previously used for joint limit) is always active. + + + + Scale the excess for in a joint motor at joint limits. Should be between zero and one. + + + Constraint force mixing used when not at a stop + + + Bounciness of the limits + + + Maximum force or torque used to reach the desired velocity. + + + The desired velocity of the joint. Should only be set if you want the joint to move on load. + + + + + + Constraint force mixing parameter used by the joint stop + + + Error reduction parameter used by the joint stop + + + + + + + Suspension constraint force mixing parameter + + + Suspension error reduction parameter + + + + + diff --git a/sdformat/sdf/1.3/light.sdf b/sdformat/sdf/1.3/light.sdf new file mode 100644 index 0000000..745308c --- /dev/null +++ b/sdformat/sdf/1.3/light.sdf @@ -0,0 +1,61 @@ + + + The light element describes a light source. + + + A unique name for the light. + + + + The light type: point, directional, spot. + + + + When true, the light will cast shadows. + + + + A position and orientation in the global coordinate frame for the light. + + + + Diffuse light color + + + Specular light color + + + + Light attenuation + + Range of the light + + + The linear attenuation factor: 1 means attenuate evenly over the distance. + + + The constant attenuation factor: 1.0 means never attenuate, 0.0 is complete attenutation. + + + The quadratic attenuation factor: adds a curvature to the attenuation. + + + + + Direction of the light, only applicable for spot and directional lights. + + + + Spot light parameters + + Angle covered by the bright inner cone + + + Angle covered by the outer cone + + + The rate of falloff between the inner and outer cones. 1.0 means a linear falloff, less means slower falloff, higher means faster falloff. + + + + diff --git a/sdformat/sdf/1.3/link.sdf b/sdformat/sdf/1.3/link.sdf new file mode 100644 index 0000000..24f7a3c --- /dev/null +++ b/sdformat/sdf/1.3/link.sdf @@ -0,0 +1,41 @@ + + + A physical link with inertia, collision, and visual properties. A link must be a child of a model, and any number of links may exist in a model. + + + A unique name for the link within the scope of the model. + + + + If true, the link is affected by gravity. + + + + If true, the link can collide with other links in the model. + + + + If true, the link is kinematic only + + + + This is the pose of the link reference frame, relative to the model reference frame. + + + + Exponential damping of the link's velocity. + + Linear damping + + + Angular damping + + + + + + + + + + diff --git a/sdformat/sdf/1.3/model.sdf b/sdformat/sdf/1.3/model.sdf new file mode 100644 index 0000000..2ec8b59 --- /dev/null +++ b/sdformat/sdf/1.3/model.sdf @@ -0,0 +1,26 @@ + + + The model element defines a complete robot or any other physical object. + + + A unique name for the model. This name must not match another model in the world. + + + + If set to true, the model is immovable. Otherwise the model is simulated in the dynamics engine. + + + + Allows a model to auto-disable, which is means the physics engine can skip updating the model when the model is at rest. This parameter is only used by models with no joints. + + + + A position and orientation in the global coordinate frame for the model. Position(x,y,z) and rotation (roll, pitch yaw) in the global coordinate frame. + + + + + + + + diff --git a/sdformat/sdf/1.3/physics.sdf b/sdformat/sdf/1.3/physics.sdf new file mode 100644 index 0000000..1811a72 --- /dev/null +++ b/sdformat/sdf/1.3/physics.sdf @@ -0,0 +1,65 @@ + + + The physics tag specifies the type and properties of the dynamics engine. + + + The type of the dynamics engine. Currently must be set to ode + + + + Rate at which to update the physics engine + + + + Maximum number of contacts allowed between two entities. This value can be over ridden by a max_contacts element in a collision element. + + + + The gravity vector + + + + Bullet specific physics properties + + Time step + + + + + ODE specific physics properties + + + + One of the following types: world, quick + + + The time duration which advances with each iteration of the dynamics engine. + + + Number of iterations for each step. A higher number produces greater accuracy at a performance cost. + + + + + + Set the successive over-relaxation parameter. + + + + + + + Constraint force mixing parameter. See the ODE page for more information. + + + Error reduction parameter. See the ODE page for more information. + + + The maximum correcting velocities allowed when resolving contacts. + + + The depth of the surface layer around all geometry objects. Contacts are allowed to sink into the surface layer up to the given depth before coming to rest. The default value is zero. Increasing this to some small value (e.g. 0.001) can help prevent jittering problems due to contacts being repeatedly made and broken. + + + + diff --git a/sdformat/sdf/1.3/plugin.sdf b/sdformat/sdf/1.3/plugin.sdf new file mode 100644 index 0000000..26405ff --- /dev/null +++ b/sdformat/sdf/1.3/plugin.sdf @@ -0,0 +1,13 @@ + + + A plugin is a dynamically loaded chunk of code. It can exist as a child of world, model, and sensor. + + A unique name for the plugin, scoped to its parent. + + + Name of the shared library to load. If the filename is not a full path name, the file will be searched for in the configuration paths. + + + This is a special element that should not be specified in an SDF file. It automatically copies child elements into the SDF element so that a plugin can access the data. + + diff --git a/sdformat/sdf/1.3/projector.sdf b/sdformat/sdf/1.3/projector.sdf new file mode 100644 index 0000000..9eabca9 --- /dev/null +++ b/sdformat/sdf/1.3/projector.sdf @@ -0,0 +1,32 @@ + + + + Name of the projector + + + + Texture name + + + + Pose of the projector + + + + + Field of view + + + + + Near clip distance + + + + + far clip distance + + + + + diff --git a/sdformat/sdf/1.3/ray.sdf b/sdformat/sdf/1.3/ray.sdf new file mode 100644 index 0000000..c56c993 --- /dev/null +++ b/sdformat/sdf/1.3/ray.sdf @@ -0,0 +1,60 @@ + + These elements are specific to the ray (laser) sensor. + + + + + + + + The number of simulated rays to generate per complete laser sweep cycle. + + + + This number is multiplied by samples to determine the number of range data points returned. If resolution is less than one, range data is interpolated. If resolution is greater than one, range data is averaged. + + + + + + + + Must be greater or equal to min_angle + + + + + + + + The number of simulated rays to generate per complete laser sweep cycle. + + + + This number is multiplied by samples to determine the number of range data points returned. If resolution is less than one, range data is interpolated. If resolution is greater than one, range data is averaged. + + + + + + + + Must be greater or equal to min_angle + + + + + + + specifies range properties of each simulated ray + + The minimum distance for each ray. + + + The maximum distance for each ray. + + + Linear resolution of each ray. + + + diff --git a/sdformat/sdf/1.3/rfid.sdf b/sdformat/sdf/1.3/rfid.sdf new file mode 100644 index 0000000..61351dd --- /dev/null +++ b/sdformat/sdf/1.3/rfid.sdf @@ -0,0 +1,2 @@ + + diff --git a/sdformat/sdf/1.3/rfidtag.sdf b/sdformat/sdf/1.3/rfidtag.sdf new file mode 100644 index 0000000..55699dc --- /dev/null +++ b/sdformat/sdf/1.3/rfidtag.sdf @@ -0,0 +1,2 @@ + + diff --git a/sdformat/sdf/1.3/road.sdf b/sdformat/sdf/1.3/road.sdf new file mode 100644 index 0000000..3549b24 --- /dev/null +++ b/sdformat/sdf/1.3/road.sdf @@ -0,0 +1,15 @@ + + + + Name of the road + + + + Width of the road + + + + A series of points define the path of the road. + + + diff --git a/sdformat/sdf/1.3/root.sdf b/sdformat/sdf/1.3/root.sdf new file mode 100644 index 0000000..bd9c69f --- /dev/null +++ b/sdformat/sdf/1.3/root.sdf @@ -0,0 +1,13 @@ + + SDF base element. + + + Version number of the SDF format. + + + + + + + + diff --git a/sdformat/sdf/1.3/scene.sdf b/sdformat/sdf/1.3/scene.sdf new file mode 100644 index 0000000..579ec9e --- /dev/null +++ b/sdformat/sdf/1.3/scene.sdf @@ -0,0 +1,78 @@ + + + Specifies the look of the environment. + + + Color of the ambient light. + + + + Color of the background. + + + + Properties for the sky + + Time of day [0..24] + + + Sunrise time [0..24] + + + Sunset time [0..24] + + + + Sunset time [0..24] + + Speed of the clouds + + + + Direction of the cloud movement + + + Density of clouds + + + + Average size of the clouds + + + + Ambient cloud color + + + + + + Enable/disable shadows + + + + Controls fog + + Fog color + + + Fog type: constant, linear, quadratic + + + Distance to start of fog + + + Distance to end of fog + + + Density of fog + + + + + Enable/disable the grid + + + diff --git a/sdformat/sdf/1.3/sensor.sdf b/sdformat/sdf/1.3/sensor.sdf new file mode 100644 index 0000000..36dafe0 --- /dev/null +++ b/sdformat/sdf/1.3/sensor.sdf @@ -0,0 +1,41 @@ + + + The sensor tag describes the type and properties of a sensor. + + + A unique name for the sensor. This name must not match another model in the model. + + + + The type name of the sensor. By default, SDF supports types camera, depth, multicamera, contact, imu, ir and ray. + + + + If true the sensor will always be updated according to the update rate. + + + + The frequency at which the sensor data is generated. If left unspecified, the sensor will generate data every cycle. + + + + If true, the sensor is visualized in the GUI + + + + This is the pose of the sensor, relative to the parent link reference frame. + + + + Name of the topic on which data is published. This is necessary for visualization + + + + + + + + + + + diff --git a/sdformat/sdf/1.3/server.sdf b/sdformat/sdf/1.3/server.sdf new file mode 100644 index 0000000..47d1606 --- /dev/null +++ b/sdformat/sdf/1.3/server.sdf @@ -0,0 +1,29 @@ + + + The distributed tag specifies the ip and port of the remote server. + + + The type of the distribution(0:client or 1:server). + + + + The ip of the remote server. + + + + The flag of the remote server. + + + + the port of the remote port + + + + the port of the remote port + + + + the port of the remote port + + + diff --git a/sdformat/sdf/1.3/state.sdf b/sdformat/sdf/1.3/state.sdf new file mode 100644 index 0000000..01d3c63 --- /dev/null +++ b/sdformat/sdf/1.3/state.sdf @@ -0,0 +1,101 @@ + + + + + Name of the world this state applies to + + + + Simulation time stamp of the state [seconds nanoseconds] + + + + Wall time stamp of the state [seconds nanoseconds] + + + + Real time stamp of the state [seconds nanoseconds] + + + + A list of new model names + + + + + A list of deleted model names + + The name of a deleted model + + + + + + + Model state + + + Name of the model + + + + Pose of the model + + + + Joint angle + + + Name of the joint + + + + + Index of the axis. + + + Angle of an axis + + + + + + Link state + + + Name of the link + + + + Pose of the link relative to the model + + + + Velocity of the link + + + + Acceleration of the link + + + + Force applied to the link + + + + Collision state + + + Name of the collision + + + + Pose of the link relative to the model + + + + + + + diff --git a/sdformat/sdf/1.3/surface.sdf b/sdformat/sdf/1.3/surface.sdf new file mode 100644 index 0000000..7dcbfb0 --- /dev/null +++ b/sdformat/sdf/1.3/surface.sdf @@ -0,0 +1,59 @@ + + The surface parameters + + + + Bounciness coefficient of restitution, from [0...1], where 0=no bounciness. + + + Bounce velocity threshold, below which effective coefficient of restitution is 0. + + + + + + + ODE friction parameters + + Coefficient of friction in the range of [0..1]. + + + Second coefficient of friction in the range of [0..1] + + + 3-tuple specifying direction of mu1 in the collision local reference frame. + + + Force dependent slip direction 1 in collision local frame, between the range of [0..1]. + + + Force dependent slip direction 2 in collision local frame, between the range of [0..1]. + + + + + + + + ODE contact parameters + + Soft constraint force mixing. + + + Soft error reduction parameter + + + dynamically "stiffness"-equivalent coefficient for contact joints + + + dynamically "damping"-equivalent coefficient for contact joints + + + maximum contact correction velocity truncation term. + + + minimum allowable depth before contact correction impulse is applied + + + + diff --git a/sdformat/sdf/1.3/urdf.sdf b/sdformat/sdf/1.3/urdf.sdf new file mode 100644 index 0000000..6068d5c --- /dev/null +++ b/sdformat/sdf/1.3/urdf.sdf @@ -0,0 +1,19 @@ + + + The robot element defines a complete robot or any other physical object using URDF. + + + A unique name for the model. This name must not match another model in the world. + + + + A position and orientation in the global coordinate frame for the model. Position(x,y,z) and rotation (roll, pitch yaw) in the global coordinate frame. + + + + + + + + + diff --git a/sdformat/sdf/1.3/visual.sdf b/sdformat/sdf/1.3/visual.sdf new file mode 100644 index 0000000..d8d924c --- /dev/null +++ b/sdformat/sdf/1.3/visual.sdf @@ -0,0 +1,71 @@ + + + The visual properties of the link. This element specifies the shape of the object (box, cylinder, etc.) for visualization purposes. + + + Unique name for the visual element within the scope of the parent link. + + + + If true the visual will cast shadows. + + + + will be implemented in the future release. + + + + The amount of transparency( 0=opaque, 1 = fully transparent) + + + + Origin of the visual relative to its parent. + + + + The material of the visual element. + + + Name of material from an installed script file. This will override the color element if the script exists. + + + URI of the material script file + + + + Name of the script within the script file + + + + + + + + vertex, pixel, normal_map_objectspace, normal_map_tangentspace + + + + filename of the normal map + + + + + The ambient color of a material specified by set of four numbers representing red/green/blue, each in the range of [0,1]. + + + + The diffuse color of a material specified by set of four numbers representing red/green/blue/alpha, each in the range of [0,1]. + + + + The specular color of a material specified by set of four numbers representing red/green/blue/alpha, each in the range of [0,1]. + + + + The emissive color of a material specified by set of four numbers representing red/green/blue, each in the range of [0,1]. + + + + + + diff --git a/sdformat/sdf/1.3/world.sdf b/sdformat/sdf/1.3/world.sdf new file mode 100644 index 0000000..a0223ad --- /dev/null +++ b/sdformat/sdf/1.3/world.sdf @@ -0,0 +1,66 @@ + + The world element encapsulates an entire world description including: models, scene, physics, joints, and plugins + + + Unique name of the world + + + + Global audio properties. + + + Device to use for audio playback. A value of "default" will use the system's default audio device. Otherwise, specify a an audio device file" + + + + + The wind tag specifies the type and properties of the wind. + + + Linear velocity of the wind. + + + + + Include resources from a URI + + URI to a resource, such as a model + + + + Override the name of the included model. + + + + Override the static value of the included model. + + + + + + + The gravity vector in m/s^2, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + The magnetic vector in Tesla, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.4/1_3.convert b/sdformat/sdf/1.4/1_3.convert new file mode 100644 index 0000000..1cea592 --- /dev/null +++ b/sdformat/sdf/1.4/1_3.convert @@ -0,0 +1,52 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.4/CMakeLists.txt b/sdformat/sdf/1.4/CMakeLists.txt new file mode 100644 index 0000000..b617d80 --- /dev/null +++ b/sdformat/sdf/1.4/CMakeLists.txt @@ -0,0 +1,47 @@ +set (sdfs + 1_3.convert + actor.sdf + audio_source.sdf + audio_sink.sdf + box_shape.sdf + camera.sdf + collision.sdf + contact.sdf + cylinder_shape.sdf + forcetorque.sdf + geometry.sdf + gps.sdf + gripper.sdf + gui.sdf + heightmap_shape.sdf + image_shape.sdf + imu.sdf + inertial.sdf + joint.sdf + light.sdf + link.sdf + mesh_shape.sdf + model.sdf + noise.sdf + physics.sdf + plane_shape.sdf + plugin.sdf + projector.sdf + ray.sdf + rfidtag.sdf + rfid.sdf + road.sdf + root.sdf + scene.sdf + sensor.sdf + spherical_coordinates.sdf + sphere_shape.sdf + sonar.sdf + state.sdf + surface.sdf + transceiver.sdf + visual.sdf + world.sdf +) + +install(FILES ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat/1.4) diff --git a/sdformat/sdf/1.4/actor.sdf b/sdformat/sdf/1.4/actor.sdf new file mode 100644 index 0000000..d90c523 --- /dev/null +++ b/sdformat/sdf/1.4/actor.sdf @@ -0,0 +1,88 @@ + + + + + + + + + + + + + + Origin of the actor + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.4/audio_sink.sdf b/sdformat/sdf/1.4/audio_sink.sdf new file mode 100644 index 0000000..d3bd071 --- /dev/null +++ b/sdformat/sdf/1.4/audio_sink.sdf @@ -0,0 +1,4 @@ + + + An audio sink. + diff --git a/sdformat/sdf/1.4/audio_source.sdf b/sdformat/sdf/1.4/audio_source.sdf new file mode 100644 index 0000000..01c6159 --- /dev/null +++ b/sdformat/sdf/1.4/audio_source.sdf @@ -0,0 +1,32 @@ + + + An audio source. + + + URI of the audio media. + + + + Pitch for the audio media, in Hz + + + + Gain for the audio media, in dB. + + + + List of collision objects that will trigger audio playback. + + Name of child collision element that will trigger audio playback. + + + + + True to make the audio source loop playback. + + + + A position and orientation in the parent coordinate frame for the audio source. Position(x,y,z) and rotation (roll, pitch yaw) in the parent coordinate frame. + + + diff --git a/sdformat/sdf/1.4/box_shape.sdf b/sdformat/sdf/1.4/box_shape.sdf new file mode 100644 index 0000000..826ab37 --- /dev/null +++ b/sdformat/sdf/1.4/box_shape.sdf @@ -0,0 +1,6 @@ + + Box shape + + The three side lengths of the box. The origin of the box is in its geometric center (inside the center of the box). + + diff --git a/sdformat/sdf/1.4/camera.sdf b/sdformat/sdf/1.4/camera.sdf new file mode 100644 index 0000000..5ae23cb --- /dev/null +++ b/sdformat/sdf/1.4/camera.sdf @@ -0,0 +1,71 @@ + + These elements are specific to camera sensors. + + + An optional name for the camera. + + + + A position and orientation in the parent coordinate frame for the camera. + + + + Horizontal field of view + + + + The image size in pixels and format. + + Width in pixels + + + Height in pixels + + + (L8|R8G8B8|B8G8R8|BAYER_RGGB8|BAYER_BGGR8|BAYER_GBRG8|BAYER_GRBG8) + + + + + The near and far clip planes. Objects closer or farther than these planes are not rendered. + + + Near clipping plane + + + + Far clipping plane + + + + + Enable or disable saving of camera frames. + + True = saving enabled + + + The path name which will hold the frame data. If path name is relative, then directory is relative to current working directory. + + + + + Depth camera parameters + + Type of output + + + + + The properties of the noise model that should be applied to generated images + + The type of noise. Currently supported types are: "gaussian" (draw additive noise values independently for each pixel from a Gaussian distribution). + + + For type "gaussian," the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which noise values are drawn. + + + + diff --git a/sdformat/sdf/1.4/collision.sdf b/sdformat/sdf/1.4/collision.sdf new file mode 100644 index 0000000..051732d --- /dev/null +++ b/sdformat/sdf/1.4/collision.sdf @@ -0,0 +1,24 @@ + + + The collision properties of a link. Note that this can be different from the visual properties of a link, for example, simpler collision models are often used to reduce computation time. + + + Unique name for the collision element within the scope of the parent link. + + + + intensity value returned by laser sensor. + + + + Maximum number of contacts allowed between two entities. This value overrides the max_contacts element defined in physics. + + + + The reference frame of the collision element, relative to the reference frame of the link. + + + + + + diff --git a/sdformat/sdf/1.4/collision_engine.sdf b/sdformat/sdf/1.4/collision_engine.sdf new file mode 100644 index 0000000..67dbc70 --- /dev/null +++ b/sdformat/sdf/1.4/collision_engine.sdf @@ -0,0 +1,17 @@ + + + The collision_engine tag specifies the type and properties of the collision detection engine. + + + + The type of the collision detection engine. Current default in ODE is OPCODE. + + + + + + The type of the collision detection engine. + + + + diff --git a/sdformat/sdf/1.4/contact.sdf b/sdformat/sdf/1.4/contact.sdf new file mode 100644 index 0000000..d1cde50 --- /dev/null +++ b/sdformat/sdf/1.4/contact.sdf @@ -0,0 +1,12 @@ + + These elements are specific to the contact sensor. + + + name of the collision element within a link that acts as the contact sensor. + + + + Topic on which contact data is published. + + + diff --git a/sdformat/sdf/1.4/cylinder_shape.sdf b/sdformat/sdf/1.4/cylinder_shape.sdf new file mode 100644 index 0000000..8e25a53 --- /dev/null +++ b/sdformat/sdf/1.4/cylinder_shape.sdf @@ -0,0 +1,9 @@ + + Cylinder shape + + Radius of the cylinder + + + Length of the cylinder + + diff --git a/sdformat/sdf/1.4/distribution.sdf b/sdformat/sdf/1.4/distribution.sdf new file mode 100644 index 0000000..924c2f5 --- /dev/null +++ b/sdformat/sdf/1.4/distribution.sdf @@ -0,0 +1,19 @@ + + + The distribution tag specifies the local ID of this gazebo and port of the remote server. + + + The ID of the gazebo. + + + + The flag of the remote server. + + + + the port of the remote port + + + + + diff --git a/sdformat/sdf/1.4/event.sdf b/sdformat/sdf/1.4/event.sdf new file mode 100644 index 0000000..16d5c20 --- /dev/null +++ b/sdformat/sdf/1.4/event.sdf @@ -0,0 +1,21 @@ + + + The parallel tag specifies the numbers of threads and tbb size of the block. + + + The type of parallel. + + + + The numbers of the threads. + + + + the size of block to tbb thread + + + + the type to block partion + + + diff --git a/sdformat/sdf/1.4/forcetorque.sdf b/sdformat/sdf/1.4/forcetorque.sdf new file mode 100644 index 0000000..b922d25 --- /dev/null +++ b/sdformat/sdf/1.4/forcetorque.sdf @@ -0,0 +1,6 @@ + + These elements are specific to the force torque sensor. + + Frame in which to report the wrench values. + + diff --git a/sdformat/sdf/1.4/gazeboid.sdf b/sdformat/sdf/1.4/gazeboid.sdf new file mode 100644 index 0000000..4cb7ae3 --- /dev/null +++ b/sdformat/sdf/1.4/gazeboid.sdf @@ -0,0 +1,17 @@ + + + The distributed tag specifies the ip and ID of the local gazebo. + + + The type of the distribution(0:client or 1:server). + + + + The ip of the local gazebo. + + + + model name in the local gazebo. + + + diff --git a/sdformat/sdf/1.4/geometry.sdf b/sdformat/sdf/1.4/geometry.sdf new file mode 100644 index 0000000..c3620ae --- /dev/null +++ b/sdformat/sdf/1.4/geometry.sdf @@ -0,0 +1,17 @@ + + + The shape of the visual or collision object. + + + You can use the empty tag to make empty geometries. + + + + + + + + + + + diff --git a/sdformat/sdf/1.4/gps.sdf b/sdformat/sdf/1.4/gps.sdf new file mode 100644 index 0000000..95e0049 --- /dev/null +++ b/sdformat/sdf/1.4/gps.sdf @@ -0,0 +1,40 @@ + + These elements are specific to the GPS sensor. + + + + Parameters related to GPS position measurement. + + + + Noise parameters for horizontal position measurement, in units of meters. + + + + + + Noise parameters for vertical position measurement, in units of meters. + + + + + + + + Parameters related to GPS position measurement. + + + + Noise parameters for horizontal velocity measurement, in units of meters/second. + + + + + + Noise parameters for vertical velocity measurement, in units of meters/second. + + + + + + diff --git a/sdformat/sdf/1.4/gripper.sdf b/sdformat/sdf/1.4/gripper.sdf new file mode 100644 index 0000000..12fd0b3 --- /dev/null +++ b/sdformat/sdf/1.4/gripper.sdf @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.4/gui.sdf b/sdformat/sdf/1.4/gui.sdf new file mode 100644 index 0000000..8300090 --- /dev/null +++ b/sdformat/sdf/1.4/gui.sdf @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.4/heightmap_shape.sdf b/sdformat/sdf/1.4/heightmap_shape.sdf new file mode 100644 index 0000000..087f4ca --- /dev/null +++ b/sdformat/sdf/1.4/heightmap_shape.sdf @@ -0,0 +1,40 @@ + + A heightmap based on a 2d grayscale image. + + URI to a grayscale image file + + + The size of the heightmap in world units. + When loading an image: "size" is used if present, otherwise defaults to 1x1x1. + When loading a DEM: "size" is used if present, otherwise defaults to true size of DEM. + + + + A position offset. + + + + The heightmap can contain multiple textures. The order of the texture matters. The first texture will appear at the lowest height, and the last texture at the highest height. Use blend to control the height thresholds and fade between textures. + + Size of the applied texture in meters. + + + Diffuse texture image filename + + + Normalmap texture image filename + + + + The blend tag controls how two adjacent textures are mixed. The number of blend elements should equal one less than the number of textures. + + Min height of a blend layer + + + Distance over which the blend occurs + + + + Set if the rendering engine will use terrain paging + + diff --git a/sdformat/sdf/1.4/image_shape.sdf b/sdformat/sdf/1.4/image_shape.sdf new file mode 100644 index 0000000..369de7c --- /dev/null +++ b/sdformat/sdf/1.4/image_shape.sdf @@ -0,0 +1,18 @@ + + Extrude a set of boxes from a grayscale image. + + URI of the grayscale image file + + + Scaling factor applied to the image + + + Grayscale threshold + + + Height of the extruded boxes + + + The amount of error in the model + + diff --git a/sdformat/sdf/1.4/imu.sdf b/sdformat/sdf/1.4/imu.sdf new file mode 100644 index 0000000..dde8db3 --- /dev/null +++ b/sdformat/sdf/1.4/imu.sdf @@ -0,0 +1,46 @@ + + These elements are specific to the IMU sensor. + + + Topic on which data is published. + + + + The properties of the noise model that should be applied to generated data + + The type of noise. Currently supported types are: "gaussian" (draw noise values independently for each beam from a Gaussian distribution). + + + Noise parameters for angular rates. + + For type "gaussian," the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the mean of the Gaussian distribution from which bias values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which bias values are drawn. + + + + + Noise parameters for linear accelerations. + + For type "gaussian," the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the mean of the Gaussian distribution from which bias values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which bias values are drawn. + + + + + diff --git a/sdformat/sdf/1.4/inertial.sdf b/sdformat/sdf/1.4/inertial.sdf new file mode 100644 index 0000000..417489f --- /dev/null +++ b/sdformat/sdf/1.4/inertial.sdf @@ -0,0 +1,34 @@ + + + The inertial properties of the link. + + + The mass of the link. + + + + This is the pose of the inertial reference frame, relative to the link reference frame. The origin of the inertial reference frame needs to be at the center of gravity. The axes of the inertial reference frame do not need to be aligned with the principal axes of the inertia. + + + + The 3x3 rotational inertia matrix. Because the rotational inertia matrix is symmetric, only 6 above-diagonal elements of this matrix are specified here, using the attributes ixx, ixy, ixz, iyy, iyz, izz. + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.4/joint.sdf b/sdformat/sdf/1.4/joint.sdf new file mode 100644 index 0000000..9d65270 --- /dev/null +++ b/sdformat/sdf/1.4/joint.sdf @@ -0,0 +1,186 @@ + + + A joint connections two links with kinematic and dynamic properties. + + + A unique name for the joint within the scope of the model. + + + + The type of joint, which must be one of the following: (revolute) a hinge joint that rotates on a single axis with either a fixed or continuous range of motion, (gearbox) geared revolute joints, (revolute2) same as two revolute joints connected in series, (prismatic) a sliding joint that slides along an axis with a limited range specified by upper and lower limits, (ball) a ball and socket joint, (universal), like a ball joint, but constrains one degree of freedom, (piston) similar to a Slider joint except that rotation around the translation axis is possible. + + + + Name of the parent link + + + + Name of the child link + + + + offset from child link origin in child link frame. + + + + Parameter for gearbox joints. Given theta_1 and theta_2 defined in description for gearbox_reference_body, theta_2 = -gearbox_ratio * theta_1. + + + + Parameter for gearbox joints. Gearbox ratio is enforced over two joint angles. First joint angle (theta_1) is the angle from the gearbox_reference_body to the parent link in the direction of the axis element and the second joint angle (theta_2) is the angle from the gearbox_reference_body to the child link in the direction of the axis2 element. + + + + Parameter for screw joints. + + + + The joint axis specified in the parent model frame. This is the axis of rotation for revolute joints, the axis of translation for prismatic joints. The axis is currently specified in the parent model frame of reference, but this will be changed to the joint frame in future version of sdf (see gazebo issue #494). + + Represents the x,y,z components of a vector. The vector should be normalized. + + + An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation. + + The physical velocity dependent viscous damping coefficient of the joint. + + + The physical static friction value of the joint. + + + + specifies the limits of this joint + + An attribute specifying the lower joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute specifying the upper joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute for enforcing the maximum joint effort applied by Joint::SetForce. Limit is not enforced if value is negative. + + + (not implemented) An attribute for enforcing the maximum joint velocity. + + + + Joint stop stiffness. Support physics engines: SimBody. + + + + Joint stop dissipation. + + + + + + + The second joint axis specified in the parent model frame. This is the second axis of rotation for revolute2 joints and universal joints. The axis is currently specified in the parent model frame of reference, but this will be changed to the joint frame in future version of sdf (see gazebo issue #494). + + Represents the x,y,z components of a vector. The vector should be normalized. + + + An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation. + + The physical velocity dependent viscous damping coefficient of the joint. EXPERIMENTAL: if damping coefficient is negative and implicit_spring_damper is true, adaptive damping is used. + + + The physical static friction value of the joint. + + + + + + + An attribute specifying the lower joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute specifying the upper joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute for enforcing the maximum joint effort applied by Joint::SetForce. Limit is not enforced if value is negative. + + + (not implemented) An attribute for enforcing the maximum joint velocity. + + + + Joint stop stiffness. Supported physics engines: SimBody. + + + + Joint stop dissipation. Supported physics engines: SimBody. + + + + + + + Parameters that are specific to a certain physics engine. + + Simbody specific parameters + + Force cut in the multibody graph at this joint. + + + + ODE specific parameters + + (DEPRECATION WARNING: In SDF 1.5 this tag will be replaced by the same tag directly under the physics-block. For now, this tag overrides the one outside of ode-block, but in SDF 1.5 this tag will be removed completely.) If provide feedback is set to true, ODE will compute the constraint forces at this joint. + + + + If cfm damping is set to true, ODE will use CFM to simulate damping, allows for infinite damping, and one additional constraint row (previously used for joint limit) is always active. + + + + If implicit_spring_damper is set to true, ODE will use CFM, ERP to simulate stiffness and damping, allows for infinite damping, and one additional constraint row (previously used for joint limit) is always active. This replaces cfm_damping parameter in sdf 1.4. + + + + Scale the excess for in a joint motor at joint limits. Should be between zero and one. + + + Constraint force mixing for constrained directions + + + Error reduction parameter for constrained directions + + + Bounciness of the limits + + + Maximum force or torque used to reach the desired velocity. + + + The desired velocity of the joint. Should only be set if you want the joint to move on load. + + + + + + Constraint force mixing parameter used by the joint stop + + + Error reduction parameter used by the joint stop + + + + + + + Suspension constraint force mixing parameter + + + Suspension error reduction parameter + + + + + + If provide feedback is set to true, physics engine will compute the constraint forces at this joint. For now, provide_feedback under ode block will override this tag and given user warning about the migration. provide_feedback under ode is scheduled to be removed in SDF 1.5. + + + + + diff --git a/sdformat/sdf/1.4/light.sdf b/sdformat/sdf/1.4/light.sdf new file mode 100644 index 0000000..745308c --- /dev/null +++ b/sdformat/sdf/1.4/light.sdf @@ -0,0 +1,61 @@ + + + The light element describes a light source. + + + A unique name for the light. + + + + The light type: point, directional, spot. + + + + When true, the light will cast shadows. + + + + A position and orientation in the global coordinate frame for the light. + + + + Diffuse light color + + + Specular light color + + + + Light attenuation + + Range of the light + + + The linear attenuation factor: 1 means attenuate evenly over the distance. + + + The constant attenuation factor: 1.0 means never attenuate, 0.0 is complete attenutation. + + + The quadratic attenuation factor: adds a curvature to the attenuation. + + + + + Direction of the light, only applicable for spot and directional lights. + + + + Spot light parameters + + Angle covered by the bright inner cone + + + Angle covered by the outer cone + + + The rate of falloff between the inner and outer cones. 1.0 means a linear falloff, less means slower falloff, higher means faster falloff. + + + + diff --git a/sdformat/sdf/1.4/link.sdf b/sdformat/sdf/1.4/link.sdf new file mode 100644 index 0000000..8eb9809 --- /dev/null +++ b/sdformat/sdf/1.4/link.sdf @@ -0,0 +1,47 @@ + + + A physical link with inertia, collision, and visual properties. A link must be a child of a model, and any number of links may exist in a model. + + + A unique name for the link within the scope of the model. + + + + If true, the link is affected by gravity. + + + + If true, the link can collide with other links in the model. + + + + If true, the link is kinematic only + + + + This is the pose of the link reference frame, relative to the model reference frame. + + + + If true, the link will have 6DOF and be a direct child of world. + + + + Exponential damping of the link's velocity. + + Linear damping + + + Angular damping + + + + + + + + + + + + diff --git a/sdformat/sdf/1.4/mesh_shape.sdf b/sdformat/sdf/1.4/mesh_shape.sdf new file mode 100644 index 0000000..61bce76 --- /dev/null +++ b/sdformat/sdf/1.4/mesh_shape.sdf @@ -0,0 +1,20 @@ + + Mesh shape + + Mesh uri + + + + Use a named submesh. The submesh must exist in the mesh specified by the uri + + Name of the submesh within the parent mesh + + + Set to true to center the vertices of the submesh at 0,0,0. This will effectively remove any transformations on the submesh before the poses from parent links and models are applied. + + + + + Scaling factor applied to the mesh + + diff --git a/sdformat/sdf/1.4/model.sdf b/sdformat/sdf/1.4/model.sdf new file mode 100644 index 0000000..2ec8b59 --- /dev/null +++ b/sdformat/sdf/1.4/model.sdf @@ -0,0 +1,26 @@ + + + The model element defines a complete robot or any other physical object. + + + A unique name for the model. This name must not match another model in the world. + + + + If set to true, the model is immovable. Otherwise the model is simulated in the dynamics engine. + + + + Allows a model to auto-disable, which is means the physics engine can skip updating the model when the model is at rest. This parameter is only used by models with no joints. + + + + A position and orientation in the global coordinate frame for the model. Position(x,y,z) and rotation (roll, pitch yaw) in the global coordinate frame. + + + + + + + + diff --git a/sdformat/sdf/1.4/noise.sdf b/sdformat/sdf/1.4/noise.sdf new file mode 100644 index 0000000..0542422 --- /dev/null +++ b/sdformat/sdf/1.4/noise.sdf @@ -0,0 +1,31 @@ + + The properties of a sensor noise model. + + + + The type of noise. Currently supported types are: + "none" (no noise). + "gaussian" (draw noise values independently for each measurement from a Gaussian distribution). + "gaussian_quantized" ("gaussian" plus quantization of outputs (ie. rounding)) + + + + For type "gaussian*", the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian*", the standard deviation of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian*", the mean of the Gaussian distribution from which bias values are drawn. + + + For type "gaussian*", the standard deviation of the Gaussian distribution from which bias values are drawn. + + + + For type "gaussian_quantized", the precision of output signals. A value + of zero implies infinite precision / no quantization. + + + + diff --git a/sdformat/sdf/1.4/physics.sdf b/sdformat/sdf/1.4/physics.sdf new file mode 100644 index 0000000..7ee4ae7 --- /dev/null +++ b/sdformat/sdf/1.4/physics.sdf @@ -0,0 +1,201 @@ + + + The physics tag specifies the type and properties of the dynamics engine. + + + The type of the dynamics engine. Current options are ode, bullet, simbody and rtql8. Defaults to ode if left unspecified. + + + + Maximum time step size at which every system in simulation can interact with the states of the world. (was physics.sdf's dt). + + + + + target simulation speedup factor, defined by ratio of simulation time to real-time. + + + + + Rate at which to update the physics engine (UpdatePhysics calls per real-time second). (was physics.sdf's update_rate). + + + + Maximum number of contacts allowed between two entities. This value can be over ridden by a max_contacts element in a collision element. + + + + The gravity vector + + + + Simbody specific physics properties + + (Currently not used in simbody) The time duration which advances with each iteration of the dynamics engine, this has to be no bigger than max_step_size under physics block. If left unspecified, min_step_size defaults to max_step_size. + + + Roughly the relative error of the system. + -LOG(accuracy) is roughly the number of significant digits. + + + Tolerable "slip" velocity allowed by the solver when static + friction is supposed to hold object in place. + + + vc + Assume real COR=1 when v=0. + e_min = given minimum COR, at v >= vp (a.k.a. plastic_coef_restitution) + d = slope = (1-e_min)/vp + OR, e_min = 1 - d*vp + e_max = maximum COR = 1-d*vc, reached at v=vc + e = 0, v <= vc + = 1 - d*v, vc < v < vp + = e_min, v >= vp + + dissipation factor = d*min(v,vp) [compliant] + cor = e [rigid] + + Combining rule e = 0, e1==e2==0 + = 2*e1*e2/(e1+e2), otherwise]]> + + + + Default contact material stiffness + (force/dist or torque/radian). + + + dissipation coefficient to be used in compliant contact; + if not given it is (1-min_cor)/plastic_impact_velocity + + + + this is the COR to be used at high velocities for rigid + impacts; if not given it is 1 - dissipation*plastic_impact_velocity + + + + + smallest impact velocity at which min COR is reached; set + to zero if you want the min COR always to be used + + + + static friction (mu_s) as described by this plot: http://gazebosim.org/wiki/File:Stribeck_friction.png + + + dynamic friction (mu_d) as described by this plot: http://gazebosim.org/wiki/File:Stribeck_friction.png + + + viscous friction (mu_v) with units of (1/velocity) as described by this plot: http://gazebosim.org/wiki/File:Stribeck_friction.png + + + + for rigid impacts only, impact velocity at which + COR is set to zero; normally inherited from global default but can + be overridden here. Combining rule: use larger velocity + + + + This is the largest slip velocity at which + we'll consider a transition to stiction. Normally inherited + from a global default setting. For a continuous friction model + this is the velocity at which the max static friction force + is reached. Combining rule: use larger velocity + + + + + + + Bullet specific physics properties + + + + One of the following types: sequential_impulse only. + + + The time duration which advances with each iteration of the dynamics engine, this has to be no bigger than max_step_size under physics block. If left unspecified, min_step_size defaults to max_step_size. + + + Number of iterations for each step. A higher number produces greater accuracy at a performance cost. + + + Set the successive over-relaxation parameter. + + + + + Bullet constraint parameters. + + Constraint force mixing parameter. See the ODE page for more information. + + + Error reduction parameter. See the ODE page for more information. + + + The depth of the surface layer around all geometry objects. Contacts are allowed to sink into the surface layer up to the given depth before coming to rest. The default value is zero. Increasing this to some small value (e.g. 0.001) can help prevent jittering problems due to contacts being repeatedly made and broken. + + + Similar to ODE's max_vel implementation. See http://web.archive.org/web/20120430155635/http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + Similar to ODE's max_vel implementation. See http://web.archive.org/web/20120430155635/http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + + + + ODE specific physics properties + + + + One of the following types: world, quick + + + The time duration which advances with each iteration of the dynamics engine, this has to be no bigger than max_step_size under physics block. If left unspecified, min_step_size defaults to max_step_size. + + + Number of iterations for each step. A higher number produces greater accuracy at a performance cost. + + + Experimental parameter. + + + Set the successive over-relaxation parameter. + + + + Flag to enable dynamic rescaling of moment of inertia in constrained directions. + See gazebo pull request 1114 for the implementation of this feature. + https://bitbucket.org/osrf/gazebo/pull-request/1114 + + + + + + ODE constraint parameters. + + Constraint force mixing parameter. See the ODE page for more information. + + + Error reduction parameter. See the ODE page for more information. + + + The maximum correcting velocities allowed when resolving contacts. + + + The depth of the surface layer around all geometry objects. Contacts are allowed to sink into the surface layer up to the given depth before coming to rest. The default value is zero. Increasing this to some small value (e.g. 0.001) can help prevent jittering problems due to contacts being repeatedly made and broken. + + + + diff --git a/sdformat/sdf/1.4/plane_shape.sdf b/sdformat/sdf/1.4/plane_shape.sdf new file mode 100644 index 0000000..35bca28 --- /dev/null +++ b/sdformat/sdf/1.4/plane_shape.sdf @@ -0,0 +1,9 @@ + + Plane shape + + Normal direction for the plane + + + Length of each side of the plane + + diff --git a/sdformat/sdf/1.4/plugin.sdf b/sdformat/sdf/1.4/plugin.sdf new file mode 100644 index 0000000..26405ff --- /dev/null +++ b/sdformat/sdf/1.4/plugin.sdf @@ -0,0 +1,13 @@ + + + A plugin is a dynamically loaded chunk of code. It can exist as a child of world, model, and sensor. + + A unique name for the plugin, scoped to its parent. + + + Name of the shared library to load. If the filename is not a full path name, the file will be searched for in the configuration paths. + + + This is a special element that should not be specified in an SDF file. It automatically copies child elements into the SDF element so that a plugin can access the data. + + diff --git a/sdformat/sdf/1.4/projector.sdf b/sdformat/sdf/1.4/projector.sdf new file mode 100644 index 0000000..9eabca9 --- /dev/null +++ b/sdformat/sdf/1.4/projector.sdf @@ -0,0 +1,32 @@ + + + + Name of the projector + + + + Texture name + + + + Pose of the projector + + + + + Field of view + + + + + Near clip distance + + + + + far clip distance + + + + + diff --git a/sdformat/sdf/1.4/ray.sdf b/sdformat/sdf/1.4/ray.sdf new file mode 100644 index 0000000..5ffeea3 --- /dev/null +++ b/sdformat/sdf/1.4/ray.sdf @@ -0,0 +1,73 @@ + + These elements are specific to the ray (laser) sensor. + + + + + + + + The number of simulated rays to generate per complete laser sweep cycle. + + + + This number is multiplied by samples to determine the number of range data points returned. If resolution is less than one, range data is interpolated. If resolution is greater than one, range data is averaged. + + + + + + + + Must be greater or equal to min_angle + + + + + + + + The number of simulated rays to generate per complete laser sweep cycle. + + + + This number is multiplied by samples to determine the number of range data points returned. If resolution is less than one, range data is interpolated. If resolution is greater than one, range data is averaged. + + + + + + + + Must be greater or equal to min_angle + + + + + + + specifies range properties of each simulated ray + + The minimum distance for each ray. + + + The maximum distance for each ray. + + + Linear resolution of each ray. + + + + + The properties of the noise model that should be applied to generated scans + + The type of noise. Currently supported types are: "gaussian" (draw noise values independently for each beam from a Gaussian distribution). + + + For type "gaussian," the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which noise values are drawn. + + + diff --git a/sdformat/sdf/1.4/rfid.sdf b/sdformat/sdf/1.4/rfid.sdf new file mode 100644 index 0000000..61351dd --- /dev/null +++ b/sdformat/sdf/1.4/rfid.sdf @@ -0,0 +1,2 @@ + + diff --git a/sdformat/sdf/1.4/rfidtag.sdf b/sdformat/sdf/1.4/rfidtag.sdf new file mode 100644 index 0000000..55699dc --- /dev/null +++ b/sdformat/sdf/1.4/rfidtag.sdf @@ -0,0 +1,2 @@ + + diff --git a/sdformat/sdf/1.4/road.sdf b/sdformat/sdf/1.4/road.sdf new file mode 100644 index 0000000..3549b24 --- /dev/null +++ b/sdformat/sdf/1.4/road.sdf @@ -0,0 +1,15 @@ + + + + Name of the road + + + + Width of the road + + + + A series of points define the path of the road. + + + diff --git a/sdformat/sdf/1.4/root.sdf b/sdformat/sdf/1.4/root.sdf new file mode 100644 index 0000000..8dc9d3f --- /dev/null +++ b/sdformat/sdf/1.4/root.sdf @@ -0,0 +1,13 @@ + + SDF base element. + + + Version number of the SDF format. + + + + + + + + diff --git a/sdformat/sdf/1.4/scene.sdf b/sdformat/sdf/1.4/scene.sdf new file mode 100644 index 0000000..c4a4e84 --- /dev/null +++ b/sdformat/sdf/1.4/scene.sdf @@ -0,0 +1,78 @@ + + + Specifies the look of the environment. + + + Color of the ambient light. + + + + Color of the background. + + + + Properties for the sky + + Time of day [0..24] + + + Sunrise time [0..24] + + + Sunset time [0..24] + + + + Sunset time [0..24] + + Speed of the clouds + + + + Direction of the cloud movement + + + Density of clouds + + + + Average size of the clouds + + + + Ambient cloud color + + + + + + Enable/disable shadows + + + + Controls fog + + Fog color + + + Fog type: constant, linear, quadratic + + + Distance to start of fog + + + Distance to end of fog + + + Density of fog + + + + + Enable/disable the grid + + + diff --git a/sdformat/sdf/1.4/sensor.sdf b/sdformat/sdf/1.4/sensor.sdf new file mode 100644 index 0000000..03d982a --- /dev/null +++ b/sdformat/sdf/1.4/sensor.sdf @@ -0,0 +1,45 @@ + + + The sensor tag describes the type and properties of a sensor. + + + A unique name for the sensor. This name must not match another model in the model. + + + + The type name of the sensor. By default, SDF supports types camera, depth, multicamera, contact, gps, imu, ir and ray. + + + + If true the sensor will always be updated according to the update rate. + + + + The frequency at which the sensor data is generated. If left unspecified, the sensor will generate data every cycle. + + + + If true, the sensor is visualized in the GUI + + + + This is the pose of the sensor, relative to the parent link reference frame. + + + + Name of the topic on which data is published. This is necessary for visualization + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.4/server.sdf b/sdformat/sdf/1.4/server.sdf new file mode 100644 index 0000000..47d1606 --- /dev/null +++ b/sdformat/sdf/1.4/server.sdf @@ -0,0 +1,29 @@ + + + The distributed tag specifies the ip and port of the remote server. + + + The type of the distribution(0:client or 1:server). + + + + The ip of the remote server. + + + + The flag of the remote server. + + + + the port of the remote port + + + + the port of the remote port + + + + the port of the remote port + + + diff --git a/sdformat/sdf/1.4/sonar.sdf b/sdformat/sdf/1.4/sonar.sdf new file mode 100644 index 0000000..d27017f --- /dev/null +++ b/sdformat/sdf/1.4/sonar.sdf @@ -0,0 +1,13 @@ + + These elements are specific to the sonar sensor. + + Minimum range + + + Max range + + + + Radius of the sonar cone at max range. + + diff --git a/sdformat/sdf/1.4/sphere_shape.sdf b/sdformat/sdf/1.4/sphere_shape.sdf new file mode 100644 index 0000000..73ad03e --- /dev/null +++ b/sdformat/sdf/1.4/sphere_shape.sdf @@ -0,0 +1,6 @@ + + Sphere shape + + radius of the sphere + + diff --git a/sdformat/sdf/1.4/spherical_coordinates.sdf b/sdformat/sdf/1.4/spherical_coordinates.sdf new file mode 100644 index 0000000..e6c8c96 --- /dev/null +++ b/sdformat/sdf/1.4/spherical_coordinates.sdf @@ -0,0 +1,39 @@ + + + + Name of planetary surface model, used to determine the surface altitude + at a given latitude and longitude. The default is an ellipsoid model of + the earth based on the WGS-84 standard. It is used in Gazebo's GPS sensor + implementation. + + + + + + Geodetic latitude at origin of gazebo reference frame, specified + in units of degrees. + + + + + + Longitude at origin of gazebo reference frame, specified in units + of degrees. + + + + + + Elevation of origin of gazebo reference frame, specified in meters. + + + + + + Heading offset of gazebo reference frame, measured as angle between + East and gazebo x axis, or equivalently, the angle between North and + gazebo y axis. The angle is specified in degrees. + + + + diff --git a/sdformat/sdf/1.4/state.sdf b/sdformat/sdf/1.4/state.sdf new file mode 100644 index 0000000..01d3c63 --- /dev/null +++ b/sdformat/sdf/1.4/state.sdf @@ -0,0 +1,101 @@ + + + + + Name of the world this state applies to + + + + Simulation time stamp of the state [seconds nanoseconds] + + + + Wall time stamp of the state [seconds nanoseconds] + + + + Real time stamp of the state [seconds nanoseconds] + + + + A list of new model names + + + + + A list of deleted model names + + The name of a deleted model + + + + + + + Model state + + + Name of the model + + + + Pose of the model + + + + Joint angle + + + Name of the joint + + + + + Index of the axis. + + + Angle of an axis + + + + + + Link state + + + Name of the link + + + + Pose of the link relative to the model + + + + Velocity of the link + + + + Acceleration of the link + + + + Force applied to the link + + + + Collision state + + + Name of the collision + + + + Pose of the link relative to the model + + + + + + + diff --git a/sdformat/sdf/1.4/surface.sdf b/sdformat/sdf/1.4/surface.sdf new file mode 100644 index 0000000..5e9519f --- /dev/null +++ b/sdformat/sdf/1.4/surface.sdf @@ -0,0 +1,127 @@ + + The surface parameters + + + + Bounciness coefficient of restitution, from [0...1], where 0=no bounciness. + + + Bounce capture velocity, below which effective coefficient of restitution is 0. + + + + + + + ODE friction parameters + + Coefficient of friction in the range of [0..1]. + + + Second coefficient of friction in the range of [0..1] + + + 3-tuple specifying direction of mu1 in the collision local reference frame. + + + Force dependent slip direction 1 in collision local frame, between the range of [0..1]. + + + Force dependent slip direction 2 in collision local frame, between the range of [0..1]. + + + + + Coefficient of friction in the range of [0..1]. + + + Coefficient of friction in the range of [0..1]. + + + 3-tuple specifying direction of mu1 in the collision local reference frame. + + + coefficient of friction in the range of [0..1] + + + + + + + + Flag to disable contact force generation, while still allowing collision checks and contact visualization to occur. + + + Bitmask for collision filtering when collide_without_contact is on + + + + Bitmask for collision filtering. This will override collide_without_contact + + + + ODE contact parameters + + Soft constraint force mixing. + + + Soft error reduction parameter + + + dynamically "stiffness"-equivalent coefficient for contact joints + + + dynamically "damping"-equivalent coefficient for contact joints + + + maximum contact correction velocity truncation term. + + + minimum allowable depth before contact correction impulse is applied + + + + Bullet contact parameters + + Soft constraint force mixing. + + + Soft error reduction parameter + + + dynamically "stiffness"-equivalent coefficient for contact joints + + + dynamically "damping"-equivalent coefficient for contact joints + + + Similar to ODE's max_vel implementation. See http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + Similar to ODE's max_vel implementation. See http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + + + + + + soft contact pamameters based on paper: + http://www.cc.gatech.edu/graphics/projects/Sumit/homepage/papers/sigasia11/jain_softcontacts_siga11.pdf + + + This is variable k_v in the soft contacts paper. Its unit is N/m. + + + This is variable k_e in the soft contacts paper. Its unit is N/m. + + + Viscous damping of point velocity in body frame. Its unit is N/m/s. + + + Fraction of mass to be distributed among deformable nodes. + + + + + diff --git a/sdformat/sdf/1.4/transceiver.sdf b/sdformat/sdf/1.4/transceiver.sdf new file mode 100644 index 0000000..9f05b06 --- /dev/null +++ b/sdformat/sdf/1.4/transceiver.sdf @@ -0,0 +1,34 @@ + + These elements are specific to a wireless transceiver. + + + Service set identifier (network name) + + + + Specifies the frequency of transmission in MHz + + + + Only a frequency range is filtered. Here we set the lower bound (MHz). + + + + + Only a frequency range is filtered. Here we set the upper bound (MHz). + + + + + Specifies the antenna gain in dBi + + + + Specifies the transmission power in dBm + + + + Mininum received signal power in dBm + + + diff --git a/sdformat/sdf/1.4/urdf.sdf b/sdformat/sdf/1.4/urdf.sdf new file mode 100644 index 0000000..6068d5c --- /dev/null +++ b/sdformat/sdf/1.4/urdf.sdf @@ -0,0 +1,19 @@ + + + The robot element defines a complete robot or any other physical object using URDF. + + + A unique name for the model. This name must not match another model in the world. + + + + A position and orientation in the global coordinate frame for the model. Position(x,y,z) and rotation (roll, pitch yaw) in the global coordinate frame. + + + + + + + + + diff --git a/sdformat/sdf/1.4/visual.sdf b/sdformat/sdf/1.4/visual.sdf new file mode 100644 index 0000000..644bff4 --- /dev/null +++ b/sdformat/sdf/1.4/visual.sdf @@ -0,0 +1,75 @@ + + + The visual properties of the link. This element specifies the shape of the object (box, cylinder, etc.) for visualization purposes. + + + Unique name for the visual element within the scope of the parent link. + + + + If true the visual will cast shadows. + + + + will be implemented in the future release. + + + + The amount of transparency( 0=opaque, 1 = fully transparent) + + + + The reference frame of the visual element, relative to the reference frame of the link. + + + + The material of the visual element. + + + Name of material from an installed script file. This will override the color element if the script exists. + + + URI of the material script file + + + + Name of the script within the script file + + + + + + + + vertex, pixel, normal_map_objectspace, normal_map_tangentspace + + + + filename of the normal map + + + + + If false, dynamic lighting will be disabled + + + + The ambient color of a material specified by set of four numbers representing red/green/blue, each in the range of [0,1]. + + + + The diffuse color of a material specified by set of four numbers representing red/green/blue/alpha, each in the range of [0,1]. + + + + The specular color of a material specified by set of four numbers representing red/green/blue/alpha, each in the range of [0,1]. + + + + The emissive color of a material specified by set of four numbers representing red/green/blue, each in the range of [0,1]. + + + + + + diff --git a/sdformat/sdf/1.4/world.sdf b/sdformat/sdf/1.4/world.sdf new file mode 100644 index 0000000..a0223ad --- /dev/null +++ b/sdformat/sdf/1.4/world.sdf @@ -0,0 +1,66 @@ + + The world element encapsulates an entire world description including: models, scene, physics, joints, and plugins + + + Unique name of the world + + + + Global audio properties. + + + Device to use for audio playback. A value of "default" will use the system's default audio device. Otherwise, specify a an audio device file" + + + + + The wind tag specifies the type and properties of the wind. + + + Linear velocity of the wind. + + + + + Include resources from a URI + + URI to a resource, such as a model + + + + Override the name of the included model. + + + + Override the static value of the included model. + + + + + + + The gravity vector in m/s^2, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + The magnetic vector in Tesla, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.5/1_4.convert b/sdformat/sdf/1.5/1_4.convert new file mode 100644 index 0000000..8c6a864 --- /dev/null +++ b/sdformat/sdf/1.5/1_4.convert @@ -0,0 +1,43 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.5/CMakeLists.txt b/sdformat/sdf/1.5/CMakeLists.txt new file mode 100644 index 0000000..581b9c6 --- /dev/null +++ b/sdformat/sdf/1.5/CMakeLists.txt @@ -0,0 +1,80 @@ +set (sdfs + actor.sdf + altimeter.sdf + audio_source.sdf + audio_sink.sdf + battery.sdf + box_shape.sdf + camera.sdf + collision.sdf + contact.sdf + cylinder_shape.sdf + frame.sdf + forcetorque.sdf + geometry.sdf + gps.sdf + gripper.sdf + gui.sdf + heightmap_shape.sdf + image_shape.sdf + imu.sdf + inertial.sdf + joint.sdf + light.sdf + light_state.sdf + link.sdf + link_state.sdf + logical_camera.sdf + magnetometer.sdf + material.sdf + mesh_shape.sdf + model.sdf + model_state.sdf + noise.sdf + physics.sdf + plane_shape.sdf + plugin.sdf + polyline_shape.sdf + population.sdf + pose.sdf + projector.sdf + ray.sdf + rfidtag.sdf + rfid.sdf + road.sdf + root.sdf + scene.sdf + sensor.sdf + spherical_coordinates.sdf + sphere_shape.sdf + sonar.sdf + state.sdf + surface.sdf + transceiver.sdf + visual.sdf + world.sdf +) + +set (SDF_SCHEMA) + +foreach(FIL ${sdfs}) + get_filename_component(ABS_FIL ${FIL} ABSOLUTE) + get_filename_component(FIL_WE ${FIL} NAME_WE) + + list(APPEND SDF_SCHEMA "${CMAKE_CURRENT_BINARY_DIR}/${FIL_WE}.xsd") + + add_custom_command( + OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/${FIL_WE}.xsd" + COMMAND ${RUBY} ${CMAKE_SOURCE_DIR}/tools/xmlschema.rb + ARGS -s ${CMAKE_CURRENT_SOURCE_DIR} -i ${ABS_FIL} -o ${CMAKE_CURRENT_BINARY_DIR} + DEPENDS ${ABS_FIL} + COMMENT "Running xml schema compiler on ${FIL}" + VERBATIM) +endforeach() + +add_custom_target(schema1_5 ALL DEPENDS ${SDF_SCHEMA}) + +set_source_files_properties(${SDF_SCHEMA} PROPERTIES GENERATED TRUE) + +install(FILES 1_4.convert ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat/1.5) +install(FILES ${SDF_SCHEMA} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat/1.5) diff --git a/sdformat/sdf/1.5/actor.sdf b/sdformat/sdf/1.5/actor.sdf new file mode 100644 index 0000000..bb1fa41 --- /dev/null +++ b/sdformat/sdf/1.5/actor.sdf @@ -0,0 +1,87 @@ + + + + + + + + + + Actors should be static, in terms of physics simulation. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.5/altimeter.sdf b/sdformat/sdf/1.5/altimeter.sdf new file mode 100644 index 0000000..66ddee5 --- /dev/null +++ b/sdformat/sdf/1.5/altimeter.sdf @@ -0,0 +1,18 @@ + + These elements are specific to an altimeter sensor. + + + + Noise parameters for vertical position + + + + + + + Noise parameters for vertical velocity + + + + + diff --git a/sdformat/sdf/1.5/atmosphere.sdf b/sdformat/sdf/1.5/atmosphere.sdf new file mode 100644 index 0000000..641facc --- /dev/null +++ b/sdformat/sdf/1.5/atmosphere.sdf @@ -0,0 +1,21 @@ + + + The atmosphere tag specifies the type and properties of the atmosphere model. + + + The type of the atmosphere engine. Current options are adiabatic. Defaults to adiabatic if left unspecified. + + + + Temperature at sea level in kelvins. + + + + Pressure at sea level in pascals. + + + + Temperature gradient with respect to increasing altitude at sea level in units of K/m. + + + diff --git a/sdformat/sdf/1.5/audio_sink.sdf b/sdformat/sdf/1.5/audio_sink.sdf new file mode 100644 index 0000000..d3bd071 --- /dev/null +++ b/sdformat/sdf/1.5/audio_sink.sdf @@ -0,0 +1,4 @@ + + + An audio sink. + diff --git a/sdformat/sdf/1.5/audio_source.sdf b/sdformat/sdf/1.5/audio_source.sdf new file mode 100644 index 0000000..8f8c23d --- /dev/null +++ b/sdformat/sdf/1.5/audio_source.sdf @@ -0,0 +1,31 @@ + + + An audio source. + + + URI of the audio media. + + + + Pitch for the audio media, in Hz + + + + Gain for the audio media, in dB. + + + + List of collision objects that will trigger audio playback. + + Name of child collision element that will trigger audio playback. + + + + + True to make the audio source loop playback. + + + + + + diff --git a/sdformat/sdf/1.5/battery.sdf b/sdformat/sdf/1.5/battery.sdf new file mode 100644 index 0000000..dc6f8de --- /dev/null +++ b/sdformat/sdf/1.5/battery.sdf @@ -0,0 +1,12 @@ + + + Description of a battery. + + + Unique name for the battery. + + + + Initial voltage in volts. + + diff --git a/sdformat/sdf/1.5/box_shape.sdf b/sdformat/sdf/1.5/box_shape.sdf new file mode 100644 index 0000000..826ab37 --- /dev/null +++ b/sdformat/sdf/1.5/box_shape.sdf @@ -0,0 +1,6 @@ + + Box shape + + The three side lengths of the box. The origin of the box is in its geometric center (inside the center of the box). + + diff --git a/sdformat/sdf/1.5/camera.sdf b/sdformat/sdf/1.5/camera.sdf new file mode 100644 index 0000000..cf46793 --- /dev/null +++ b/sdformat/sdf/1.5/camera.sdf @@ -0,0 +1,130 @@ + + These elements are specific to camera sensors. + + + An optional name for the camera. + + + + Horizontal field of view + + + + The image size in pixels and format. + + Width in pixels + + + Height in pixels + + + (L8|R8G8B8|B8G8R8|BAYER_RGGB8|BAYER_BGGR8|BAYER_GBRG8|BAYER_GRBG8) + + + + + The near and far clip planes. Objects closer or farther than these planes are not rendered. + + + Near clipping plane + + + + Far clipping plane + + + + + Enable or disable saving of camera frames. + + True = saving enabled + + + The path name which will hold the frame data. If path name is relative, then directory is relative to current working directory. + + + + + Depth camera parameters + + Type of output + + + + + The properties of the noise model that should be applied to generated images + + The type of noise. Currently supported types are: "gaussian" (draw additive noise values independently for each pixel from a Gaussian distribution). + + + For type "gaussian," the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which noise values are drawn. + + + + + Lens distortion to be applied to camera images. See http://en.wikipedia.org/wiki/Distortion_(optics)#Software_correction + + The radial distortion coefficient k1 + + + The radial distortion coefficient k2 + + + The radial distortion coefficient k3 + + + The tangential distortion coefficient p1 + + + The tangential distortion coefficient p2 + + + The distortion center or principal point + + + + + Lens projection description + + + Type of the lens mapping. Supported values are gnomonical, stereographic, equidistant, equisolid_angle, orthographic, custom. For gnomonical (perspective) projection, it is recommended to specify a horizontal_fov of less than or equal to 90° + + + If true the image will be scaled to fit horizontal FOV, otherwise it will be shown according to projection type parameters + + + + Definition of custom mapping function in a form of r=c1*f*fun(theta/c2 + c3). See https://en.wikipedia.org/wiki/Fisheye_lens#Mapping_function + + Linear scaling constant + + + Angle scaling constant + + + Angle offset constant + + + Focal length of the optical system. Note: It's not a focal length of the lens in a common sense! This value is ignored if 'scale_to_fov' is set to true + + + Possible values are 'sin', 'tan' and 'id' + + + + + Everything outside of the specified angle will be hidden, 90° by default + + + + Resolution of the environment cube map used to draw the world + + + + + + + diff --git a/sdformat/sdf/1.5/collision.sdf b/sdformat/sdf/1.5/collision.sdf new file mode 100644 index 0000000..09c4eac --- /dev/null +++ b/sdformat/sdf/1.5/collision.sdf @@ -0,0 +1,23 @@ + + + The collision properties of a link. Note that this can be different from the visual properties of a link, for example, simpler collision models are often used to reduce computation time. + + + Unique name for the collision element within the scope of the parent link. + + + + intensity value returned by laser sensor. + + + + Maximum number of contacts allowed between two entities. This value overrides the max_contacts element defined in physics. + + + + + + + + + diff --git a/sdformat/sdf/1.5/collision_engine.sdf b/sdformat/sdf/1.5/collision_engine.sdf new file mode 100644 index 0000000..67dbc70 --- /dev/null +++ b/sdformat/sdf/1.5/collision_engine.sdf @@ -0,0 +1,17 @@ + + + The collision_engine tag specifies the type and properties of the collision detection engine. + + + + The type of the collision detection engine. Current default in ODE is OPCODE. + + + + + + The type of the collision detection engine. + + + + diff --git a/sdformat/sdf/1.5/contact.sdf b/sdformat/sdf/1.5/contact.sdf new file mode 100644 index 0000000..d1cde50 --- /dev/null +++ b/sdformat/sdf/1.5/contact.sdf @@ -0,0 +1,12 @@ + + These elements are specific to the contact sensor. + + + name of the collision element within a link that acts as the contact sensor. + + + + Topic on which contact data is published. + + + diff --git a/sdformat/sdf/1.5/cylinder_shape.sdf b/sdformat/sdf/1.5/cylinder_shape.sdf new file mode 100644 index 0000000..8e25a53 --- /dev/null +++ b/sdformat/sdf/1.5/cylinder_shape.sdf @@ -0,0 +1,9 @@ + + Cylinder shape + + Radius of the cylinder + + + Length of the cylinder + + diff --git a/sdformat/sdf/1.5/distribution.sdf b/sdformat/sdf/1.5/distribution.sdf new file mode 100644 index 0000000..924c2f5 --- /dev/null +++ b/sdformat/sdf/1.5/distribution.sdf @@ -0,0 +1,19 @@ + + + The distribution tag specifies the local ID of this gazebo and port of the remote server. + + + The ID of the gazebo. + + + + The flag of the remote server. + + + + the port of the remote port + + + + + diff --git a/sdformat/sdf/1.5/event.sdf b/sdformat/sdf/1.5/event.sdf new file mode 100644 index 0000000..16d5c20 --- /dev/null +++ b/sdformat/sdf/1.5/event.sdf @@ -0,0 +1,21 @@ + + + The parallel tag specifies the numbers of threads and tbb size of the block. + + + The type of parallel. + + + + The numbers of the threads. + + + + the size of block to tbb thread + + + + the type to block partion + + + diff --git a/sdformat/sdf/1.5/forcetorque.sdf b/sdformat/sdf/1.5/forcetorque.sdf new file mode 100644 index 0000000..08388cf --- /dev/null +++ b/sdformat/sdf/1.5/forcetorque.sdf @@ -0,0 +1,20 @@ + + These elements are specific to the force torque sensor. + + + Frame in which to report the wrench values. Currently supported frames are: + "parent" report the wrench expressed in the orientation of the parent link frame, + "child" report the wrench expressed in the orientation of the child link frame, + "sensor" report the wrench expressed in the orientation of the joint sensor frame. + Note that for each option the point with respect to which the + torque component of the wrench is expressed is the joint origin. + + + + + Direction of the wrench measured by the sensor. The supported options are: + "parent_to_child" if the measured wrench is the one applied by parent link on the child link, + "child_to_parent" if the measured wrench is the one applied by the child link on the parent link. + + + diff --git a/sdformat/sdf/1.5/frame.sdf b/sdformat/sdf/1.5/frame.sdf new file mode 100644 index 0000000..28eefc5 --- /dev/null +++ b/sdformat/sdf/1.5/frame.sdf @@ -0,0 +1,11 @@ + + + A frame of reference to which a pose is relative. + + + Name of the frame. This name must not match another frame defined inside the parent that this frame is attached to. + + + + + diff --git a/sdformat/sdf/1.5/gazeboid.sdf b/sdformat/sdf/1.5/gazeboid.sdf new file mode 100644 index 0000000..4cb7ae3 --- /dev/null +++ b/sdformat/sdf/1.5/gazeboid.sdf @@ -0,0 +1,17 @@ + + + The distributed tag specifies the ip and ID of the local gazebo. + + + The type of the distribution(0:client or 1:server). + + + + The ip of the local gazebo. + + + + model name in the local gazebo. + + + diff --git a/sdformat/sdf/1.5/geometry.sdf b/sdformat/sdf/1.5/geometry.sdf new file mode 100644 index 0000000..5fe95ed --- /dev/null +++ b/sdformat/sdf/1.5/geometry.sdf @@ -0,0 +1,18 @@ + + + The shape of the visual or collision object. + + + You can use the empty tag to make empty geometries. + + + + + + + + + + + + diff --git a/sdformat/sdf/1.5/gps.sdf b/sdformat/sdf/1.5/gps.sdf new file mode 100644 index 0000000..95e0049 --- /dev/null +++ b/sdformat/sdf/1.5/gps.sdf @@ -0,0 +1,40 @@ + + These elements are specific to the GPS sensor. + + + + Parameters related to GPS position measurement. + + + + Noise parameters for horizontal position measurement, in units of meters. + + + + + + Noise parameters for vertical position measurement, in units of meters. + + + + + + + + Parameters related to GPS position measurement. + + + + Noise parameters for horizontal velocity measurement, in units of meters/second. + + + + + + Noise parameters for vertical velocity measurement, in units of meters/second. + + + + + + diff --git a/sdformat/sdf/1.5/gripper.sdf b/sdformat/sdf/1.5/gripper.sdf new file mode 100644 index 0000000..12fd0b3 --- /dev/null +++ b/sdformat/sdf/1.5/gripper.sdf @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.5/gui.sdf b/sdformat/sdf/1.5/gui.sdf new file mode 100644 index 0000000..ecbe364 --- /dev/null +++ b/sdformat/sdf/1.5/gui.sdf @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + Set the type of projection for the camera. Valid values are "perspective" and "orthographic". + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.5/heightmap_shape.sdf b/sdformat/sdf/1.5/heightmap_shape.sdf new file mode 100644 index 0000000..087f4ca --- /dev/null +++ b/sdformat/sdf/1.5/heightmap_shape.sdf @@ -0,0 +1,40 @@ + + A heightmap based on a 2d grayscale image. + + URI to a grayscale image file + + + The size of the heightmap in world units. + When loading an image: "size" is used if present, otherwise defaults to 1x1x1. + When loading a DEM: "size" is used if present, otherwise defaults to true size of DEM. + + + + A position offset. + + + + The heightmap can contain multiple textures. The order of the texture matters. The first texture will appear at the lowest height, and the last texture at the highest height. Use blend to control the height thresholds and fade between textures. + + Size of the applied texture in meters. + + + Diffuse texture image filename + + + Normalmap texture image filename + + + + The blend tag controls how two adjacent textures are mixed. The number of blend elements should equal one less than the number of textures. + + Min height of a blend layer + + + Distance over which the blend occurs + + + + Set if the rendering engine will use terrain paging + + diff --git a/sdformat/sdf/1.5/image_shape.sdf b/sdformat/sdf/1.5/image_shape.sdf new file mode 100644 index 0000000..369de7c --- /dev/null +++ b/sdformat/sdf/1.5/image_shape.sdf @@ -0,0 +1,18 @@ + + Extrude a set of boxes from a grayscale image. + + URI of the grayscale image file + + + Scaling factor applied to the image + + + Grayscale threshold + + + Height of the extruded boxes + + + The amount of error in the model + + diff --git a/sdformat/sdf/1.5/imu.sdf b/sdformat/sdf/1.5/imu.sdf new file mode 100644 index 0000000..254431c --- /dev/null +++ b/sdformat/sdf/1.5/imu.sdf @@ -0,0 +1,82 @@ + + These elements are specific to the IMU sensor. + + + Topic on which data is published. + + + + These elements are specific to body-frame angular velocity, + which is expressed in radians per second + + Angular velocity about the X axis + + + + Angular velocity about the Y axis + + + + Angular velocity about the Z axis + + + + + + These elements are specific to body-frame linear acceleration, + which is expressed in meters per second squared + + Linear acceleration about the X axis + + + + Linear acceleration about the Y axis + + + + Linear acceleration about the Z axis + + + + + + + + The properties of the noise model that should be applied to generated data + + The type of noise. Currently supported types are: "gaussian" (draw noise values independently for each beam from a Gaussian distribution). + + + Noise parameters for angular rates. + + For type "gaussian," the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the mean of the Gaussian distribution from which bias values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which bias values are drawn. + + + + + Noise parameters for linear accelerations. + + For type "gaussian," the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the mean of the Gaussian distribution from which bias values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which bias values are drawn. + + + + + diff --git a/sdformat/sdf/1.5/inertial.sdf b/sdformat/sdf/1.5/inertial.sdf new file mode 100644 index 0000000..b8160bf --- /dev/null +++ b/sdformat/sdf/1.5/inertial.sdf @@ -0,0 +1,36 @@ + + + The inertial properties of the link. + + + The mass of the link. + + + + + + This is the pose of the inertial reference frame, relative to the specified reference frame. The origin of the inertial reference frame needs to be at the center of gravity. The axes of the inertial reference frame do not need to be aligned with the principal axes of the inertia. + + + + The 3x3 rotational inertia matrix. Because the rotational inertia matrix is symmetric, only 6 above-diagonal elements of this matrix are specified here, using the attributes ixx, ixy, ixz, iyy, iyz, izz. + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.5/joint.sdf b/sdformat/sdf/1.5/joint.sdf new file mode 100644 index 0000000..abc9750 --- /dev/null +++ b/sdformat/sdf/1.5/joint.sdf @@ -0,0 +1,232 @@ + + + A joint connections two links with kinematic and dynamic properties. + + + A unique name for the joint within the scope of the model. + + + + The type of joint, which must be one of the following: + (revolute) a hinge joint that rotates on a single axis with either a fixed or continuous range of motion, + (gearbox) geared revolute joints, + (revolute2) same as two revolute joints connected in series, + (prismatic) a sliding joint that slides along an axis with a limited range specified by upper and lower limits, + (ball) a ball and socket joint, + (screw) a single degree of freedom joint with coupled sliding and rotational motion, + (universal) like a ball joint, but constrains one degree of freedom, + (fixed) a joint with zero degrees of freedom that rigidly connects two links. + + + + + Name of the parent link + + + + Name of the child link + + + + Parameter for gearbox joints. Given theta_1 and theta_2 defined in description for gearbox_reference_body, theta_2 = -gearbox_ratio * theta_1. + + + + Parameter for gearbox joints. Gearbox ratio is enforced over two joint angles. First joint angle (theta_1) is the angle from the gearbox_reference_body to the parent link in the direction of the axis element and the second joint angle (theta_2) is the angle from the gearbox_reference_body to the child link in the direction of the axis2 element. + + + + Parameter for screw joints. + + + + + Parameters related to the axis of rotation for revolute joints, + the axis of translation for prismatic joints. + + + + Represents the x,y,z components of the axis unit vector. The axis is + expressed in the joint frame unless the use_parent_model_frame + flag is set to true. The vector should be normalized. + + + + + Flag to interpret the axis xyz element in the parent model frame instead + of joint frame. Provided for Gazebo compatibility + (see https://bitbucket.org/osrf/gazebo/issue/494 ). + + + + An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation. + + The physical velocity dependent viscous damping coefficient of the joint. + + + The physical static friction value of the joint. + + + The spring reference position for this joint axis. + + + The spring stiffness for this joint axis. + + + + specifies the limits of this joint + + An attribute specifying the lower joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute specifying the upper joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute for enforcing the maximum joint effort applied by Joint::SetForce. Limit is not enforced if value is negative. + + + (not implemented) An attribute for enforcing the maximum joint velocity. + + + + Joint stop stiffness. Support physics engines: SimBody. + + + + Joint stop dissipation. + + + + + + + + Parameters related to the second axis of rotation for revolute2 joints and universal joints. + + + + Represents the x,y,z components of the axis unit vector. The axis is + expressed in the joint frame unless the use_parent_model_frame + flag is set to true. The vector should be normalized. + + + + + Flag to interpret the axis xyz element in the parent model frame instead + of joint frame. Provided for Gazebo compatibility + (see https://bitbucket.org/osrf/gazebo/issue/494 ). + + + + An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation. + + The physical velocity dependent viscous damping coefficient of the joint. EXPERIMENTAL: if damping coefficient is negative and implicit_spring_damper is true, adaptive damping is used. + + + The physical static friction value of the joint. + + + The spring reference position for this joint axis. + + + The spring stiffness for this joint axis. + + + + + + + An attribute specifying the lower joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute specifying the upper joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute for enforcing the maximum joint effort applied by Joint::SetForce. Limit is not enforced if value is negative. + + + (not implemented) An attribute for enforcing the maximum joint velocity. + + + + Joint stop stiffness. Supported physics engines: SimBody. + + + + Joint stop dissipation. Supported physics engines: SimBody. + + + + + + + Parameters that are specific to a certain physics engine. + + Simbody specific parameters + + Force cut in the multibody graph at this joint. + + + + ODE specific parameters + + (DEPRECATION WARNING: In SDF 1.5 this tag will be replaced by the same tag directly under the physics-block. For now, this tag overrides the one outside of ode-block, but in SDF 1.5 this tag will be removed completely.) If provide feedback is set to true, ODE will compute the constraint forces at this joint. + + + + If cfm damping is set to true, ODE will use CFM to simulate damping, allows for infinite damping, and one additional constraint row (previously used for joint limit) is always active. + + + + If implicit_spring_damper is set to true, ODE will use CFM, ERP to simulate stiffness and damping, allows for infinite damping, and one additional constraint row (previously used for joint limit) is always active. This replaces cfm_damping parameter in sdf 1.4. + + + + Scale the excess for in a joint motor at joint limits. Should be between zero and one. + + + Constraint force mixing for constrained directions + + + Error reduction parameter for constrained directions + + + Bounciness of the limits + + + Maximum force or torque used to reach the desired velocity. + + + The desired velocity of the joint. Should only be set if you want the joint to move on load. + + + + + + Constraint force mixing parameter used by the joint stop + + + Error reduction parameter used by the joint stop + + + + + + + Suspension constraint force mixing parameter + + + Suspension error reduction parameter + + + + + + If provide feedback is set to true, physics engine will compute the constraint forces at this joint. For now, provide_feedback under ode block will override this tag and given user warning about the migration. provide_feedback under ode is scheduled to be removed in SDF 1.5. + + + + + + + diff --git a/sdformat/sdf/1.5/light.sdf b/sdformat/sdf/1.5/light.sdf new file mode 100644 index 0000000..336cd7f --- /dev/null +++ b/sdformat/sdf/1.5/light.sdf @@ -0,0 +1,60 @@ + + + The light element describes a light source. + + + A unique name for the light. + + + + The light type: point, directional, spot. + + + + When true, the light will cast shadows. + + + + + + + Diffuse light color + + + Specular light color + + + + Light attenuation + + Range of the light + + + The linear attenuation factor: 1 means attenuate evenly over the distance. + + + The constant attenuation factor: 1.0 means never attenuate, 0.0 is complete attenutation. + + + The quadratic attenuation factor: adds a curvature to the attenuation. + + + + + Direction of the light, only applicable for spot and directional lights. + + + + Spot light parameters + + Angle covered by the bright inner cone + + + Angle covered by the outer cone + + + The rate of falloff between the inner and outer cones. 1.0 means a linear falloff, less means slower falloff, higher means faster falloff. + + + + diff --git a/sdformat/sdf/1.5/light_state.sdf b/sdformat/sdf/1.5/light_state.sdf new file mode 100644 index 0000000..af128fd --- /dev/null +++ b/sdformat/sdf/1.5/light_state.sdf @@ -0,0 +1,11 @@ + + + Light state + + + Name of the light + + + + + diff --git a/sdformat/sdf/1.5/link.sdf b/sdformat/sdf/1.5/link.sdf new file mode 100644 index 0000000..d19c01b --- /dev/null +++ b/sdformat/sdf/1.5/link.sdf @@ -0,0 +1,46 @@ + + + A physical link with inertia, collision, and visual properties. A link must be a child of a model, and any number of links may exist in a model. + + + A unique name for the link within the scope of the model. + + + + If true, the link is affected by gravity. + + + + If true, the link can collide with other links in the model. Two links within a model will collide if link1.self_collide OR link2.self_collide. Links connected by a joint will never collide. + + + + If true, the link is kinematic only + + + + If true, the link will have 6DOF and be a direct child of world. + + + + Exponential damping of the link's velocity. + + Linear damping + + + Angular damping + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.5/link_state.sdf b/sdformat/sdf/1.5/link_state.sdf new file mode 100644 index 0000000..5269415 --- /dev/null +++ b/sdformat/sdf/1.5/link_state.sdf @@ -0,0 +1,41 @@ + + + Link state + + + Name of the link + + + + Velocity of the link. The x, y, z components of the pose + correspond to the linear velocity of the link, and the roll, pitch, yaw + components correspond to the angular velocity of the link + + + + + Acceleration of the link. The x, y, z components of the pose + correspond to the linear acceleration of the link, and the roll, + pitch, yaw components correspond to the angular acceleration of the link + + + + + Force and torque applied to the link. The x, y, z components + of the pose correspond to the force applied to the link, and the roll, + pitch, yaw components correspond to the torque applied to the link + + + + + Collision state + + + Name of the collision + + + + + + + diff --git a/sdformat/sdf/1.5/logical_camera.sdf b/sdformat/sdf/1.5/logical_camera.sdf new file mode 100644 index 0000000..de47703 --- /dev/null +++ b/sdformat/sdf/1.5/logical_camera.sdf @@ -0,0 +1,19 @@ + + These elements are specific to logical camera sensors. A logical camera reports objects that fall within a frustum. Computation should be performed on the CPU. + + + Near clipping distance of the view frustum + + + + Far clipping distance of the view frustum + + + + Aspect ratio of the near and far planes. This is the width divided by the height of the near or far planes. + + + + Horizontal field of view of the frustum, in radians. This is the angle between the frustum's vertex and the edges of the near or far plane. + + diff --git a/sdformat/sdf/1.5/magnetometer.sdf b/sdformat/sdf/1.5/magnetometer.sdf new file mode 100644 index 0000000..2f3bfee --- /dev/null +++ b/sdformat/sdf/1.5/magnetometer.sdf @@ -0,0 +1,21 @@ + + These elements are specific to a Magnetometer sensor. + + + Parameters related to the body-frame X axis of the magnetometer + + + + + + Parameters related to the body-frame Y axis of the magnetometer + + + + + + Parameters related to the body-frame Z axis of the magnetometer + + + + \ No newline at end of file diff --git a/sdformat/sdf/1.5/material.sdf b/sdformat/sdf/1.5/material.sdf new file mode 100644 index 0000000..137436e --- /dev/null +++ b/sdformat/sdf/1.5/material.sdf @@ -0,0 +1,47 @@ + + + The material of the visual element. + + + Name of material from an installed script file. This will override the color element if the script exists. + + + URI of the material script file + + + + Name of the script within the script file + + + + + + + vertex, pixel, normal_map_objectspace, normal_map_tangentspace + + + + filename of the normal map + + + + + If false, dynamic lighting will be disabled + + + + The ambient color of a material specified by set of four numbers representing red/green/blue, each in the range of [0,1]. + + + + The diffuse color of a material specified by set of four numbers representing red/green/blue/alpha, each in the range of [0,1]. + + + + The specular color of a material specified by set of four numbers representing red/green/blue/alpha, each in the range of [0,1]. + + + + The emissive color of a material specified by set of four numbers representing red/green/blue, each in the range of [0,1]. + + diff --git a/sdformat/sdf/1.5/mesh_shape.sdf b/sdformat/sdf/1.5/mesh_shape.sdf new file mode 100644 index 0000000..61bce76 --- /dev/null +++ b/sdformat/sdf/1.5/mesh_shape.sdf @@ -0,0 +1,20 @@ + + Mesh shape + + Mesh uri + + + + Use a named submesh. The submesh must exist in the mesh specified by the uri + + Name of the submesh within the parent mesh + + + Set to true to center the vertices of the submesh at 0,0,0. This will effectively remove any transformations on the submesh before the poses from parent links and models are applied. + + + + + Scaling factor applied to the mesh + + diff --git a/sdformat/sdf/1.5/model.sdf b/sdformat/sdf/1.5/model.sdf new file mode 100644 index 0000000..5f7b583 --- /dev/null +++ b/sdformat/sdf/1.5/model.sdf @@ -0,0 +1,54 @@ + + + The model element defines a complete robot or any other physical object. + + + A unique name for the model. This name must not match another model in the world. + + + + If set to true, the model is immovable. Otherwise the model is simulated in the dynamics engine. + + + + If set to true, all links in the model will collide with each other (except those connected by a joint). Can be overridden by the link or collision element self_collide property. Two links within a model will collide if link1.self_collide OR link2.self_collide. Links connected by a joint will never collide. + + + + Allows a model to auto-disable, which is means the physics engine can skip updating the model when the model is at rest. This parameter is only used by models with no joints. + + + + + + + + + + + Include resources from a URI. This can be used to nest models. + + URI to a resource, such as a model + + + + Override the pose of the included model. A position and orientation in the global coordinate frame for the model. Position(x,y,z) and rotation (roll, pitch yaw) in the global coordinate frame. + + + + Override the name of the included model. + + + + Override the static value of the included model. + + + + + A nested model element + + A unique name for the model. This name must not match another nested model in the same level as this model. + + + + diff --git a/sdformat/sdf/1.5/model_state.sdf b/sdformat/sdf/1.5/model_state.sdf new file mode 100644 index 0000000..27b65e8 --- /dev/null +++ b/sdformat/sdf/1.5/model_state.sdf @@ -0,0 +1,37 @@ + + + Model state + + + Name of the model + + + + Joint angle + + + Name of the joint + + + + + Index of the axis. + + + Angle of an axis + + + + + A nested model state element + + Name of the model. + + + + + + + + + diff --git a/sdformat/sdf/1.5/noise.sdf b/sdformat/sdf/1.5/noise.sdf new file mode 100644 index 0000000..0542422 --- /dev/null +++ b/sdformat/sdf/1.5/noise.sdf @@ -0,0 +1,31 @@ + + The properties of a sensor noise model. + + + + The type of noise. Currently supported types are: + "none" (no noise). + "gaussian" (draw noise values independently for each measurement from a Gaussian distribution). + "gaussian_quantized" ("gaussian" plus quantization of outputs (ie. rounding)) + + + + For type "gaussian*", the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian*", the standard deviation of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian*", the mean of the Gaussian distribution from which bias values are drawn. + + + For type "gaussian*", the standard deviation of the Gaussian distribution from which bias values are drawn. + + + + For type "gaussian_quantized", the precision of output signals. A value + of zero implies infinite precision / no quantization. + + + + diff --git a/sdformat/sdf/1.5/physics.sdf b/sdformat/sdf/1.5/physics.sdf new file mode 100644 index 0000000..7814b98 --- /dev/null +++ b/sdformat/sdf/1.5/physics.sdf @@ -0,0 +1,213 @@ + + + The physics tag specifies the type and properties of the dynamics engine. + + + The name of this set of physics parameters. + + + + If true, this physics element is set as the default physics profile for the world. If multiple default physics elements exist, the first element marked as default is chosen. If no default physics element exists, the first physics element is chosen. + + + + The type of the dynamics engine. Current options are ode, bullet, simbody and rtql8. Defaults to ode if left unspecified. + + + + Maximum time step size at which every system in simulation can interact with the states of the world. (was physics.sdf's dt). + + + + + target simulation speedup factor, defined by ratio of simulation time to real-time. + + + + + Rate at which to update the physics engine (UpdatePhysics calls per real-time second). (was physics.sdf's update_rate). + + + + Maximum number of contacts allowed between two entities. This value can be over ridden by a max_contacts element in a collision element. + + + + The gravity vector in m/s^2, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + The magnetic vector in Tesla, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + Simbody specific physics properties + + (Currently not used in simbody) The time duration which advances with each iteration of the dynamics engine, this has to be no bigger than max_step_size under physics block. If left unspecified, min_step_size defaults to max_step_size. + + + Roughly the relative error of the system. + -LOG(accuracy) is roughly the number of significant digits. + + + Tolerable "slip" velocity allowed by the solver when static + friction is supposed to hold object in place. + + + vc + Assume real COR=1 when v=0. + e_min = given minimum COR, at v >= vp (a.k.a. plastic_coef_restitution) + d = slope = (1-e_min)/vp + OR, e_min = 1 - d*vp + e_max = maximum COR = 1-d*vc, reached at v=vc + e = 0, v <= vc + = 1 - d*v, vc < v < vp + = e_min, v >= vp + + dissipation factor = d*min(v,vp) [compliant] + cor = e [rigid] + + Combining rule e = 0, e1==e2==0 + = 2*e1*e2/(e1+e2), otherwise]]> + + + + Default contact material stiffness + (force/dist or torque/radian). + + + dissipation coefficient to be used in compliant contact; + if not given it is (1-min_cor)/plastic_impact_velocity + + + + this is the COR to be used at high velocities for rigid + impacts; if not given it is 1 - dissipation*plastic_impact_velocity + + + + + smallest impact velocity at which min COR is reached; set + to zero if you want the min COR always to be used + + + + static friction (mu_s) as described by this plot: http://gazebosim.org/wiki/File:Stribeck_friction.png + + + dynamic friction (mu_d) as described by this plot: http://gazebosim.org/wiki/File:Stribeck_friction.png + + + viscous friction (mu_v) with units of (1/velocity) as described by this plot: http://gazebosim.org/wiki/File:Stribeck_friction.png + + + + for rigid impacts only, impact velocity at which + COR is set to zero; normally inherited from global default but can + be overridden here. Combining rule: use larger velocity + + + + This is the largest slip velocity at which + we'll consider a transition to stiction. Normally inherited + from a global default setting. For a continuous friction model + this is the velocity at which the max static friction force + is reached. Combining rule: use larger velocity + + + + + + + Bullet specific physics properties + + + + One of the following types: sequential_impulse only. + + + The time duration which advances with each iteration of the dynamics engine, this has to be no bigger than max_step_size under physics block. If left unspecified, min_step_size defaults to max_step_size. + + + Number of iterations for each step. A higher number produces greater accuracy at a performance cost. + + + Set the successive over-relaxation parameter. + + + + + Bullet constraint parameters. + + Constraint force mixing parameter. See the ODE page for more information. + + + Error reduction parameter. See the ODE page for more information. + + + The depth of the surface layer around all geometry objects. Contacts are allowed to sink into the surface layer up to the given depth before coming to rest. The default value is zero. Increasing this to some small value (e.g. 0.001) can help prevent jittering problems due to contacts being repeatedly made and broken. + + + Similar to ODE's max_vel implementation. See http://web.archive.org/web/20120430155635/http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + Similar to ODE's max_vel implementation. See http://web.archive.org/web/20120430155635/http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + + + + ODE specific physics properties + + + + One of the following types: world, quick + + + The time duration which advances with each iteration of the dynamics engine, this has to be no bigger than max_step_size under physics block. If left unspecified, min_step_size defaults to max_step_size. + + + Number of iterations for each step. A higher number produces greater accuracy at a performance cost. + + + Experimental parameter. + + + Set the successive over-relaxation parameter. + + + + Flag to enable dynamic rescaling of moment of inertia in constrained directions. + See gazebo pull request 1114 for the implementation of this feature. + https://bitbucket.org/osrf/gazebo/pull-request/1114 + + + + + + ODE constraint parameters. + + Constraint force mixing parameter. See the ODE page for more information. + + + Error reduction parameter. See the ODE page for more information. + + + The maximum correcting velocities allowed when resolving contacts. + + + The depth of the surface layer around all geometry objects. Contacts are allowed to sink into the surface layer up to the given depth before coming to rest. The default value is zero. Increasing this to some small value (e.g. 0.001) can help prevent jittering problems due to contacts being repeatedly made and broken. + + + + diff --git a/sdformat/sdf/1.5/plane_shape.sdf b/sdformat/sdf/1.5/plane_shape.sdf new file mode 100644 index 0000000..35bca28 --- /dev/null +++ b/sdformat/sdf/1.5/plane_shape.sdf @@ -0,0 +1,9 @@ + + Plane shape + + Normal direction for the plane + + + Length of each side of the plane + + diff --git a/sdformat/sdf/1.5/plugin.sdf b/sdformat/sdf/1.5/plugin.sdf new file mode 100644 index 0000000..26405ff --- /dev/null +++ b/sdformat/sdf/1.5/plugin.sdf @@ -0,0 +1,13 @@ + + + A plugin is a dynamically loaded chunk of code. It can exist as a child of world, model, and sensor. + + A unique name for the plugin, scoped to its parent. + + + Name of the shared library to load. If the filename is not a full path name, the file will be searched for in the configuration paths. + + + This is a special element that should not be specified in an SDF file. It automatically copies child elements into the SDF element so that a plugin can access the data. + + diff --git a/sdformat/sdf/1.5/polyline_shape.sdf b/sdformat/sdf/1.5/polyline_shape.sdf new file mode 100644 index 0000000..6658843 --- /dev/null +++ b/sdformat/sdf/1.5/polyline_shape.sdf @@ -0,0 +1,14 @@ + + Defines an extruded polyline shape + + + + A series of points that define the path of the polyline. + + + + + Height of the polyline + + + diff --git a/sdformat/sdf/1.5/population.sdf b/sdformat/sdf/1.5/population.sdf new file mode 100644 index 0000000..2f97e61 --- /dev/null +++ b/sdformat/sdf/1.5/population.sdf @@ -0,0 +1,59 @@ + + + + The population element defines how and where a set of models will + be automatically populated in Gazebo. + + + + + A unique name for the population. This name must not match + another population in the world. + + + + + + + + The number of models to place. + + + + + Specifies the type of object distribution and its optional parameters. + + + + + Define how the objects will be placed in the specified region. + - random: Models placed at random. + - uniform: Models approximately placed in a 2D grid pattern with control + over the number of objects. + - grid: Models evenly placed in a 2D grid pattern. The number of objects + is not explicitly specified, it is based on the number of rows and + columns of the grid. + - linear-x: Models evently placed in a row along the global x-axis. + - linear-y: Models evently placed in a row along the global y-axis. + - linear-z: Models evently placed in a row along the global z-axis. + + + + + Number of rows in the grid. + + + Number of columns in the grid. + + + Distance between elements of the grid. + + + + + + + + + + diff --git a/sdformat/sdf/1.5/pose.sdf b/sdformat/sdf/1.5/pose.sdf new file mode 100644 index 0000000..7cee8ed --- /dev/null +++ b/sdformat/sdf/1.5/pose.sdf @@ -0,0 +1,9 @@ + + + A position(x,y,z) and orientation(roll, pitch yaw) with respect to the specified frame. + + + Name of frame which the pose is defined relative to. + + + diff --git a/sdformat/sdf/1.5/projector.sdf b/sdformat/sdf/1.5/projector.sdf new file mode 100644 index 0000000..67de493 --- /dev/null +++ b/sdformat/sdf/1.5/projector.sdf @@ -0,0 +1,29 @@ + + + + Name of the projector + + + + Texture name + + + + Field of view + + + + + Near clip distance + + + + + far clip distance + + + + + + + diff --git a/sdformat/sdf/1.5/ray.sdf b/sdformat/sdf/1.5/ray.sdf new file mode 100644 index 0000000..5ffeea3 --- /dev/null +++ b/sdformat/sdf/1.5/ray.sdf @@ -0,0 +1,73 @@ + + These elements are specific to the ray (laser) sensor. + + + + + + + + The number of simulated rays to generate per complete laser sweep cycle. + + + + This number is multiplied by samples to determine the number of range data points returned. If resolution is less than one, range data is interpolated. If resolution is greater than one, range data is averaged. + + + + + + + + Must be greater or equal to min_angle + + + + + + + + The number of simulated rays to generate per complete laser sweep cycle. + + + + This number is multiplied by samples to determine the number of range data points returned. If resolution is less than one, range data is interpolated. If resolution is greater than one, range data is averaged. + + + + + + + + Must be greater or equal to min_angle + + + + + + + specifies range properties of each simulated ray + + The minimum distance for each ray. + + + The maximum distance for each ray. + + + Linear resolution of each ray. + + + + + The properties of the noise model that should be applied to generated scans + + The type of noise. Currently supported types are: "gaussian" (draw noise values independently for each beam from a Gaussian distribution). + + + For type "gaussian," the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which noise values are drawn. + + + diff --git a/sdformat/sdf/1.5/rfid.sdf b/sdformat/sdf/1.5/rfid.sdf new file mode 100644 index 0000000..61351dd --- /dev/null +++ b/sdformat/sdf/1.5/rfid.sdf @@ -0,0 +1,2 @@ + + diff --git a/sdformat/sdf/1.5/rfidtag.sdf b/sdformat/sdf/1.5/rfidtag.sdf new file mode 100644 index 0000000..55699dc --- /dev/null +++ b/sdformat/sdf/1.5/rfidtag.sdf @@ -0,0 +1,2 @@ + + diff --git a/sdformat/sdf/1.5/road.sdf b/sdformat/sdf/1.5/road.sdf new file mode 100644 index 0000000..172e480 --- /dev/null +++ b/sdformat/sdf/1.5/road.sdf @@ -0,0 +1,16 @@ + + + + Name of the road + + + + Width of the road + + + + A series of points that define the path of the road. + + + + diff --git a/sdformat/sdf/1.5/root.sdf b/sdformat/sdf/1.5/root.sdf new file mode 100644 index 0000000..47d443a --- /dev/null +++ b/sdformat/sdf/1.5/root.sdf @@ -0,0 +1,13 @@ + + SDF base element. + + + Version number of the SDF format. + + + + + + + + diff --git a/sdformat/sdf/1.5/scene.sdf b/sdformat/sdf/1.5/scene.sdf new file mode 100644 index 0000000..0cdb52e --- /dev/null +++ b/sdformat/sdf/1.5/scene.sdf @@ -0,0 +1,82 @@ + + + Specifies the look of the environment. + + + Color of the ambient light. + + + + Color of the background. + + + + Properties for the sky + + Time of day [0..24] + + + Sunrise time [0..24] + + + Sunset time [0..24] + + + + Sunset time [0..24] + + Speed of the clouds + + + + Direction of the cloud movement + + + Density of clouds + + + + Average size of the clouds + + + + Ambient cloud color + + + + + + Enable/disable shadows + + + + Controls fog + + Fog color + + + Fog type: constant, linear, quadratic + + + Distance to start of fog + + + Distance to end of fog + + + Density of fog + + + + + Enable/disable the grid + + + + Show/hide world origin indicator + + + diff --git a/sdformat/sdf/1.5/schema/types.xsd b/sdformat/sdf/1.5/schema/types.xsd new file mode 100644 index 0000000..53f3d8d --- /dev/null +++ b/sdformat/sdf/1.5/schema/types.xsd @@ -0,0 +1,44 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.5/sensor.sdf b/sdformat/sdf/1.5/sensor.sdf new file mode 100644 index 0000000..1c503e3 --- /dev/null +++ b/sdformat/sdf/1.5/sensor.sdf @@ -0,0 +1,63 @@ + + + The sensor tag describes the type and properties of a sensor. + + + A unique name for the sensor. This name must not match another model in the model. + + + + The type name of the sensor. By default, SDF supports types + altimeter, + camera, + contact, + depth, + force_torque, + gps, + gpu_ray, + imu, + logical_camera, + magnetometer, + multicamera, + ray, + rfid, + rfidtag, + sonar, + wireless_receiver, and + wireless_transmitter. + + + + If true the sensor will always be updated according to the update rate. + + + + The frequency at which the sensor data is generated. If left unspecified, the sensor will generate data every cycle. + + + + If true, the sensor is visualized in the GUI + + + + Name of the topic on which data is published. This is necessary for visualization + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.5/server.sdf b/sdformat/sdf/1.5/server.sdf new file mode 100644 index 0000000..47d1606 --- /dev/null +++ b/sdformat/sdf/1.5/server.sdf @@ -0,0 +1,29 @@ + + + The distributed tag specifies the ip and port of the remote server. + + + The type of the distribution(0:client or 1:server). + + + + The ip of the remote server. + + + + The flag of the remote server. + + + + the port of the remote port + + + + the port of the remote port + + + + the port of the remote port + + + diff --git a/sdformat/sdf/1.5/sonar.sdf b/sdformat/sdf/1.5/sonar.sdf new file mode 100644 index 0000000..d27017f --- /dev/null +++ b/sdformat/sdf/1.5/sonar.sdf @@ -0,0 +1,13 @@ + + These elements are specific to the sonar sensor. + + Minimum range + + + Max range + + + + Radius of the sonar cone at max range. + + diff --git a/sdformat/sdf/1.5/sphere_shape.sdf b/sdformat/sdf/1.5/sphere_shape.sdf new file mode 100644 index 0000000..73ad03e --- /dev/null +++ b/sdformat/sdf/1.5/sphere_shape.sdf @@ -0,0 +1,6 @@ + + Sphere shape + + radius of the sphere + + diff --git a/sdformat/sdf/1.5/spherical_coordinates.sdf b/sdformat/sdf/1.5/spherical_coordinates.sdf new file mode 100644 index 0000000..e6c8c96 --- /dev/null +++ b/sdformat/sdf/1.5/spherical_coordinates.sdf @@ -0,0 +1,39 @@ + + + + Name of planetary surface model, used to determine the surface altitude + at a given latitude and longitude. The default is an ellipsoid model of + the earth based on the WGS-84 standard. It is used in Gazebo's GPS sensor + implementation. + + + + + + Geodetic latitude at origin of gazebo reference frame, specified + in units of degrees. + + + + + + Longitude at origin of gazebo reference frame, specified in units + of degrees. + + + + + + Elevation of origin of gazebo reference frame, specified in meters. + + + + + + Heading offset of gazebo reference frame, measured as angle between + East and gazebo x axis, or equivalently, the angle between North and + gazebo y axis. The angle is specified in degrees. + + + + diff --git a/sdformat/sdf/1.5/state.sdf b/sdformat/sdf/1.5/state.sdf new file mode 100644 index 0000000..9e23d81 --- /dev/null +++ b/sdformat/sdf/1.5/state.sdf @@ -0,0 +1,40 @@ + + + + + Name of the world this state applies to + + + + Simulation time stamp of the state [seconds nanoseconds] + + + + Wall time stamp of the state [seconds nanoseconds] + + + + Real time stamp of the state [seconds nanoseconds] + + + + Number of simulation iterations. + + + + A list of new model names + + + + + A list of deleted model names + + The name of a deleted model + + + + + + + + diff --git a/sdformat/sdf/1.5/surface.sdf b/sdformat/sdf/1.5/surface.sdf new file mode 100644 index 0000000..7545103 --- /dev/null +++ b/sdformat/sdf/1.5/surface.sdf @@ -0,0 +1,185 @@ + + The surface parameters + + + + Bounciness coefficient of restitution, from [0...1], where 0=no bounciness. + + + Bounce capture velocity, below which effective coefficient of restitution is 0. + + + + + + + + Parameters for torsional friction + + Torsional friction coefficient in the range of [0..1]. + + + + If this flag is true, + torsional friction is calculated using the "patch_radius" parameter. + If this flag is set to false, + "surface_radius" (R) and contact depth (d) + are used to compute the patch radius as sqrt(R*d). + + + + Radius of contact patch surface. + + + Surface radius on the point of contact. + + + Torsional friction parameters for ODE + + Force dependent slip for torsional friction, between the range of [0..1]. + + + + + + ODE friction parameters + + Coefficient of friction in the range of [0..1]. + + + Second coefficient of friction in the range of [0..1] + + + 3-tuple specifying direction of mu1 in the collision local reference frame. + + + Force dependent slip direction 1 in collision local frame, between the range of [0..1]. + + + Force dependent slip direction 2 in collision local frame, between the range of [0..1]. + + + + + Coefficient of friction in the range of [0..1]. + + + Coefficient of friction in the range of [0..1]. + + + 3-tuple specifying direction of mu1 in the collision local reference frame. + + + coefficient of friction in the range of [0..1] + + + + + + + + Flag to disable contact force generation, while still allowing collision checks and contact visualization to occur. + + + Bitmask for collision filtering when collide_without_contact is on + + + + Bitmask for collision filtering. This will override collide_without_contact + + + + + Poisson's ratio is the ratio between transverse and axial strain. + This value must lie between (-1, 0.5). Defaults to 0.3 for typical steel. + Note typical silicone elastomers have Poisson's ratio near 0.49 ~ 0.50. + + For reference, approximate values for Material:(Young's Modulus, Poisson's Ratio) + for some of the typical materials are: + Plastic: (1e8 ~ 3e9 Pa, 0.35 ~ 0.41), + Wood: (4e9 ~ 1e10 Pa, 0.22 ~ 0.50), + Aluminum: (7e10 Pa, 0.32 ~ 0.35), + Steel: (2e11 Pa, 0.26 ~ 0.31). + + + + + Young's Modulus in SI derived unit Pascal. + Defaults to -1. If value is less or equal to zero, + contact using elastic modulus (with Poisson's Ratio) is disabled. + + For reference, approximate values for Material:(Young's Modulus, Poisson's Ratio) + for some of the typical materials are: + Plastic: (1e8 ~ 3e9 Pa, 0.35 ~ 0.41), + Wood: (4e9 ~ 1e10 Pa, 0.22 ~ 0.50), + Aluminum: (7e10 Pa, 0.32 ~ 0.35), + Steel: (2e11 Pa, 0.26 ~ 0.31). + + + + + ODE contact parameters + + Soft constraint force mixing. + + + Soft error reduction parameter + + + dynamically "stiffness"-equivalent coefficient for contact joints + + + dynamically "damping"-equivalent coefficient for contact joints + + + maximum contact correction velocity truncation term. + + + minimum allowable depth before contact correction impulse is applied + + + + Bullet contact parameters + + Soft constraint force mixing. + + + Soft error reduction parameter + + + dynamically "stiffness"-equivalent coefficient for contact joints + + + dynamically "damping"-equivalent coefficient for contact joints + + + Similar to ODE's max_vel implementation. See http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + Similar to ODE's max_vel implementation. See http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + + + + + + soft contact pamameters based on paper: + http://www.cc.gatech.edu/graphics/projects/Sumit/homepage/papers/sigasia11/jain_softcontacts_siga11.pdf + + + This is variable k_v in the soft contacts paper. Its unit is N/m. + + + This is variable k_e in the soft contacts paper. Its unit is N/m. + + + Viscous damping of point velocity in body frame. Its unit is N/m/s. + + + Fraction of mass to be distributed among deformable nodes. + + + + + diff --git a/sdformat/sdf/1.5/transceiver.sdf b/sdformat/sdf/1.5/transceiver.sdf new file mode 100644 index 0000000..9f05b06 --- /dev/null +++ b/sdformat/sdf/1.5/transceiver.sdf @@ -0,0 +1,34 @@ + + These elements are specific to a wireless transceiver. + + + Service set identifier (network name) + + + + Specifies the frequency of transmission in MHz + + + + Only a frequency range is filtered. Here we set the lower bound (MHz). + + + + + Only a frequency range is filtered. Here we set the upper bound (MHz). + + + + + Specifies the antenna gain in dBi + + + + Specifies the transmission power in dBm + + + + Mininum received signal power in dBm + + + diff --git a/sdformat/sdf/1.5/urdf.sdf b/sdformat/sdf/1.5/urdf.sdf new file mode 100644 index 0000000..6068d5c --- /dev/null +++ b/sdformat/sdf/1.5/urdf.sdf @@ -0,0 +1,19 @@ + + + The robot element defines a complete robot or any other physical object using URDF. + + + A unique name for the model. This name must not match another model in the world. + + + + A position and orientation in the global coordinate frame for the model. Position(x,y,z) and rotation (roll, pitch yaw) in the global coordinate frame. + + + + + + + + + diff --git a/sdformat/sdf/1.5/visual.sdf b/sdformat/sdf/1.5/visual.sdf new file mode 100644 index 0000000..04b29c7 --- /dev/null +++ b/sdformat/sdf/1.5/visual.sdf @@ -0,0 +1,35 @@ + + + The visual properties of the link. This element specifies the shape of the object (box, cylinder, etc.) for visualization purposes. + + + Unique name for the visual element within the scope of the parent link. + + + + If true the visual will cast shadows. + + + + will be implemented in the future release. + + + + The amount of transparency( 0=opaque, 1 = fully transparent) + + + + Optional meta information for the visual. The information contained within this element should be used to provide additional feedback to an end user. + + + The layer in which this visual is displayed. The layer number is useful for programs, such as Gazebo, that put visuals in different layers for enhanced visualization. + + + + + + + + + + diff --git a/sdformat/sdf/1.5/world.sdf b/sdformat/sdf/1.5/world.sdf new file mode 100644 index 0000000..a0223ad --- /dev/null +++ b/sdformat/sdf/1.5/world.sdf @@ -0,0 +1,66 @@ + + The world element encapsulates an entire world description including: models, scene, physics, joints, and plugins + + + Unique name of the world + + + + Global audio properties. + + + Device to use for audio playback. A value of "default" will use the system's default audio device. Otherwise, specify a an audio device file" + + + + + The wind tag specifies the type and properties of the wind. + + + Linear velocity of the wind. + + + + + Include resources from a URI + + URI to a resource, such as a model + + + + Override the name of the included model. + + + + Override the static value of the included model. + + + + + + + The gravity vector in m/s^2, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + The magnetic vector in Tesla, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.6/1_5.convert b/sdformat/sdf/1.6/1_5.convert new file mode 100644 index 0000000..121091d --- /dev/null +++ b/sdformat/sdf/1.6/1_5.convert @@ -0,0 +1,331 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.6/CMakeLists.txt b/sdformat/sdf/1.6/CMakeLists.txt new file mode 100644 index 0000000..5e1884e --- /dev/null +++ b/sdformat/sdf/1.6/CMakeLists.txt @@ -0,0 +1,81 @@ +set (sdfs + actor.sdf + altimeter.sdf + atmosphere.sdf + audio_source.sdf + audio_sink.sdf + battery.sdf + box_shape.sdf + camera.sdf + collision.sdf + contact.sdf + cylinder_shape.sdf + frame.sdf + forcetorque.sdf + geometry.sdf + gps.sdf + gripper.sdf + gui.sdf + heightmap_shape.sdf + image_shape.sdf + imu.sdf + inertial.sdf + joint.sdf + light.sdf + light_state.sdf + link.sdf + link_state.sdf + logical_camera.sdf + magnetometer.sdf + material.sdf + mesh_shape.sdf + model.sdf + model_state.sdf + noise.sdf + physics.sdf + plane_shape.sdf + plugin.sdf + polyline_shape.sdf + population.sdf + pose.sdf + projector.sdf + ray.sdf + rfidtag.sdf + rfid.sdf + road.sdf + root.sdf + scene.sdf + sensor.sdf + spherical_coordinates.sdf + sphere_shape.sdf + sonar.sdf + state.sdf + surface.sdf + transceiver.sdf + visual.sdf + world.sdf +) + +set (SDF_SCHEMA) + +foreach(FIL ${sdfs}) + get_filename_component(ABS_FIL ${FIL} ABSOLUTE) + get_filename_component(FIL_WE ${FIL} NAME_WE) + + list(APPEND SDF_SCHEMA "${CMAKE_CURRENT_BINARY_DIR}/${FIL_WE}.xsd") + + add_custom_command( + OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/${FIL_WE}.xsd" + COMMAND ${RUBY} ${CMAKE_SOURCE_DIR}/tools/xmlschema.rb + ARGS -s ${CMAKE_CURRENT_SOURCE_DIR} -i ${ABS_FIL} -o ${CMAKE_CURRENT_BINARY_DIR} + DEPENDS ${ABS_FIL} + COMMENT "Running xml schema compiler on ${FIL}" + VERBATIM) +endforeach() + +add_custom_target(schema1_6 ALL DEPENDS ${SDF_SCHEMA}) + +set_source_files_properties(${SDF_SCHEMA} PROPERTIES GENERATED TRUE) + +install(FILES 1_5.convert ${sdfs} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat/1.6) +install(FILES ${SDF_SCHEMA} DESTINATION ${CMAKE_INSTALL_FULL_DATAROOTDIR}/sdformat/1.6) diff --git a/sdformat/sdf/1.6/actor.sdf b/sdformat/sdf/1.6/actor.sdf new file mode 100644 index 0000000..7ed3460 --- /dev/null +++ b/sdformat/sdf/1.6/actor.sdf @@ -0,0 +1,87 @@ + + + A special kind of model which can have a scripted motion. This includes both global waypoint type animations and skeleton animations. + + + A unique name for the actor. + + + + (DEPRECATION WARNING: This is deprecated in 1.6 and removed in 1.7. Actors should be static, so this is always true. + + + + + + + Skin file which defines a visual and the underlying skeleton which moves it. + + + Path to skin file, accepted formats: COLLADA, BVH. + + + + Scale the skin's size. + + + + + Animation file defines an animation for the skeleton in the skin. The skeleton must be compatible with the skin skeleton. + + + Unique name for animation. + + + + Path to animation file. Accepted formats: COLLADA, BVH. + + + Scale for the animation skeleton. + + + Set to true so the animation is interpolated on X. + + + + + Adds scripted trajectories to the actor. + + + Set this to true for the script to be repeated in a loop. For a fluid continuous motion, make sure the last waypoint matches the first one. + + + + This is the time to wait before starting the script. If running in a loop, this time will be waited before starting each cycle. + + + + Set to true if the animation should start as soon as the simulation starts playing. It is useful to set this to false if the animation should only start playing only when triggered by a plugin, for example. + + + + The trajectory contains a series of keyframes to be followed. + + Unique id for a trajectory. + + + + If it matches the type of an animation, they will be played at the same time. + + + + Each point in the trajectory. + + The time in seconds, counted from the beginning of the script, when the pose should be reached. + + + The pose which should be reached at the given time. + + + + + + + + + + diff --git a/sdformat/sdf/1.6/altimeter.sdf b/sdformat/sdf/1.6/altimeter.sdf new file mode 100644 index 0000000..66ddee5 --- /dev/null +++ b/sdformat/sdf/1.6/altimeter.sdf @@ -0,0 +1,18 @@ + + These elements are specific to an altimeter sensor. + + + + Noise parameters for vertical position + + + + + + + Noise parameters for vertical velocity + + + + + diff --git a/sdformat/sdf/1.6/atmosphere.sdf b/sdformat/sdf/1.6/atmosphere.sdf new file mode 100644 index 0000000..641facc --- /dev/null +++ b/sdformat/sdf/1.6/atmosphere.sdf @@ -0,0 +1,21 @@ + + + The atmosphere tag specifies the type and properties of the atmosphere model. + + + The type of the atmosphere engine. Current options are adiabatic. Defaults to adiabatic if left unspecified. + + + + Temperature at sea level in kelvins. + + + + Pressure at sea level in pascals. + + + + Temperature gradient with respect to increasing altitude at sea level in units of K/m. + + + diff --git a/sdformat/sdf/1.6/audio_sink.sdf b/sdformat/sdf/1.6/audio_sink.sdf new file mode 100644 index 0000000..d3bd071 --- /dev/null +++ b/sdformat/sdf/1.6/audio_sink.sdf @@ -0,0 +1,4 @@ + + + An audio sink. + diff --git a/sdformat/sdf/1.6/audio_source.sdf b/sdformat/sdf/1.6/audio_source.sdf new file mode 100644 index 0000000..8f8c23d --- /dev/null +++ b/sdformat/sdf/1.6/audio_source.sdf @@ -0,0 +1,31 @@ + + + An audio source. + + + URI of the audio media. + + + + Pitch for the audio media, in Hz + + + + Gain for the audio media, in dB. + + + + List of collision objects that will trigger audio playback. + + Name of child collision element that will trigger audio playback. + + + + + True to make the audio source loop playback. + + + + + + diff --git a/sdformat/sdf/1.6/battery.sdf b/sdformat/sdf/1.6/battery.sdf new file mode 100644 index 0000000..dc6f8de --- /dev/null +++ b/sdformat/sdf/1.6/battery.sdf @@ -0,0 +1,12 @@ + + + Description of a battery. + + + Unique name for the battery. + + + + Initial voltage in volts. + + diff --git a/sdformat/sdf/1.6/box_shape.sdf b/sdformat/sdf/1.6/box_shape.sdf new file mode 100644 index 0000000..826ab37 --- /dev/null +++ b/sdformat/sdf/1.6/box_shape.sdf @@ -0,0 +1,6 @@ + + Box shape + + The three side lengths of the box. The origin of the box is in its geometric center (inside the center of the box). + + diff --git a/sdformat/sdf/1.6/camera.sdf b/sdformat/sdf/1.6/camera.sdf new file mode 100644 index 0000000..cf46793 --- /dev/null +++ b/sdformat/sdf/1.6/camera.sdf @@ -0,0 +1,130 @@ + + These elements are specific to camera sensors. + + + An optional name for the camera. + + + + Horizontal field of view + + + + The image size in pixels and format. + + Width in pixels + + + Height in pixels + + + (L8|R8G8B8|B8G8R8|BAYER_RGGB8|BAYER_BGGR8|BAYER_GBRG8|BAYER_GRBG8) + + + + + The near and far clip planes. Objects closer or farther than these planes are not rendered. + + + Near clipping plane + + + + Far clipping plane + + + + + Enable or disable saving of camera frames. + + True = saving enabled + + + The path name which will hold the frame data. If path name is relative, then directory is relative to current working directory. + + + + + Depth camera parameters + + Type of output + + + + + The properties of the noise model that should be applied to generated images + + The type of noise. Currently supported types are: "gaussian" (draw additive noise values independently for each pixel from a Gaussian distribution). + + + For type "gaussian," the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which noise values are drawn. + + + + + Lens distortion to be applied to camera images. See http://en.wikipedia.org/wiki/Distortion_(optics)#Software_correction + + The radial distortion coefficient k1 + + + The radial distortion coefficient k2 + + + The radial distortion coefficient k3 + + + The tangential distortion coefficient p1 + + + The tangential distortion coefficient p2 + + + The distortion center or principal point + + + + + Lens projection description + + + Type of the lens mapping. Supported values are gnomonical, stereographic, equidistant, equisolid_angle, orthographic, custom. For gnomonical (perspective) projection, it is recommended to specify a horizontal_fov of less than or equal to 90° + + + If true the image will be scaled to fit horizontal FOV, otherwise it will be shown according to projection type parameters + + + + Definition of custom mapping function in a form of r=c1*f*fun(theta/c2 + c3). See https://en.wikipedia.org/wiki/Fisheye_lens#Mapping_function + + Linear scaling constant + + + Angle scaling constant + + + Angle offset constant + + + Focal length of the optical system. Note: It's not a focal length of the lens in a common sense! This value is ignored if 'scale_to_fov' is set to true + + + Possible values are 'sin', 'tan' and 'id' + + + + + Everything outside of the specified angle will be hidden, 90° by default + + + + Resolution of the environment cube map used to draw the world + + + + + + + diff --git a/sdformat/sdf/1.6/collision.sdf b/sdformat/sdf/1.6/collision.sdf new file mode 100644 index 0000000..09c4eac --- /dev/null +++ b/sdformat/sdf/1.6/collision.sdf @@ -0,0 +1,23 @@ + + + The collision properties of a link. Note that this can be different from the visual properties of a link, for example, simpler collision models are often used to reduce computation time. + + + Unique name for the collision element within the scope of the parent link. + + + + intensity value returned by laser sensor. + + + + Maximum number of contacts allowed between two entities. This value overrides the max_contacts element defined in physics. + + + + + + + + + diff --git a/sdformat/sdf/1.6/collision_engine.sdf b/sdformat/sdf/1.6/collision_engine.sdf new file mode 100644 index 0000000..67dbc70 --- /dev/null +++ b/sdformat/sdf/1.6/collision_engine.sdf @@ -0,0 +1,17 @@ + + + The collision_engine tag specifies the type and properties of the collision detection engine. + + + + The type of the collision detection engine. Current default in ODE is OPCODE. + + + + + + The type of the collision detection engine. + + + + diff --git a/sdformat/sdf/1.6/contact.sdf b/sdformat/sdf/1.6/contact.sdf new file mode 100644 index 0000000..d1cde50 --- /dev/null +++ b/sdformat/sdf/1.6/contact.sdf @@ -0,0 +1,12 @@ + + These elements are specific to the contact sensor. + + + name of the collision element within a link that acts as the contact sensor. + + + + Topic on which contact data is published. + + + diff --git a/sdformat/sdf/1.6/cylinder_shape.sdf b/sdformat/sdf/1.6/cylinder_shape.sdf new file mode 100644 index 0000000..8e25a53 --- /dev/null +++ b/sdformat/sdf/1.6/cylinder_shape.sdf @@ -0,0 +1,9 @@ + + Cylinder shape + + Radius of the cylinder + + + Length of the cylinder + + diff --git a/sdformat/sdf/1.6/distribution.sdf b/sdformat/sdf/1.6/distribution.sdf new file mode 100644 index 0000000..924c2f5 --- /dev/null +++ b/sdformat/sdf/1.6/distribution.sdf @@ -0,0 +1,19 @@ + + + The distribution tag specifies the local ID of this gazebo and port of the remote server. + + + The ID of the gazebo. + + + + The flag of the remote server. + + + + the port of the remote port + + + + + diff --git a/sdformat/sdf/1.6/event (å¤ä»¶).sdf b/sdformat/sdf/1.6/event (å¤ä»¶).sdf new file mode 100644 index 0000000..35d7aba --- /dev/null +++ b/sdformat/sdf/1.6/event (å¤ä»¶).sdf @@ -0,0 +1,17 @@ + + + The event tag specifies the numbers of threads and size of the block. + + + The numbers of the thread's callback parameters. + + + + the size of block to tbb thread + + + + the type to block partion + + + diff --git a/sdformat/sdf/1.6/event.sdf b/sdformat/sdf/1.6/event.sdf new file mode 100644 index 0000000..16d5c20 --- /dev/null +++ b/sdformat/sdf/1.6/event.sdf @@ -0,0 +1,21 @@ + + + The parallel tag specifies the numbers of threads and tbb size of the block. + + + The type of parallel. + + + + The numbers of the threads. + + + + the size of block to tbb thread + + + + the type to block partion + + + diff --git a/sdformat/sdf/1.6/forcetorque.sdf b/sdformat/sdf/1.6/forcetorque.sdf new file mode 100644 index 0000000..08388cf --- /dev/null +++ b/sdformat/sdf/1.6/forcetorque.sdf @@ -0,0 +1,20 @@ + + These elements are specific to the force torque sensor. + + + Frame in which to report the wrench values. Currently supported frames are: + "parent" report the wrench expressed in the orientation of the parent link frame, + "child" report the wrench expressed in the orientation of the child link frame, + "sensor" report the wrench expressed in the orientation of the joint sensor frame. + Note that for each option the point with respect to which the + torque component of the wrench is expressed is the joint origin. + + + + + Direction of the wrench measured by the sensor. The supported options are: + "parent_to_child" if the measured wrench is the one applied by parent link on the child link, + "child_to_parent" if the measured wrench is the one applied by the child link on the parent link. + + + diff --git a/sdformat/sdf/1.6/frame.sdf b/sdformat/sdf/1.6/frame.sdf new file mode 100644 index 0000000..28eefc5 --- /dev/null +++ b/sdformat/sdf/1.6/frame.sdf @@ -0,0 +1,11 @@ + + + A frame of reference to which a pose is relative. + + + Name of the frame. This name must not match another frame defined inside the parent that this frame is attached to. + + + + + diff --git a/sdformat/sdf/1.6/gazeboid.sdf b/sdformat/sdf/1.6/gazeboid.sdf new file mode 100644 index 0000000..4cb7ae3 --- /dev/null +++ b/sdformat/sdf/1.6/gazeboid.sdf @@ -0,0 +1,17 @@ + + + The distributed tag specifies the ip and ID of the local gazebo. + + + The type of the distribution(0:client or 1:server). + + + + The ip of the local gazebo. + + + + model name in the local gazebo. + + + diff --git a/sdformat/sdf/1.6/geometry.sdf b/sdformat/sdf/1.6/geometry.sdf new file mode 100644 index 0000000..5fe95ed --- /dev/null +++ b/sdformat/sdf/1.6/geometry.sdf @@ -0,0 +1,18 @@ + + + The shape of the visual or collision object. + + + You can use the empty tag to make empty geometries. + + + + + + + + + + + + diff --git a/sdformat/sdf/1.6/gps.sdf b/sdformat/sdf/1.6/gps.sdf new file mode 100644 index 0000000..95e0049 --- /dev/null +++ b/sdformat/sdf/1.6/gps.sdf @@ -0,0 +1,40 @@ + + These elements are specific to the GPS sensor. + + + + Parameters related to GPS position measurement. + + + + Noise parameters for horizontal position measurement, in units of meters. + + + + + + Noise parameters for vertical position measurement, in units of meters. + + + + + + + + Parameters related to GPS position measurement. + + + + Noise parameters for horizontal velocity measurement, in units of meters/second. + + + + + + Noise parameters for vertical velocity measurement, in units of meters/second. + + + + + + diff --git a/sdformat/sdf/1.6/gripper.sdf b/sdformat/sdf/1.6/gripper.sdf new file mode 100644 index 0000000..12fd0b3 --- /dev/null +++ b/sdformat/sdf/1.6/gripper.sdf @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.6/gui.sdf b/sdformat/sdf/1.6/gui.sdf new file mode 100644 index 0000000..2eab16b --- /dev/null +++ b/sdformat/sdf/1.6/gui.sdf @@ -0,0 +1,61 @@ + + + + + + + + + + + + + + + + + + + + + Set the type of projection for the camera. Valid values are "perspective" and "orthographic". + + + + + + + Name of the tracked visual. If no name is provided, the remaining settings will be applied whenever tracking is triggered in the GUI. + + + + Minimum distance between the camera and the tracked visual. This parameter is only used if static is set to false. + + + + Maximum distance between the camera and the tracked visual. This parameter is only used if static is set to false. + + + + If set to true, the position of the camera is fixed relatively to the model or to the world, depending on the value of the use_model_frame element. Otherwise, the position of the camera may vary but the distance between the camera and the model will depend on the value of the min_dist and max_dist elements. In any case, the camera will always follow the model by changing its orientation. + + + + If set to true, the position of the camera is relative to the model reference frame, which means that its position relative to the model will not change. Otherwise, the position of the camera is relative to the world reference frame, which means that its position relative to the world will not change. This parameter is only used if static is set to true. + + + + The position of the camera's reference frame. This parameter is only used if static is set to true. If use_model_frame is set to true, the position is relative to the model reference frame, otherwise it represents world coordinates. + + + + If set to true, the camera will inherit the yaw rotation of the tracked model. This parameter is only used if static and use_model_frame are set to true. + + + + + + + + + diff --git a/sdformat/sdf/1.6/heightmap_shape.sdf b/sdformat/sdf/1.6/heightmap_shape.sdf new file mode 100644 index 0000000..8db8c67 --- /dev/null +++ b/sdformat/sdf/1.6/heightmap_shape.sdf @@ -0,0 +1,44 @@ + + A heightmap based on a 2d grayscale image. + + URI to a grayscale image file + + + The size of the heightmap in world units. + When loading an image: "size" is used if present, otherwise defaults to 1x1x1. + When loading a DEM: "size" is used if present, otherwise defaults to true size of DEM. + + + + A position offset. + + + + The heightmap can contain multiple textures. The order of the texture matters. The first texture will appear at the lowest height, and the last texture at the highest height. Use blend to control the height thresholds and fade between textures. + + Size of the applied texture in meters. + + + Diffuse texture image filename + + + Normalmap texture image filename + + + + The blend tag controls how two adjacent textures are mixed. The number of blend elements should equal one less than the number of textures. + + Min height of a blend layer + + + Distance over which the blend occurs + + + + Set if the rendering engine will use terrain paging + + + Samples per heightmap datum. For rasterized heightmaps, this indicates the number of samples to take per pixel. Using a lower value, e.g. 1, will generally improve the performance of the heightmap but lower the heightmap quality. + + + diff --git a/sdformat/sdf/1.6/image_shape.sdf b/sdformat/sdf/1.6/image_shape.sdf new file mode 100644 index 0000000..369de7c --- /dev/null +++ b/sdformat/sdf/1.6/image_shape.sdf @@ -0,0 +1,18 @@ + + Extrude a set of boxes from a grayscale image. + + URI of the grayscale image file + + + Scaling factor applied to the image + + + Grayscale threshold + + + Height of the extruded boxes + + + The amount of error in the model + + diff --git a/sdformat/sdf/1.6/imu.sdf b/sdformat/sdf/1.6/imu.sdf new file mode 100644 index 0000000..d812b0f --- /dev/null +++ b/sdformat/sdf/1.6/imu.sdf @@ -0,0 +1,121 @@ + + These elements are specific to the IMU sensor. + + + + + + This string represents special hardcoded use cases that are commonly seen with typical robot IMU's: + - CUSTOM: use Euler angle custom_rpy orientation specification. + The orientation of the IMU's reference frame is defined by adding the custom_rpy rotation + to the parent_frame. + - NED: The IMU XYZ aligns with NED, where NED orientation relative to Gazebo world + is defined by the SphericalCoordinates class. + - ENU: The IMU XYZ aligns with ENU, where ENU orientation relative to Gazebo world + is defined by the SphericalCoordinates class. + - NWU: The IMU XYZ aligns with NWU, where NWU orientation relative to Gazebo world + is defined by the SphericalCoordinates class. + - GRAV_UP: where direction of gravity maps to IMU reference frame Z-axis with Z-axis pointing in + the opposite direction of gravity. IMU reference frame X-axis direction is defined by grav_dir_x. + Note if grav_dir_x is parallel to gravity direction, this configuration fails. + Otherwise, IMU reference frame X-axis is defined by projection of grav_dir_x onto a plane + normal to the gravity vector. IMU reference frame Y-axis is a vector orthogonal to both + X and Z axis following the right hand rule. + - GRAV_DOWN: where direction of gravity maps to IMU reference frame Z-axis with Z-axis pointing in + the direction of gravity. IMU reference frame X-axis direction is defined by grav_dir_x. + Note if grav_dir_x is parallel to gravity direction, this configuration fails. + Otherwise, IMU reference frame X-axis is defined by projection of grav_dir_x onto a plane + normal to the gravity vector. IMU reference frame Y-axis is a vector orthogonal to both + X and Z axis following the right hand rule. + + + + + This field and parent_frame are used when localization is set to CUSTOM. + Orientation (fixed axis roll, pitch yaw) transform from parent_frame to this IMU's reference frame. + Some common examples are: + - IMU reports in its local frame on boot. IMU sensor frame is the reference frame. + Example: parent_frame="", custom_rpy="0 0 0" + - IMU reports in Gazebo world frame. + Example sdf: parent_frame="world", custom_rpy="0 0 0" + - IMU reports in NWU frame. + Uses SphericalCoordinates class to determine world frame in relation to magnetic north and gravity; + i.e. rotation between North-West-Up and world (+X,+Y,+Z) frame is defined by SphericalCoordinates class. + Example sdf given world is NWU: parent_frame="world", custom_rpy="0 0 0" + - IMU reports in NED frame. + Uses SphericalCoordinates class to determine world frame in relation to magnetic north and gravity; + i.e. rotation between North-East-Down and world (+X,+Y,+Z) frame is defined by SphericalCoordinates class. + Example sdf given world is NWU: parent_frame="world", custom_rpy="M_PI 0 0" + - IMU reports in ENU frame. + Uses SphericalCoordinates class to determine world frame in relation to magnetic north and gravity; + i.e. rotation between East-North-Up and world (+X,+Y,+Z) frame is defined by SphericalCoordinates class. + Example sdf given world is NWU: parent_frame="world", custom_rpy="0 0 -0.5*M_PI" + - IMU reports in ROS optical frame as described in http://www.ros.org/reps/rep-0103.html#suffix-frames, which is + (z-forward, x-left to right when facing +z, y-top to bottom when facing +z). + (default gazebo camera is +x:view direction, +y:left, +z:up). + Example sdf: parent_frame="local", custom_rpy="-0.5*M_PI 0 -0.5*M_PI" + + + + Name of parent frame which the custom_rpy transform is defined relative to. + It can be any valid fully scoped Gazebo Link name or the special reserved "world" frame. + If left empty, use the sensor's own local frame. + + + + + + Used when localization is set to GRAV_UP or GRAV_DOWN, a projection of this vector + into a plane that is orthogonal to the gravity vector + defines the direction of the IMU reference frame's X-axis. + grav_dir_x is defined in the coordinate frame as defined by the parent_frame element. + + + + Name of parent frame in which the grav_dir_x vector is defined. + It can be any valid fully scoped Gazebo Link name or the special reserved "world" frame. + If left empty, use the sensor's own local frame. + + + + + + + Topic on which data is published. + + + + These elements are specific to body-frame angular velocity, + which is expressed in radians per second + + Angular velocity about the X axis + + + + Angular velocity about the Y axis + + + + Angular velocity about the Z axis + + + + + + These elements are specific to body-frame linear acceleration, + which is expressed in meters per second squared + + Linear acceleration about the X axis + + + + Linear acceleration about the Y axis + + + + Linear acceleration about the Z axis + + + + + diff --git a/sdformat/sdf/1.6/inertial.sdf b/sdformat/sdf/1.6/inertial.sdf new file mode 100644 index 0000000..b8160bf --- /dev/null +++ b/sdformat/sdf/1.6/inertial.sdf @@ -0,0 +1,36 @@ + + + The inertial properties of the link. + + + The mass of the link. + + + + + + This is the pose of the inertial reference frame, relative to the specified reference frame. The origin of the inertial reference frame needs to be at the center of gravity. The axes of the inertial reference frame do not need to be aligned with the principal axes of the inertia. + + + + The 3x3 rotational inertia matrix. Because the rotational inertia matrix is symmetric, only 6 above-diagonal elements of this matrix are specified here, using the attributes ixx, ixy, ixz, iyy, iyz, izz. + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.6/joint.sdf b/sdformat/sdf/1.6/joint.sdf new file mode 100644 index 0000000..75e3e63 --- /dev/null +++ b/sdformat/sdf/1.6/joint.sdf @@ -0,0 +1,242 @@ + + + A joint connections two links with kinematic and dynamic properties. + + + A unique name for the joint within the scope of the model. + + + + The type of joint, which must be one of the following: + (revolute) a hinge joint that rotates on a single axis with either a fixed or continuous range of motion, + (gearbox) geared revolute joints, + (revolute2) same as two revolute joints connected in series, + (prismatic) a sliding joint that slides along an axis with a limited range specified by upper and lower limits, + (ball) a ball and socket joint, + (screw) a single degree of freedom joint with coupled sliding and rotational motion, + (universal) like a ball joint, but constrains one degree of freedom, + (fixed) a joint with zero degrees of freedom that rigidly connects two links. + + + + + Name of the parent link + + + + Name of the child link + + + + Parameter for gearbox joints. Given theta_1 and theta_2 defined in description for gearbox_reference_body, theta_2 = -gearbox_ratio * theta_1. + + + + Parameter for gearbox joints. Gearbox ratio is enforced over two joint angles. First joint angle (theta_1) is the angle from the gearbox_reference_body to the parent link in the direction of the axis element and the second joint angle (theta_2) is the angle from the gearbox_reference_body to the child link in the direction of the axis2 element. + + + + Parameter for screw joints. + + + + + Parameters related to the axis of rotation for revolute joints, + the axis of translation for prismatic joints. + + + + Default joint position for this joint axis. + + + + + Represents the x,y,z components of the axis unit vector. The axis is + expressed in the joint frame unless the use_parent_model_frame + flag is set to true. The vector should be normalized. + + + + + Flag to interpret the axis xyz element in the parent model frame instead + of joint frame. Provided for Gazebo compatibility + (see https://bitbucket.org/osrf/gazebo/issue/494 ). + + + + An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation. + + The physical velocity dependent viscous damping coefficient of the joint. + + + The physical static friction value of the joint. + + + The spring reference position for this joint axis. + + + The spring stiffness for this joint axis. + + + + specifies the limits of this joint + + An attribute specifying the lower joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute specifying the upper joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute for enforcing the maximum joint effort applied by Joint::SetForce. Limit is not enforced if value is negative. + + + (not implemented) An attribute for enforcing the maximum joint velocity. + + + + Joint stop stiffness. Support physics engines: SimBody. + + + + Joint stop dissipation. + + + + + + + + Parameters related to the second axis of rotation for revolute2 joints and universal joints. + + + + Default joint position for this joint axis. + + + + + Represents the x,y,z components of the axis unit vector. The axis is + expressed in the joint frame unless the use_parent_model_frame + flag is set to true. The vector should be normalized. + + + + + Flag to interpret the axis xyz element in the parent model frame instead + of joint frame. Provided for Gazebo compatibility + (see https://bitbucket.org/osrf/gazebo/issue/494 ). + + + + An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation. + + The physical velocity dependent viscous damping coefficient of the joint. EXPERIMENTAL: if damping coefficient is negative and implicit_spring_damper is true, adaptive damping is used. + + + The physical static friction value of the joint. + + + The spring reference position for this joint axis. + + + The spring stiffness for this joint axis. + + + + + + + An attribute specifying the lower joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute specifying the upper joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. + + + An attribute for enforcing the maximum joint effort applied by Joint::SetForce. Limit is not enforced if value is negative. + + + (not implemented) An attribute for enforcing the maximum joint velocity. + + + + Joint stop stiffness. Supported physics engines: SimBody. + + + + Joint stop dissipation. Supported physics engines: SimBody. + + + + + + + Parameters that are specific to a certain physics engine. + + Simbody specific parameters + + Force cut in the multibody graph at this joint. + + + + ODE specific parameters + + (DEPRECATION WARNING: In SDF 1.5 this tag will be replaced by the same tag directly under the physics-block. For now, this tag overrides the one outside of ode-block, but in SDF 1.5 this tag will be removed completely.) If provide feedback is set to true, ODE will compute the constraint forces at this joint. + + + + If cfm damping is set to true, ODE will use CFM to simulate damping, allows for infinite damping, and one additional constraint row (previously used for joint limit) is always active. + + + + If implicit_spring_damper is set to true, ODE will use CFM, ERP to simulate stiffness and damping, allows for infinite damping, and one additional constraint row (previously used for joint limit) is always active. This replaces cfm_damping parameter in sdf 1.4. + + + + Scale the excess for in a joint motor at joint limits. Should be between zero and one. + + + Constraint force mixing for constrained directions + + + Error reduction parameter for constrained directions + + + Bounciness of the limits + + + Maximum force or torque used to reach the desired velocity. + + + The desired velocity of the joint. Should only be set if you want the joint to move on load. + + + + + + Constraint force mixing parameter used by the joint stop + + + Error reduction parameter used by the joint stop + + + + + + + Suspension constraint force mixing parameter + + + Suspension error reduction parameter + + + + + + If provide feedback is set to true, physics engine will compute the constraint forces at this joint. For now, provide_feedback under ode block will override this tag and given user warning about the migration. provide_feedback under ode is scheduled to be removed in SDF 1.5. + + + + + + + diff --git a/sdformat/sdf/1.6/light.sdf b/sdformat/sdf/1.6/light.sdf new file mode 100644 index 0000000..336cd7f --- /dev/null +++ b/sdformat/sdf/1.6/light.sdf @@ -0,0 +1,60 @@ + + + The light element describes a light source. + + + A unique name for the light. + + + + The light type: point, directional, spot. + + + + When true, the light will cast shadows. + + + + + + + Diffuse light color + + + Specular light color + + + + Light attenuation + + Range of the light + + + The linear attenuation factor: 1 means attenuate evenly over the distance. + + + The constant attenuation factor: 1.0 means never attenuate, 0.0 is complete attenutation. + + + The quadratic attenuation factor: adds a curvature to the attenuation. + + + + + Direction of the light, only applicable for spot and directional lights. + + + + Spot light parameters + + Angle covered by the bright inner cone + + + Angle covered by the outer cone + + + The rate of falloff between the inner and outer cones. 1.0 means a linear falloff, less means slower falloff, higher means faster falloff. + + + + diff --git a/sdformat/sdf/1.6/light_state.sdf b/sdformat/sdf/1.6/light_state.sdf new file mode 100644 index 0000000..af128fd --- /dev/null +++ b/sdformat/sdf/1.6/light_state.sdf @@ -0,0 +1,11 @@ + + + Light state + + + Name of the light + + + + + diff --git a/sdformat/sdf/1.6/link.sdf b/sdformat/sdf/1.6/link.sdf new file mode 100644 index 0000000..238d445 --- /dev/null +++ b/sdformat/sdf/1.6/link.sdf @@ -0,0 +1,51 @@ + + + A physical link with inertia, collision, and visual properties. A link must be a child of a model, and any number of links may exist in a model. + + + A unique name for the link within the scope of the model. + + + + If true, the link is affected by gravity. + + + + If true, the link is affected by the wind. + + + + If true, the link can collide with other links in the model. Two links within a model will collide if link1.self_collide OR link2.self_collide. Links connected by a joint will never collide. + + + + If true, the link is kinematic only + + + + If true, the link will have 6DOF and be a direct child of world. + + + + Exponential damping of the link's velocity. + + Linear damping + + + Angular damping + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.6/link_state.sdf b/sdformat/sdf/1.6/link_state.sdf new file mode 100644 index 0000000..5269415 --- /dev/null +++ b/sdformat/sdf/1.6/link_state.sdf @@ -0,0 +1,41 @@ + + + Link state + + + Name of the link + + + + Velocity of the link. The x, y, z components of the pose + correspond to the linear velocity of the link, and the roll, pitch, yaw + components correspond to the angular velocity of the link + + + + + Acceleration of the link. The x, y, z components of the pose + correspond to the linear acceleration of the link, and the roll, + pitch, yaw components correspond to the angular acceleration of the link + + + + + Force and torque applied to the link. The x, y, z components + of the pose correspond to the force applied to the link, and the roll, + pitch, yaw components correspond to the torque applied to the link + + + + + Collision state + + + Name of the collision + + + + + + + diff --git a/sdformat/sdf/1.6/logical_camera.sdf b/sdformat/sdf/1.6/logical_camera.sdf new file mode 100644 index 0000000..de47703 --- /dev/null +++ b/sdformat/sdf/1.6/logical_camera.sdf @@ -0,0 +1,19 @@ + + These elements are specific to logical camera sensors. A logical camera reports objects that fall within a frustum. Computation should be performed on the CPU. + + + Near clipping distance of the view frustum + + + + Far clipping distance of the view frustum + + + + Aspect ratio of the near and far planes. This is the width divided by the height of the near or far planes. + + + + Horizontal field of view of the frustum, in radians. This is the angle between the frustum's vertex and the edges of the near or far plane. + + diff --git a/sdformat/sdf/1.6/magnetometer.sdf b/sdformat/sdf/1.6/magnetometer.sdf new file mode 100644 index 0000000..2f3bfee --- /dev/null +++ b/sdformat/sdf/1.6/magnetometer.sdf @@ -0,0 +1,21 @@ + + These elements are specific to a Magnetometer sensor. + + + Parameters related to the body-frame X axis of the magnetometer + + + + + + Parameters related to the body-frame Y axis of the magnetometer + + + + + + Parameters related to the body-frame Z axis of the magnetometer + + + + \ No newline at end of file diff --git a/sdformat/sdf/1.6/material.sdf b/sdformat/sdf/1.6/material.sdf new file mode 100644 index 0000000..137436e --- /dev/null +++ b/sdformat/sdf/1.6/material.sdf @@ -0,0 +1,47 @@ + + + The material of the visual element. + + + Name of material from an installed script file. This will override the color element if the script exists. + + + URI of the material script file + + + + Name of the script within the script file + + + + + + + vertex, pixel, normal_map_objectspace, normal_map_tangentspace + + + + filename of the normal map + + + + + If false, dynamic lighting will be disabled + + + + The ambient color of a material specified by set of four numbers representing red/green/blue, each in the range of [0,1]. + + + + The diffuse color of a material specified by set of four numbers representing red/green/blue/alpha, each in the range of [0,1]. + + + + The specular color of a material specified by set of four numbers representing red/green/blue/alpha, each in the range of [0,1]. + + + + The emissive color of a material specified by set of four numbers representing red/green/blue, each in the range of [0,1]. + + diff --git a/sdformat/sdf/1.6/mesh_shape.sdf b/sdformat/sdf/1.6/mesh_shape.sdf new file mode 100644 index 0000000..61bce76 --- /dev/null +++ b/sdformat/sdf/1.6/mesh_shape.sdf @@ -0,0 +1,20 @@ + + Mesh shape + + Mesh uri + + + + Use a named submesh. The submesh must exist in the mesh specified by the uri + + Name of the submesh within the parent mesh + + + Set to true to center the vertices of the submesh at 0,0,0. This will effectively remove any transformations on the submesh before the poses from parent links and models are applied. + + + + + Scaling factor applied to the mesh + + diff --git a/sdformat/sdf/1.6/model.sdf b/sdformat/sdf/1.6/model.sdf new file mode 100644 index 0000000..54e13ff --- /dev/null +++ b/sdformat/sdf/1.6/model.sdf @@ -0,0 +1,58 @@ + + + The model element defines a complete robot or any other physical object. + + + A unique name for the model. This name must not match another model in the world. + + + + If set to true, the model is immovable. Otherwise the model is simulated in the dynamics engine. + + + + If set to true, all links in the model will collide with each other (except those connected by a joint). Can be overridden by the link or collision element self_collide property. Two links within a model will collide if link1.self_collide OR link2.self_collide. Links connected by a joint will never collide. + + + + Allows a model to auto-disable, which is means the physics engine can skip updating the model when the model is at rest. This parameter is only used by models with no joints. + + + + + + + + + + + Include resources from a URI. This can be used to nest models. + + URI to a resource, such as a model + + + + Override the pose of the included model. A position and orientation in the global coordinate frame for the model. Position(x,y,z) and rotation (roll, pitch yaw) in the global coordinate frame. + + + + Override the name of the included model. + + + + Override the static value of the included model. + + + + + A nested model element + + A unique name for the model. This name must not match another nested model in the same level as this model. + + + + + If set to true, all links in the model will be affected by the wind. Can be overriden by the link wind property. + + + diff --git a/sdformat/sdf/1.6/model_state.sdf b/sdformat/sdf/1.6/model_state.sdf new file mode 100644 index 0000000..3fd296f --- /dev/null +++ b/sdformat/sdf/1.6/model_state.sdf @@ -0,0 +1,41 @@ + + + Model state + + + Name of the model + + + + Joint angle + + + Name of the joint + + + + + Index of the axis. + + + Angle of an axis + + + + + A nested model state element + + Name of the model. + + + + + + + + Scale for the 3 dimensions of the model. + + + + + diff --git a/sdformat/sdf/1.6/noise.sdf b/sdformat/sdf/1.6/noise.sdf new file mode 100644 index 0000000..0542422 --- /dev/null +++ b/sdformat/sdf/1.6/noise.sdf @@ -0,0 +1,31 @@ + + The properties of a sensor noise model. + + + + The type of noise. Currently supported types are: + "none" (no noise). + "gaussian" (draw noise values independently for each measurement from a Gaussian distribution). + "gaussian_quantized" ("gaussian" plus quantization of outputs (ie. rounding)) + + + + For type "gaussian*", the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian*", the standard deviation of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian*", the mean of the Gaussian distribution from which bias values are drawn. + + + For type "gaussian*", the standard deviation of the Gaussian distribution from which bias values are drawn. + + + + For type "gaussian_quantized", the precision of output signals. A value + of zero implies infinite precision / no quantization. + + + + diff --git a/sdformat/sdf/1.6/physics.sdf b/sdformat/sdf/1.6/physics.sdf new file mode 100644 index 0000000..d86777a --- /dev/null +++ b/sdformat/sdf/1.6/physics.sdf @@ -0,0 +1,225 @@ + + + The physics tag specifies the type and properties of the dynamics engine. + + + The name of this set of physics parameters. + + + + If true, this physics element is set as the default physics profile for the world. If multiple default physics elements exist, the first element marked as default is chosen. If no default physics element exists, the first physics element is chosen. + + + + The type of the dynamics engine. Current options are ode, bullet, simbody and rtql8. Defaults to ode if left unspecified. + + + + Maximum time step size at which every system in simulation can interact with the states of the world. (was physics.sdf's dt). + + + + + target simulation speedup factor, defined by ratio of simulation time to real-time. + + + + + Rate at which to update the physics engine (UpdatePhysics calls per real-time second). (was physics.sdf's update_rate). + + + + Maximum number of contacts allowed between two entities. This value can be over ridden by a max_contacts element in a collision element. + + + + Simbody specific physics properties + + (Currently not used in simbody) The time duration which advances with each iteration of the dynamics engine, this has to be no bigger than max_step_size under physics block. If left unspecified, min_step_size defaults to max_step_size. + + + Roughly the relative error of the system. + -LOG(accuracy) is roughly the number of significant digits. + + + Tolerable "slip" velocity allowed by the solver when static + friction is supposed to hold object in place. + + + vc + Assume real COR=1 when v=0. + e_min = given minimum COR, at v >= vp (a.k.a. plastic_coef_restitution) + d = slope = (1-e_min)/vp + OR, e_min = 1 - d*vp + e_max = maximum COR = 1-d*vc, reached at v=vc + e = 0, v <= vc + = 1 - d*v, vc < v < vp + = e_min, v >= vp + + dissipation factor = d*min(v,vp) [compliant] + cor = e [rigid] + + Combining rule e = 0, e1==e2==0 + = 2*e1*e2/(e1+e2), otherwise]]> + + + + Default contact material stiffness + (force/dist or torque/radian). + + + dissipation coefficient to be used in compliant contact; + if not given it is (1-min_cor)/plastic_impact_velocity + + + + this is the COR to be used at high velocities for rigid + impacts; if not given it is 1 - dissipation*plastic_impact_velocity + + + + + smallest impact velocity at which min COR is reached; set + to zero if you want the min COR always to be used + + + + static friction (mu_s) as described by this plot: http://gazebosim.org/wiki/File:Stribeck_friction.png + + + dynamic friction (mu_d) as described by this plot: http://gazebosim.org/wiki/File:Stribeck_friction.png + + + viscous friction (mu_v) with units of (1/velocity) as described by this plot: http://gazebosim.org/wiki/File:Stribeck_friction.png + + + + for rigid impacts only, impact velocity at which + COR is set to zero; normally inherited from global default but can + be overridden here. Combining rule: use larger velocity + + + + This is the largest slip velocity at which + we'll consider a transition to stiction. Normally inherited + from a global default setting. For a continuous friction model + this is the velocity at which the max static friction force + is reached. Combining rule: use larger velocity + + + + + + + Bullet specific physics properties + + + + One of the following types: sequential_impulse only. + + + The time duration which advances with each iteration of the dynamics engine, this has to be no bigger than max_step_size under physics block. If left unspecified, min_step_size defaults to max_step_size. + + + Number of iterations for each step. A higher number produces greater accuracy at a performance cost. + + + Set the successive over-relaxation parameter. + + + + + Bullet constraint parameters. + + Constraint force mixing parameter. See the ODE page for more information. + + + Error reduction parameter. See the ODE page for more information. + + + The depth of the surface layer around all geometry objects. Contacts are allowed to sink into the surface layer up to the given depth before coming to rest. The default value is zero. Increasing this to some small value (e.g. 0.001) can help prevent jittering problems due to contacts being repeatedly made and broken. + + + Similar to ODE's max_vel implementation. See http://web.archive.org/web/20120430155635/http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + Similar to ODE's max_vel implementation. See http://web.archive.org/web/20120430155635/http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + + + + ODE specific physics properties + + + + One of the following types: world, quick + + + The time duration which advances with each iteration of the dynamics engine, this has to be no bigger than max_step_size under physics block. If left unspecified, min_step_size defaults to max_step_size. + + + Number of threads to use for "islands" of disconnected models. + + + Number of iterations for each step. A higher number produces greater accuracy at a performance cost. + + + Experimental parameter. + + + Set the successive over-relaxation parameter. + + + Flag to use threading to speed up position correction computation. + + + + Flag to enable dynamic rescaling of moment of inertia in constrained directions. + See gazebo pull request 1114 for the implementation of this feature. + https://bitbucket.org/osrf/gazebo/pull-request/1114 + + + + + Name of ODE friction model to use. Valid values include: + + pyramid_model: (default) friction forces limited in two directions + in proportion to normal force. + box_model: friction forces limited to constant in two directions. + cone_model: friction force magnitude limited in proportion to normal force. + + See gazebo pull request 1522 for the implementation of this feature. + https://bitbucket.org/osrf/gazebo/pull-request/1522 + https://bitbucket.org/osrf/gazebo/commits/8c05ad64967c + + + + + + ODE constraint parameters. + + Constraint force mixing parameter. See the ODE page for more information. + + + Error reduction parameter. See the ODE page for more information. + + + The maximum correcting velocities allowed when resolving contacts. + + + The depth of the surface layer around all geometry objects. Contacts are allowed to sink into the surface layer up to the given depth before coming to rest. The default value is zero. Increasing this to some small value (e.g. 0.001) can help prevent jittering problems due to contacts being repeatedly made and broken. + + + + diff --git a/sdformat/sdf/1.6/plane_shape.sdf b/sdformat/sdf/1.6/plane_shape.sdf new file mode 100644 index 0000000..35bca28 --- /dev/null +++ b/sdformat/sdf/1.6/plane_shape.sdf @@ -0,0 +1,9 @@ + + Plane shape + + Normal direction for the plane + + + Length of each side of the plane + + diff --git a/sdformat/sdf/1.6/plugin.sdf b/sdformat/sdf/1.6/plugin.sdf new file mode 100644 index 0000000..26405ff --- /dev/null +++ b/sdformat/sdf/1.6/plugin.sdf @@ -0,0 +1,13 @@ + + + A plugin is a dynamically loaded chunk of code. It can exist as a child of world, model, and sensor. + + A unique name for the plugin, scoped to its parent. + + + Name of the shared library to load. If the filename is not a full path name, the file will be searched for in the configuration paths. + + + This is a special element that should not be specified in an SDF file. It automatically copies child elements into the SDF element so that a plugin can access the data. + + diff --git a/sdformat/sdf/1.6/polyline_shape.sdf b/sdformat/sdf/1.6/polyline_shape.sdf new file mode 100644 index 0000000..6658843 --- /dev/null +++ b/sdformat/sdf/1.6/polyline_shape.sdf @@ -0,0 +1,14 @@ + + Defines an extruded polyline shape + + + + A series of points that define the path of the polyline. + + + + + Height of the polyline + + + diff --git a/sdformat/sdf/1.6/population.sdf b/sdformat/sdf/1.6/population.sdf new file mode 100644 index 0000000..2f97e61 --- /dev/null +++ b/sdformat/sdf/1.6/population.sdf @@ -0,0 +1,59 @@ + + + + The population element defines how and where a set of models will + be automatically populated in Gazebo. + + + + + A unique name for the population. This name must not match + another population in the world. + + + + + + + + The number of models to place. + + + + + Specifies the type of object distribution and its optional parameters. + + + + + Define how the objects will be placed in the specified region. + - random: Models placed at random. + - uniform: Models approximately placed in a 2D grid pattern with control + over the number of objects. + - grid: Models evenly placed in a 2D grid pattern. The number of objects + is not explicitly specified, it is based on the number of rows and + columns of the grid. + - linear-x: Models evently placed in a row along the global x-axis. + - linear-y: Models evently placed in a row along the global y-axis. + - linear-z: Models evently placed in a row along the global z-axis. + + + + + Number of rows in the grid. + + + Number of columns in the grid. + + + Distance between elements of the grid. + + + + + + + + + + diff --git a/sdformat/sdf/1.6/pose.sdf b/sdformat/sdf/1.6/pose.sdf new file mode 100644 index 0000000..7cee8ed --- /dev/null +++ b/sdformat/sdf/1.6/pose.sdf @@ -0,0 +1,9 @@ + + + A position(x,y,z) and orientation(roll, pitch yaw) with respect to the specified frame. + + + Name of frame which the pose is defined relative to. + + + diff --git a/sdformat/sdf/1.6/projector.sdf b/sdformat/sdf/1.6/projector.sdf new file mode 100644 index 0000000..67de493 --- /dev/null +++ b/sdformat/sdf/1.6/projector.sdf @@ -0,0 +1,29 @@ + + + + Name of the projector + + + + Texture name + + + + Field of view + + + + + Near clip distance + + + + + far clip distance + + + + + + + diff --git a/sdformat/sdf/1.6/ray.sdf b/sdformat/sdf/1.6/ray.sdf new file mode 100644 index 0000000..5ffeea3 --- /dev/null +++ b/sdformat/sdf/1.6/ray.sdf @@ -0,0 +1,73 @@ + + These elements are specific to the ray (laser) sensor. + + + + + + + + The number of simulated rays to generate per complete laser sweep cycle. + + + + This number is multiplied by samples to determine the number of range data points returned. If resolution is less than one, range data is interpolated. If resolution is greater than one, range data is averaged. + + + + + + + + Must be greater or equal to min_angle + + + + + + + + The number of simulated rays to generate per complete laser sweep cycle. + + + + This number is multiplied by samples to determine the number of range data points returned. If resolution is less than one, range data is interpolated. If resolution is greater than one, range data is averaged. + + + + + + + + Must be greater or equal to min_angle + + + + + + + specifies range properties of each simulated ray + + The minimum distance for each ray. + + + The maximum distance for each ray. + + + Linear resolution of each ray. + + + + + The properties of the noise model that should be applied to generated scans + + The type of noise. Currently supported types are: "gaussian" (draw noise values independently for each beam from a Gaussian distribution). + + + For type "gaussian," the mean of the Gaussian distribution from which noise values are drawn. + + + For type "gaussian," the standard deviation of the Gaussian distribution from which noise values are drawn. + + + diff --git a/sdformat/sdf/1.6/rfid.sdf b/sdformat/sdf/1.6/rfid.sdf new file mode 100644 index 0000000..61351dd --- /dev/null +++ b/sdformat/sdf/1.6/rfid.sdf @@ -0,0 +1,2 @@ + + diff --git a/sdformat/sdf/1.6/rfidtag.sdf b/sdformat/sdf/1.6/rfidtag.sdf new file mode 100644 index 0000000..55699dc --- /dev/null +++ b/sdformat/sdf/1.6/rfidtag.sdf @@ -0,0 +1,2 @@ + + diff --git a/sdformat/sdf/1.6/road.sdf b/sdformat/sdf/1.6/road.sdf new file mode 100644 index 0000000..172e480 --- /dev/null +++ b/sdformat/sdf/1.6/road.sdf @@ -0,0 +1,16 @@ + + + + Name of the road + + + + Width of the road + + + + A series of points that define the path of the road. + + + + diff --git a/sdformat/sdf/1.6/root.sdf b/sdformat/sdf/1.6/root.sdf new file mode 100644 index 0000000..47d443a --- /dev/null +++ b/sdformat/sdf/1.6/root.sdf @@ -0,0 +1,13 @@ + + SDF base element. + + + Version number of the SDF format. + + + + + + + + diff --git a/sdformat/sdf/1.6/scene.sdf b/sdformat/sdf/1.6/scene.sdf new file mode 100644 index 0000000..0cdb52e --- /dev/null +++ b/sdformat/sdf/1.6/scene.sdf @@ -0,0 +1,82 @@ + + + Specifies the look of the environment. + + + Color of the ambient light. + + + + Color of the background. + + + + Properties for the sky + + Time of day [0..24] + + + Sunrise time [0..24] + + + Sunset time [0..24] + + + + Sunset time [0..24] + + Speed of the clouds + + + + Direction of the cloud movement + + + Density of clouds + + + + Average size of the clouds + + + + Ambient cloud color + + + + + + Enable/disable shadows + + + + Controls fog + + Fog color + + + Fog type: constant, linear, quadratic + + + Distance to start of fog + + + Distance to end of fog + + + Density of fog + + + + + Enable/disable the grid + + + + Show/hide world origin indicator + + + diff --git a/sdformat/sdf/1.6/schema/types.xsd b/sdformat/sdf/1.6/schema/types.xsd new file mode 100644 index 0000000..53f3d8d --- /dev/null +++ b/sdformat/sdf/1.6/schema/types.xsd @@ -0,0 +1,44 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.6/sensor.sdf b/sdformat/sdf/1.6/sensor.sdf new file mode 100644 index 0000000..1c503e3 --- /dev/null +++ b/sdformat/sdf/1.6/sensor.sdf @@ -0,0 +1,63 @@ + + + The sensor tag describes the type and properties of a sensor. + + + A unique name for the sensor. This name must not match another model in the model. + + + + The type name of the sensor. By default, SDF supports types + altimeter, + camera, + contact, + depth, + force_torque, + gps, + gpu_ray, + imu, + logical_camera, + magnetometer, + multicamera, + ray, + rfid, + rfidtag, + sonar, + wireless_receiver, and + wireless_transmitter. + + + + If true the sensor will always be updated according to the update rate. + + + + The frequency at which the sensor data is generated. If left unspecified, the sensor will generate data every cycle. + + + + If true, the sensor is visualized in the GUI + + + + Name of the topic on which data is published. This is necessary for visualization + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/1.6/server (å¤ä»¶).sdf b/sdformat/sdf/1.6/server (å¤ä»¶).sdf new file mode 100644 index 0000000..9a622a0 --- /dev/null +++ b/sdformat/sdf/1.6/server (å¤ä»¶).sdf @@ -0,0 +1,17 @@ + + + The server tag specifies the ip and port of the remote server. + + + The ip of the remote server. + + + + The flag of the remote server. + + + + the port of the remote port + + + diff --git a/sdformat/sdf/1.6/server.sdf b/sdformat/sdf/1.6/server.sdf new file mode 100644 index 0000000..47d1606 --- /dev/null +++ b/sdformat/sdf/1.6/server.sdf @@ -0,0 +1,29 @@ + + + The distributed tag specifies the ip and port of the remote server. + + + The type of the distribution(0:client or 1:server). + + + + The ip of the remote server. + + + + The flag of the remote server. + + + + the port of the remote port + + + + the port of the remote port + + + + the port of the remote port + + + diff --git a/sdformat/sdf/1.6/sonar.sdf b/sdformat/sdf/1.6/sonar.sdf new file mode 100644 index 0000000..d27017f --- /dev/null +++ b/sdformat/sdf/1.6/sonar.sdf @@ -0,0 +1,13 @@ + + These elements are specific to the sonar sensor. + + Minimum range + + + Max range + + + + Radius of the sonar cone at max range. + + diff --git a/sdformat/sdf/1.6/sphere_shape.sdf b/sdformat/sdf/1.6/sphere_shape.sdf new file mode 100644 index 0000000..73ad03e --- /dev/null +++ b/sdformat/sdf/1.6/sphere_shape.sdf @@ -0,0 +1,6 @@ + + Sphere shape + + radius of the sphere + + diff --git a/sdformat/sdf/1.6/spherical_coordinates.sdf b/sdformat/sdf/1.6/spherical_coordinates.sdf new file mode 100644 index 0000000..a0aa103 --- /dev/null +++ b/sdformat/sdf/1.6/spherical_coordinates.sdf @@ -0,0 +1,59 @@ + + + + Name of planetary surface model, used to determine the surface altitude + at a given latitude and longitude. The default is an ellipsoid model of + the earth based on the WGS-84 standard. It is used in Gazebo's GPS sensor + implementation. + + + + + + This field identifies how Gazebo world frame is aligned in Geographical + sense. The final Gazebo world frame orientation is obtained by rotating + a frame aligned with following notation by the field heading_deg (Note + that heading_deg corresponds to positive yaw rotation in the NED frame, + so it's inverse specifies positive Z-rotation in ENU or NWU). + Options are: + - ENU (East-North-Up) + - NED (North-East-Down) + - NWU (North-West-Up) + For example, world frame specified by setting world_orientation="ENU" + and heading_deg=-90° is effectively equivalent to NWU with heading of 0°. + + + + + Geodetic latitude at origin of gazebo reference frame, specified + in units of degrees. + + + + + + Longitude at origin of gazebo reference frame, specified in units + of degrees. + + + + + + Elevation of origin of gazebo reference frame, specified in meters. + + + + + + Heading offset of gazebo reference frame, measured as angle between + Gazebo world frame and the world_frame_orientation type (ENU/NED/NWU). + Rotations about the downward-vector (e.g. North to East) are positive. + The direction of rotation is chosen to be consistent with compass + heading convention (e.g. 0 degrees points North and 90 degrees + points East, positive rotation indicates counterclockwise rotation + when viewed from top-down direction). + The angle is specified in degrees. + + + + diff --git a/sdformat/sdf/1.6/state.sdf b/sdformat/sdf/1.6/state.sdf new file mode 100644 index 0000000..6a13e28 --- /dev/null +++ b/sdformat/sdf/1.6/state.sdf @@ -0,0 +1,41 @@ + + + + + Name of the world this state applies to + + + + Simulation time stamp of the state [seconds nanoseconds] + + + + Wall time stamp of the state [seconds nanoseconds] + + + + Real time stamp of the state [seconds nanoseconds] + + + + Number of simulation iterations. + + + + A list containing the entire description of entities inserted. + + + + + + A list of names of deleted entities/ + + The name of a deleted entity. + + + + + + + + diff --git a/sdformat/sdf/1.6/surface.sdf b/sdformat/sdf/1.6/surface.sdf new file mode 100644 index 0000000..b6d5867 --- /dev/null +++ b/sdformat/sdf/1.6/surface.sdf @@ -0,0 +1,245 @@ + + The surface parameters + + + + Bounciness coefficient of restitution, from [0...1], where 0=no bounciness. + + + Bounce capture velocity, below which effective coefficient of restitution is 0. + + + + + + + + Parameters for torsional friction + + + Torsional friction coefficient, unitless maximum ratio of + tangential stress to normal stress. + + + + + If this flag is true, + torsional friction is calculated using the "patch_radius" parameter. + If this flag is set to false, + "surface_radius" (R) and contact depth (d) + are used to compute the patch radius as sqrt(R*d). + + + + Radius of contact patch surface. + + + Surface radius on the point of contact. + + + Torsional friction parameters for ODE + + + Force dependent slip for torsional friction, + equivalent to inverse of viscous damping coefficient + with units of rad/s/(Nm). + A slip value of 0 is infinitely viscous. + + + + + + + ODE friction parameters + + + Coefficient of friction in first friction pyramid direction, + the unitless maximum ratio of force in first friction pyramid + direction to normal force. + + + + + Coefficient of friction in second friction pyramid direction, + the unitless maximum ratio of force in second friction pyramid + direction to normal force. + + + + + Unit vector specifying first friction pyramid direction in + collision-fixed reference frame. + If the friction pyramid model is in use, + and this value is set to a unit vector for one of the + colliding surfaces, + the ODE Collide callback function will align the friction pyramid directions + with a reference frame fixed to that collision surface. + If both surfaces have this value set to a vector of zeros, + the friction pyramid directions will be aligned with the world frame. + If this value is set for both surfaces, the behavior is undefined. + + + + + Force dependent slip in first friction pyramid direction, + equivalent to inverse of viscous damping coefficient + with units of m/s/N. + A slip value of 0 is infinitely viscous. + + + + + Force dependent slip in second friction pyramid direction, + equivalent to inverse of viscous damping coefficient + with units of m/s/N. + A slip value of 0 is infinitely viscous. + + + + + + + Coefficient of friction in first friction pyramid direction, + the unitless maximum ratio of force in first friction pyramid + direction to normal force. + + + + + Coefficient of friction in second friction pyramid direction, + the unitless maximum ratio of force in second friction pyramid + direction to normal force. + + + + + Unit vector specifying first friction pyramid direction in + collision-fixed reference frame. + If the friction pyramid model is in use, + and this value is set to a unit vector for one of the + colliding surfaces, + the friction pyramid directions will be aligned + with a reference frame fixed to that collision surface. + If both surfaces have this value set to a vector of zeros, + the friction pyramid directions will be aligned with the world frame. + If this value is set for both surfaces, the behavior is undefined. + + + + Coefficient of rolling friction + + + + + + + + Flag to disable contact force generation, while still allowing collision checks and contact visualization to occur. + + + Bitmask for collision filtering when collide_without_contact is on + + + + Bitmask for collision filtering. This will override collide_without_contact + + + + + + + + + Poisson's ratio is the unitless ratio between transverse and axial strain. + This value must lie between (-1, 0.5). Defaults to 0.3 for typical steel. + Note typical silicone elastomers have Poisson's ratio near 0.49 ~ 0.50. + + For reference, approximate values for Material:(Young's Modulus, Poisson's Ratio) + for some of the typical materials are: + Plastic: (1e8 ~ 3e9 Pa, 0.35 ~ 0.41), + Wood: (4e9 ~ 1e10 Pa, 0.22 ~ 0.50), + Aluminum: (7e10 Pa, 0.32 ~ 0.35), + Steel: (2e11 Pa, 0.26 ~ 0.31). + + + + + Young's Modulus in SI derived unit Pascal. + Defaults to -1. If value is less or equal to zero, + contact using elastic modulus (with Poisson's Ratio) is disabled. + + For reference, approximate values for Material:(Young's Modulus, Poisson's Ratio) + for some of the typical materials are: + Plastic: (1e8 ~ 3e9 Pa, 0.35 ~ 0.41), + Wood: (4e9 ~ 1e10 Pa, 0.22 ~ 0.50), + Aluminum: (7e10 Pa, 0.32 ~ 0.35), + Steel: (2e11 Pa, 0.26 ~ 0.31). + + + + + ODE contact parameters + + Soft constraint force mixing. + + + Soft error reduction parameter + + + dynamically "stiffness"-equivalent coefficient for contact joints + + + dynamically "damping"-equivalent coefficient for contact joints + + + maximum contact correction velocity truncation term. + + + minimum allowable depth before contact correction impulse is applied + + + + Bullet contact parameters + + Soft constraint force mixing. + + + Soft error reduction parameter + + + dynamically "stiffness"-equivalent coefficient for contact joints + + + dynamically "damping"-equivalent coefficient for contact joints + + + Similar to ODE's max_vel implementation. See http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + Similar to ODE's max_vel implementation. See http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information. + + + + + + + + soft contact pamameters based on paper: + http://www.cc.gatech.edu/graphics/projects/Sumit/homepage/papers/sigasia11/jain_softcontacts_siga11.pdf + + + This is variable k_v in the soft contacts paper. Its unit is N/m. + + + This is variable k_e in the soft contacts paper. Its unit is N/m. + + + Viscous damping of point velocity in body frame. Its unit is N/m/s. + + + Fraction of mass to be distributed among deformable nodes. + + + + + diff --git a/sdformat/sdf/1.6/transceiver.sdf b/sdformat/sdf/1.6/transceiver.sdf new file mode 100644 index 0000000..9f05b06 --- /dev/null +++ b/sdformat/sdf/1.6/transceiver.sdf @@ -0,0 +1,34 @@ + + These elements are specific to a wireless transceiver. + + + Service set identifier (network name) + + + + Specifies the frequency of transmission in MHz + + + + Only a frequency range is filtered. Here we set the lower bound (MHz). + + + + + Only a frequency range is filtered. Here we set the upper bound (MHz). + + + + + Specifies the antenna gain in dBi + + + + Specifies the transmission power in dBm + + + + Mininum received signal power in dBm + + + diff --git a/sdformat/sdf/1.6/urdf.sdf b/sdformat/sdf/1.6/urdf.sdf new file mode 100644 index 0000000..6068d5c --- /dev/null +++ b/sdformat/sdf/1.6/urdf.sdf @@ -0,0 +1,19 @@ + + + The robot element defines a complete robot or any other physical object using URDF. + + + A unique name for the model. This name must not match another model in the world. + + + + A position and orientation in the global coordinate frame for the model. Position(x,y,z) and rotation (roll, pitch yaw) in the global coordinate frame. + + + + + + + + + diff --git a/sdformat/sdf/1.6/visual.sdf b/sdformat/sdf/1.6/visual.sdf new file mode 100644 index 0000000..04b29c7 --- /dev/null +++ b/sdformat/sdf/1.6/visual.sdf @@ -0,0 +1,35 @@ + + + The visual properties of the link. This element specifies the shape of the object (box, cylinder, etc.) for visualization purposes. + + + Unique name for the visual element within the scope of the parent link. + + + + If true the visual will cast shadows. + + + + will be implemented in the future release. + + + + The amount of transparency( 0=opaque, 1 = fully transparent) + + + + Optional meta information for the visual. The information contained within this element should be used to provide additional feedback to an end user. + + + The layer in which this visual is displayed. The layer number is useful for programs, such as Gazebo, that put visuals in different layers for enhanced visualization. + + + + + + + + + + diff --git a/sdformat/sdf/1.6/world.sdf b/sdformat/sdf/1.6/world.sdf new file mode 100644 index 0000000..a0223ad --- /dev/null +++ b/sdformat/sdf/1.6/world.sdf @@ -0,0 +1,66 @@ + + The world element encapsulates an entire world description including: models, scene, physics, joints, and plugins + + + Unique name of the world + + + + Global audio properties. + + + Device to use for audio playback. A value of "default" will use the system's default audio device. Otherwise, specify a an audio device file" + + + + + The wind tag specifies the type and properties of the wind. + + + Linear velocity of the wind. + + + + + Include resources from a URI + + URI to a resource, such as a model + + + + Override the name of the included model. + + + + Override the static value of the included model. + + + + + + + The gravity vector in m/s^2, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + The magnetic vector in Tesla, expressed in a coordinate frame defined by the spherical_coordinates tag. + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/sdf/CMakeLists.txt b/sdformat/sdf/CMakeLists.txt new file mode 100644 index 0000000..61342e2 --- /dev/null +++ b/sdformat/sdf/CMakeLists.txt @@ -0,0 +1,9 @@ +add_subdirectory(1.0) +add_subdirectory(1.2) +add_subdirectory(1.3) +add_subdirectory(1.4) +add_subdirectory(1.5) +add_subdirectory(1.6) + +add_custom_target(schema) +add_dependencies(schema schema1_6) diff --git a/sdformat/sdf/Migration.md b/sdformat/sdf/Migration.md new file mode 100644 index 0000000..cdc63b3 --- /dev/null +++ b/sdformat/sdf/Migration.md @@ -0,0 +1,93 @@ +# Migration Guide for SDF Protocol +This document contains information about migrating +between different versions of the SDF protocol. +The SDF protocol version number is specified in the `version` attribute +of the `sdf` element (1.4, 1.5, 1.6, etc.) +and is distinct from sdformat library version +(2.3, 3.0, 4.0, etc.). + +# Note on backward compatibility +There are `*.convert` files that allow old sdf files to be migrated +forward programmatically. +This document aims to contain similar information to those files +but with improved human-readability. + +## SDF protocol 1.5 to 1.6 + +### Additions + +1. **heightmap_shape.sdf** `sampling` element + + description: Samples per heightmap datum. + For rasterized heightmaps, this indicates the number of samples to take per pixel. + Using a lower value, e.g. 1, will generally improve the performance + of the heightmap but lower the heightmap quality. + + type: unsigned int + + default: 2 + + required: 0 + + [pull request 293](https://bitbucket.org/osrf/sdformat/pull-requests/293) + +1. **link.sdf** `enable_wind` element + + description: If true, the link is affected by the wind + + type: bool + + default: false + + required: 0 + + [pull request 240](https://bitbucket.org/osrf/sdformat/pull-requests/240) + +1. **model.sdf** `enable_wind` element + + description: If set to true, all links in the model + will be affected by the wind. + Can be overriden by the link wind property. + + type: bool + + default: false + + required: 0 + + [pull request 240](https://bitbucket.org/osrf/sdformat/pull-requests/240) + +1. **model_state.sdf** `scale` element + + description: Scale for the 3 dimensions of the model. + + type: vector3 + + default: "1 1 1" + + required: 0 + + [pull request 246](https://bitbucket.org/osrf/sdformat/pull-requests/246) + +1. **physics.sdf** `friction_model` element + + description: Name of ODE friction model to use. Valid values include: + + pyramid_model: (default) friction forces limited in two directions + in proportion to normal force. + + box_model: friction forces limited to constant in two directions. + + cone_model: friction force magnitude limited in proportion to normal force. + See [gazebo pull request 1522](https://bitbucket.org/osrf/gazebo/pull-request/1522) + (merged in [gazebo 8c05ad64967c](https://bitbucket.org/osrf/gazebo/commits/8c05ad64967c)) + for the implementation of this feature. + + type: string + + default: "pyramid_model" + + required: 0 + + [pull request 294](https://bitbucket.org/osrf/sdformat/pull-requests/294) + +1. **world.sdf** `wind` element + + description: The wind tag specifies the type and properties of the wind. + + required: 0 + + [pull request 240](https://bitbucket.org/osrf/sdformat/pull-requests/240) + +1. **world.sdf** `wind::linear_velocity` element + + description: Linear velocity of the wind. + + type: vector3 + + default: "0 0 0" + + required: 0 + + [pull request 240](https://bitbucket.org/osrf/sdformat/pull-requests/240) + +### Modifications + +1. `gravity` and `magnetic_field` elements are moved + from `physics` to `world` + + [pull request 247](https://bitbucket.org/osrf/sdformat/pull-requests/247) + + [gazebo pull request 2090](https://bitbucket.org/osrf/gazebo/pull-requests/2090) + +1. A new style for representing the noise properties of an `imu` was implemented + in [pull request 199](https://bitbucket.org/osrf/sdformat/pull-requests/199) + for sdf 1.5 and the old style was declared as deprecated. + The old style has been removed from sdf 1.6 with the conversion script + updating to the new style. + + [pull request 199](https://bitbucket.org/osrf/sdformat/pull-requests/199) + + [pull request 243](https://bitbucket.org/osrf/sdformat/pull-requests/243) + + [pull request 244](https://bitbucket.org/osrf/sdformat/pull-requests/244) + diff --git a/sdformat/src/Assert.cc b/sdformat/src/Assert.cc new file mode 100644 index 0000000..d82e4b7 --- /dev/null +++ b/sdformat/src/Assert.cc @@ -0,0 +1,41 @@ +/* + * Copyright 2013 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#include +#include "sdf/Assert.hh" +#include "sdf/Exception.hh" + +/* + * When using the flag BOOST_ENABLE_ASSERT_HANDLER, the boost functions + * assert_failed and assertion_failed_msg function need to be defined. SDF + * behaviour is to thrown a gazebo::common::AssertionInternalError. + */ +namespace boost +{ + void assertion_failed(char const * expr, char const * function, + char const * file, int64_t line) + { + throw sdf::AssertionInternalError(file, line, expr, function); + } + + + void assertion_failed_msg(char const * expr, char const * msg, + char const * function, char const * file, + int64_t line) + { + throw sdf::AssertionInternalError(file, line, expr, function, msg); + } +} diff --git a/sdformat/src/CMakeLists.txt b/sdformat/src/CMakeLists.txt new file mode 100644 index 0000000..b15bd68 --- /dev/null +++ b/sdformat/src/CMakeLists.txt @@ -0,0 +1,91 @@ +include (${sdf_cmake_dir}/SDFUtils.cmake) + +include_directories( + ${Boost_INCLUDE_DIR} + ${IGNITION-MATH_INCLUDE_DIRS} +) + +link_directories( + ${PROJECT_BINARY_DIR}/test + ${Boost_LIBRARY_DIR} + ${IGNITION-MATH_LIBRARY_DIRS} +) + +if (USE_EXTERNAL_URDF) + link_directories(${URDF_LIBRARY_DIRS}) +endif() + +if (USE_EXTERNAL_TINYXML) + link_directories(${tinyxml_LIBRARY_DIRS}) +endif() + +set (sources + Assert.cc + Console.cc + Converter.cc + Element.cc + Exception.cc + parser.cc + parser_urdf.cc + Param.cc + SDF.cc + SDFExtension.cc + Types.cc +) + +include_directories(${Boost_INCLUDE_DIRS}) + +if (USE_EXTERNAL_TINYXML) + include_directories(${tinyxml_INCLUDE_DIRS}) +else() + set(sources ${sources} + win/tinyxml/tinystr.cpp + win/tinyxml/tinyxmlerror.cpp + win/tinyxml/tinyxml.cpp + win/tinyxml/tinyxmlparser.cpp) + + install (FILES win/tinyxml/tinyxml.h + DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/sdformat-${SDF_VERSION}) +endif() + +if (USE_EXTERNAL_URDF) + include_directories(${URDF_INCLUDE_DIRS}) +else() + include_directories(${CMAKE_CURRENT_SOURCE_DIR}/urdf) + set(sources ${sources} + urdf/urdf_parser/model.cpp + urdf/urdf_parser/link.cpp + urdf/urdf_parser/joint.cpp + urdf/urdf_parser/pose.cpp + urdf/urdf_parser/twist.cpp + urdf/urdf_parser/urdf_model_state.cpp + urdf/urdf_parser/urdf_sensor.cpp + urdf/urdf_parser/world.cpp +) +endif() + +set (gtest_sources + SDF_TEST.cc + Console_TEST.cc + Converter_TEST.cc + Exception_TEST.cc + parser_urdf_TEST.cc + Param_TEST.cc +) +sdf_build_tests(${gtest_sources}) + +sdf_add_library(sdformat ${sources}) +target_link_libraries(sdformat ${Boost_LIBRARIES} ${IGNITION-MATH_LIBRARIES}) + +if (USE_EXTERNAL_TINYXML) + target_link_libraries(sdformat ${tinyxml_LIBRARIES}) +endif() + +message (STATUS "URDF_LIBRARY_DIRS=${URDF_LIBRARY_DIRS}") +message (STATUS "URDF_LIBRARIES=${URDF_LIBRARIES}") + +if (USE_EXTERNAL_URDF) + target_link_libraries(sdformat ${URDF_LIBRARIES}) +endif() + +sdf_install_library(sdformat) diff --git a/sdformat/src/Console.cc b/sdformat/src/Console.cc new file mode 100644 index 0000000..f654744 --- /dev/null +++ b/sdformat/src/Console.cc @@ -0,0 +1,171 @@ +/* + * Copyright 2013 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include +#include +#include +#include + +/// \todo Remove this diagnositic push/pop in version 5 +#ifndef _WIN32 +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif +#include "sdf/Types.hh" +#ifndef _WIN32 +#pragma GCC diagnostic pop +#endif + +#include "sdf/Console.hh" + +using namespace sdf; + +/// Static pointer to the console. +static std::shared_ptr myself; +static std::mutex g_instance_mutex; + +/// \todo Output disabled for windows, to allow tests to pass. We should +/// disable output just for tests on windows. +#ifndef _WIN32 +static bool g_quiet = false; +#else +static bool g_quiet = true; +#endif + +static Console::ConsoleStream g_NullStream(NULL); + +////////////////////////////////////////////////// +Console::Console() + : dataPtr(new ConsolePrivate) +{ + // Set up the file that we'll log to. + try + { +#ifndef _WIN32 + char *home = getenv("HOME"); +#else + const char *home = sdf::winGetEnv("HOMEPATH"); +#endif + if (!home) + { + std::cerr << "No HOME defined in the environment. Will not log." + << std::endl; + return; + } + boost::filesystem::path logFile(home); + logFile /= ".sdformat"; + logFile /= "sdformat.log"; + boost::filesystem::path logDir = logFile.parent_path(); + if (!boost::filesystem::exists(logDir)) + { + boost::filesystem::create_directory(logDir); + } + else if (!boost::filesystem::is_directory(logDir)) + { + std::cerr << logDir << " exists but is not a directory. Will not log." + << std::endl; + return; + } + this->dataPtr->logFileStream.open(logFile.string().c_str(), std::ios::out); + } + catch(const boost::filesystem::filesystem_error& e) + { + std::cerr << "Exception while setting up logging: " << e.what() + << std::endl; + return; + } +} + +////////////////////////////////////////////////// +Console::~Console() +{ +} + +////////////////////////////////////////////////// +ConsolePtr Console::Instance() +{ + std::lock_guard lock(g_instance_mutex); + if (!myself) + myself.reset(new Console()); + + return myself; +} + +////////////////////////////////////////////////// +void Console::SetQuiet(bool _quiet) +{ + g_quiet = _quiet; +} + +////////////////////////////////////////////////// +Console::ConsoleStream &Console::ColorMsg(const std::string &lbl, + const std::string &file, + unsigned int line, int color) +{ + if (!g_quiet) + { + this->dataPtr->msgStream.Prefix(lbl, file, line, color); + return this->dataPtr->msgStream; + } + else + { + return g_NullStream; + } +} + +////////////////////////////////////////////////// +Console::ConsoleStream &Console::Log(const std::string &lbl, + const std::string &file, + unsigned int line) +{ + this->dataPtr->logStream.Prefix(lbl, file, line, 0); + return this->dataPtr->logStream; +} + +////////////////////////////////////////////////// +void Console::ConsoleStream::Prefix(const std::string &_lbl, + const std::string &_file, + unsigned int _line, + // This is here to prevent a compilation warning about an unused variable. +#ifndef _WIN32 + int _color +#else + int /*_color*/ +#endif +) +{ + size_t index = _file.find_last_of("/") + 1; + + if (this->stream) + { +#ifndef _WIN32 + *this->stream << "\033[1;" << _color << "m" << _lbl << " [" << + _file.substr(index , _file.size() - index) << ":" << _line << + "]\033[0m "; +#else + *this->stream << _lbl << " [" << + _file.substr(index , _file.size() - index) << ":" << _line << "] "; +#endif + } + + if (Console::Instance()->dataPtr->logFileStream.is_open()) + { + Console::Instance()->dataPtr->logFileStream << _lbl << " [" << + _file.substr(index , _file.size() - index)<< ":" << _line << "] "; + } +} diff --git a/sdformat/src/Console_TEST.cc b/sdformat/src/Console_TEST.cc new file mode 100644 index 0000000..01d8450 --- /dev/null +++ b/sdformat/src/Console_TEST.cc @@ -0,0 +1,37 @@ +/* + * Copyright 2013 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include "sdf/Console.hh" + +//////////////////////////////////////////////////// +/// Test out the differerent console messages. +TEST(Console, Messages) +{ + sdferr << "Error.\n"; + sdfwarn << "Warning.\n"; + sdfmsg << "Message.\n"; + sdfdbg << "Debug.\n"; +} + +///////////////////////////////////////////////// +/// Main +int main(int argc, char **argv) +{ + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/sdformat/src/Converter.cc b/sdformat/src/Converter.cc new file mode 100644 index 0000000..8a33a62 --- /dev/null +++ b/sdformat/src/Converter.cc @@ -0,0 +1,523 @@ +/* + * Copyright 2012 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include +#include +#include +#include + +#include "sdf/SDFImpl.hh" +#include "sdf/Assert.hh" +#include "sdf/Console.hh" +#include "sdf/Converter.hh" + +using namespace sdf; + +///////////////////////////////////////////////// +bool Converter::Convert(TiXmlDocument *_doc, const std::string &_toVersion, + bool _quiet) +{ + TiXmlElement *elem = _doc->FirstChildElement("gazebo"); + + // Replace with + if (elem && boost::lexical_cast(_toVersion) >= 1.3) + { + elem->SetValue("sdf"); + } + else if (!elem) + elem = _doc->FirstChildElement("sdf"); + + if (!elem || !elem->Attribute("version")) + { + sdferr << " Unable to determine original SDF version\n"; + return false; + } + + std::string origVersion = elem->Attribute("version"); + + if (origVersion == _toVersion) + return true; + + if (!_quiet) + { + sdfdbg << "Version[" << origVersion << "] to Version[" << _toVersion + << "]\n" + << " Please use the gz sdf tool to update your SDF files.\n" + << " $ gz sdf -c [sdf_file]\n"; + } + + elem->SetAttribute("version", _toVersion); + + std::string origVersionStr = origVersion; + boost::replace_all(origVersion, ".", "_"); + + std::string filename = sdf::findFile(origVersion + ".convert"); + + // Use convert file in the current sdf version folder for conversion. If file + // does not exist, then find intermediate convert files and iteratively + // convert the sdf elem. Ideally, users should use gzsdf convert so that the + // latest sdf versioned file is written and no subsequent conversions are + // necessary. + TiXmlDocument xmlDoc; + if (!xmlDoc.LoadFile(filename)) + { + std::string sdfPath = sdf::findFile("sdformat/"); + + // find all sdf version dirs in resource path + boost::filesystem::directory_iterator endIter; + std::set sdfDirs; + if (boost::filesystem::exists(sdfPath) + && boost::filesystem::is_directory(sdfPath)) + { + for (boost::filesystem::directory_iterator dirIter(sdfPath); + dirIter != endIter ; ++dirIter) + { + if (boost::filesystem::is_directory(dirIter->status())) + { + if (boost::algorithm::ilexicographical_compare( + origVersionStr, (*dirIter).path().filename().string())) + { + sdfDirs.insert((*dirIter)); + } + } + } + } + + // loop through sdf dirs and do the intermediate conversions + for (std::set::iterator it = sdfDirs.begin(); + it != sdfDirs.end(); ++it) + { + boost::filesystem::path convertFile + = boost::filesystem::operator/((*it).string(), origVersion+".convert"); + if (boost::filesystem::exists(convertFile)) + { + if (!xmlDoc.LoadFile(convertFile.string())) + { + sdferr << "Unable to load file[" << convertFile << "]\n"; + return false; + } + ConvertImpl(elem, xmlDoc.FirstChildElement("convert")); + if ((*it).filename() == _toVersion) + return true; + + origVersion = (*it).filename().string(); + boost::replace_all(origVersion, ".", "_"); + } + else + { + continue; + } + } + sdferr << "Unable to convert from SDF version " << origVersionStr + << " to " << _toVersion << "\n"; + return false; + } + + ConvertImpl(elem, xmlDoc.FirstChildElement("convert")); + + return true; +} + +///////////////////////////////////////////////// +void Converter::Convert(TiXmlDocument *_doc, TiXmlDocument *_convertDoc) +{ + SDF_ASSERT(_doc != NULL, "SDF XML doc is NULL"); + SDF_ASSERT(_convertDoc != NULL, "Convert XML doc is NULL"); + + ConvertImpl(_doc->FirstChildElement(), _convertDoc->FirstChildElement()); +} + +///////////////////////////////////////////////// +void Converter::ConvertImpl(TiXmlElement *_elem, TiXmlElement *_convert) +{ + SDF_ASSERT(_elem != NULL, "SDF element is NULL"); + SDF_ASSERT(_convert != NULL, "Convert element is NULL"); + + CheckDeprecation(_elem, _convert); + + for (TiXmlElement *convertElem = _convert->FirstChildElement("convert"); + convertElem; convertElem = convertElem->NextSiblingElement("convert")) + { + TiXmlElement *elem = NULL; + elem = _elem->FirstChildElement(convertElem->Attribute("name")); + while (elem) + { + ConvertImpl(elem, convertElem); + elem = elem->NextSiblingElement(convertElem->Attribute("name")); + } + } + + for (TiXmlElement *childElem = _convert->FirstChildElement(); + childElem; childElem = childElem->NextSiblingElement()) + { + if (childElem->ValueStr() == "rename") + Rename(_elem, childElem); + else if (childElem->ValueStr() == "copy") + Move(_elem, childElem, true); + else if (childElem->ValueStr() == "move") + Move(_elem, childElem, false); + else if (childElem->ValueStr() == "add") + Add(_elem, childElem); + else if (childElem->ValueStr() == "remove") + Remove(_elem, childElem); + else if (childElem->ValueStr() != "convert") + { + std::cerr << "Unknown convert element[" << childElem->ValueStr() + << "]\n"; + } + } +} + +///////////////////////////////////////////////// +void Converter::Rename(TiXmlElement *_elem, TiXmlElement *_renameElem) +{ + SDF_ASSERT(_elem != NULL, "SDF element is NULL"); + SDF_ASSERT(_renameElem != NULL, "Rename element is NULL"); + + TiXmlElement *fromConvertElem = _renameElem->FirstChildElement("from"); + TiXmlElement *toConvertElem = _renameElem->FirstChildElement("to"); + + const char *fromElemName = fromConvertElem->Attribute("element"); + const char *fromAttrName = fromConvertElem->Attribute("attribute"); + + const char *toElemName = toConvertElem->Attribute("element"); + const char *toAttrName = toConvertElem->Attribute("attribute"); + + const char *value = GetValue(fromElemName, fromAttrName, _elem); + if (!value) + return; + + if (!toElemName) + { + sdferr << "No 'to' element name specified\n"; + return; + } + + TiXmlElement *replaceTo = new TiXmlElement(toElemName); + if (toAttrName) + replaceTo->SetAttribute(toAttrName, value); + else + { + TiXmlText *text = new TiXmlText(value); + replaceTo->LinkEndChild(text); + } + + if (fromElemName) + { + TiXmlElement *replaceFrom = _elem->FirstChildElement(fromElemName); + _elem->ReplaceChild(replaceFrom, *replaceTo); + } + else if (fromAttrName) + { + _elem->RemoveAttribute(fromAttrName); + _elem->LinkEndChild(replaceTo); + } +} + +///////////////////////////////////////////////// +void Converter::Add(TiXmlElement *_elem, TiXmlElement *_addElem) +{ + SDF_ASSERT(_elem != NULL, "SDF element is NULL"); + SDF_ASSERT(_addElem != NULL, "Add element is NULL"); + + const char *attributeName = _addElem->Attribute("attribute"); + const char *elementName = _addElem->Attribute("element"); + const char *value = _addElem->Attribute("value"); + + if (!((attributeName == NULL) ^ (elementName == NULL))) + { + sdferr << "Exactly one 'element' or 'attribute'" + << " must be specified in \n"; + return; + } + + if (attributeName) + { + if (value) + _elem->SetAttribute(attributeName, value); + else + { + sdferr << "No 'value' specified in \n"; + return; + } + } + else + { + TiXmlElement *addElem = new TiXmlElement(elementName); + if (value) + { + TiXmlText *addText = new TiXmlText(value); + addElem->LinkEndChild(addText); + } + _elem->LinkEndChild(addElem); + } +} + +///////////////////////////////////////////////// +void Converter::Remove(TiXmlElement *_elem, TiXmlElement *_removeElem) +{ + SDF_ASSERT(_elem != NULL, "SDF element is NULL"); + SDF_ASSERT(_removeElem != NULL, "Move element is NULL"); + + const char *fromElemStr = _removeElem->Attribute("element"); + + // tokenize 'from' and 'to' strs + std::string fromStr = ""; + if (fromElemStr) + fromStr = fromElemStr; + + std::vector fromTokens; + boost::algorithm::split_regex(fromTokens, fromStr, boost::regex("::")); + + if (fromTokens.empty()) + { + sdferr << "Incorrect 'from' string format\n"; + return; + } + + // get value of the 'from' element/attribute + TiXmlElement *fromElem = _elem; + for (unsigned int i = 0; i < fromTokens.size()-1; ++i) + { + fromElem = fromElem->FirstChildElement(fromTokens[i]); + if (!fromElem) + { + // Return when the tokens don't match. Don't output an error message + // because it spams the console. + return; + } + } + + const char *fromName = fromTokens[fromTokens.size()-1].c_str(); + + TiXmlElement *moveFrom = fromElem->FirstChildElement(fromName); + + fromElem->RemoveChild(moveFrom); +} + +///////////////////////////////////////////////// +void Converter::Move(TiXmlElement *_elem, TiXmlElement *_moveElem, + const bool _copy) +{ + SDF_ASSERT(_elem != NULL, "SDF element is NULL"); + SDF_ASSERT(_moveElem != NULL, "Move element is NULL"); + + TiXmlElement *fromConvertElem = _moveElem->FirstChildElement("from"); + TiXmlElement *toConvertElem = _moveElem->FirstChildElement("to"); + + const char *fromElemStr = fromConvertElem->Attribute("element"); + const char *fromAttrStr = fromConvertElem->Attribute("attribute"); + + const char *toElemStr = toConvertElem->Attribute("element"); + const char *toAttrStr = toConvertElem->Attribute("attribute"); + + // tokenize 'from' and 'to' strs + std::string fromStr = ""; + if (fromElemStr) + fromStr = fromElemStr; + else if (fromAttrStr) + fromStr = fromAttrStr; + std::string toStr = ""; + if (toElemStr) + toStr = toElemStr; + else if (toAttrStr) + toStr = toAttrStr; + std::vector fromTokens; + std::vector toTokens; + boost::algorithm::split_regex(fromTokens, fromStr, boost::regex("::")); + boost::algorithm::split_regex(toTokens, toStr, boost::regex("::")); + + if (fromTokens.empty()) + { + sdferr << "Incorrect 'from' string format\n"; + return; + } + if (toTokens.empty()) + { + sdferr << "Incorrect 'to' string format\n"; + return; + } + + // get value of the 'from' element/attribute + TiXmlElement *fromElem = _elem; + for (unsigned int i = 0; i < fromTokens.size()-1; ++i) + { + fromElem = fromElem->FirstChildElement(fromTokens[i]); + if (!fromElem) + { + // Return when the tokens don't match. Don't output an error message + // because it spams the console. + return; + } + } + + const char *fromName = fromTokens[fromTokens.size()-1].c_str(); + const char *value = NULL; + + unsigned int newDirIndex = 0; + // get the new element/attribute name + const char *toName = toTokens[toTokens.size()-1].c_str(); + TiXmlElement *toElem = _elem; + TiXmlElement *childElem = NULL; + for (unsigned int i = 0; i < toTokens.size()-1; ++i) + { + childElem = toElem->FirstChildElement(toTokens[i]); + if (!childElem) + { + newDirIndex = i; + break; + } + toElem = childElem; + } + + // found elements in 'to' string that is not present, so create new + // elements + if (!childElem) + { + int offset = toElemStr != NULL && toAttrStr != NULL ? 0 : 1; + while (newDirIndex < (toTokens.size()-offset)) + { + TiXmlElement *newElem = new TiXmlElement(toTokens[newDirIndex]); + toElem->LinkEndChild(newElem); + toElem = newElem; + newDirIndex++; + } + } + + // Get value, or return if no element/attribute found as they don't have to + // be specified in the sdf. + if (fromElemStr) + { + TiXmlElement *moveFrom = + fromElem->FirstChildElement(fromName); + + // No matching element, so return. + if (!moveFrom) + return; + + if (toElemStr && !toAttrStr) + { + TiXmlElement *moveTo = static_cast(moveFrom->Clone()); + moveTo->SetValue(toName); + toElem->LinkEndChild(moveTo); + } + else + { + value = GetValue(fromName, NULL, fromElem); + if (!value) + return; + std::string valueStr = value; + + toElem->SetAttribute(toAttrStr, valueStr); + } + + if (!_copy) + fromElem->RemoveChild(moveFrom); + } + else if (fromAttrStr) + { + value = GetValue(NULL, fromName, fromElem); + + if (!value) + return; + + std::string valueStr = value; + + if (toElemStr) + { + TiXmlElement *moveTo = new TiXmlElement(toName); + TiXmlText *text = new TiXmlText(valueStr); + moveTo->LinkEndChild(text); + toElem->LinkEndChild(moveTo); + } + else if (toAttrStr) + { + toElem->SetAttribute(toName, valueStr); + } + + if (!_copy && fromAttrStr) + fromElem->RemoveAttribute(fromName); + } +} + +///////////////////////////////////////////////// +const char *Converter::GetValue(const char *_valueElem, const char *_valueAttr, + TiXmlElement *_elem) +{ + if (_valueElem) + { + // Check to see if the element that is being converted has the value + if (!_elem->FirstChildElement(_valueElem)) + return NULL; + + if (_valueAttr) + return _elem->FirstChildElement(_valueElem)->Attribute(_valueAttr); + else + return _elem->FirstChildElement(_valueElem)->GetText(); + } + else if (_valueAttr) + { + return _elem->Attribute(_valueAttr); + } + + return NULL; +} + +///////////////////////////////////////////////// +void Converter::CheckDeprecation(TiXmlElement *_elem, TiXmlElement *_convert) +{ + // Process deprecated elements + for (TiXmlElement *deprecatedElem = _convert->FirstChildElement("deprecated"); + deprecatedElem; + deprecatedElem = deprecatedElem->NextSiblingElement("deprecated")) + { + std::string value = deprecatedElem->GetText(); + std::vector valueSplit; + boost::split(valueSplit, value, boost::is_any_of("/")); + + bool found = false; + TiXmlElement *e = _elem; + std::ostringstream stream; + + std::string prefix = ""; + for (unsigned int i = 0; i < valueSplit.size() && !found; ++i) + { + if (e->FirstChildElement(valueSplit[i])) + { + if (stream.str().size() != 0) + { + stream << ">\n"; + prefix += " "; + } + + stream << prefix << "<" << valueSplit[i]; + e = e->FirstChildElement(valueSplit[i]); + } + else if (e->Attribute(valueSplit[i])) + { + stream << " " << valueSplit[i] << "='" + << e->Attribute(valueSplit[i].c_str()) << "'"; + found = true; + } + } + + sdfwarn << "Deprecated SDF Values in original file:\n" + << stream.str() << "\n\n"; + } +} diff --git a/sdformat/src/Converter_TEST.cc b/sdformat/src/Converter_TEST.cc new file mode 100644 index 0000000..7c34c50 --- /dev/null +++ b/sdformat/src/Converter_TEST.cc @@ -0,0 +1,420 @@ +/* + * Copyright 2012 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include "sdf/Converter.hh" + +//////////////////////////////////////////////////// +/// Set up an xml string for testing +std::string getXmlString() +{ + std::stringstream stream; + stream << "" + << " " + << " " + << " D" + << " " + << " " + << ""; + return stream.str(); +} + +//////////////////////////////////////////////////// +/// Ensure that Converter::Move function is working +/// Test moving from elem to elem +TEST(Converter, MoveElemElem) +{ + // Set up an xml string for testing + std::string xmlString = getXmlString(); + + // Verify the xml + TiXmlDocument xmlDoc; + xmlDoc.Parse(xmlString.c_str()); + TiXmlElement *childElem = xmlDoc.FirstChildElement(); + EXPECT_TRUE(childElem != NULL); + EXPECT_EQ(childElem->ValueStr(), "elemA"); + childElem = childElem->FirstChildElement(); + EXPECT_TRUE(childElem != NULL); + EXPECT_EQ(childElem->ValueStr(), "elemB"); + childElem = childElem->FirstChildElement(); + EXPECT_TRUE(childElem != NULL); + EXPECT_EQ(childElem->ValueStr(), "elemC"); + childElem = childElem->FirstChildElement(); + EXPECT_TRUE(childElem != NULL); + EXPECT_EQ(childElem->ValueStr(), "elemD"); + + // Test moving from elem to elem + // Set up a convert file + std::stringstream convertStream; + convertStream << "" + << " " + << " " + << " " + << " " + << " " + << " " + << ""; + TiXmlDocument convertXmlDoc; + convertXmlDoc.Parse(convertStream.str().c_str()); + sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); + + TiXmlElement *convertedElem = xmlDoc.FirstChildElement(); + EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + convertedElem = convertedElem->FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_TRUE(convertedElem->FirstChildElement("elemC") != NULL); + EXPECT_TRUE(convertedElem->FirstChildElement("elemE") != NULL); + std::string elemValue = convertedElem->FirstChildElement("elemE")->GetText(); + EXPECT_EQ(elemValue, "D"); + convertedElem = convertedElem->FirstChildElement("elemC"); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_FALSE(convertedElem->FirstChildElement("elemD")); +} + +//////////////////////////////////////////////////// +/// Ensure that Converter::Move function is working +/// Test moving from elem to attr +TEST(Converter, MoveElemAttr) +{ + // Set up an xml string for testing + std::string xmlString = getXmlString(); + + // Test moving from elem to attr + TiXmlDocument xmlDoc2; + xmlDoc2.Parse(xmlString.c_str()); + std::stringstream convertStream; + convertStream << "" + << " " + << " " + << " " + << " " + << " " + << " " + << ""; + TiXmlDocument convertXmlDoc2; + convertXmlDoc2.Parse(convertStream.str().c_str()); + sdf::Converter::Convert(&xmlDoc2, &convertXmlDoc2); + + TiXmlElement *convertedElem = xmlDoc2.FirstChildElement(); + EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + convertedElem = convertedElem->FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_TRUE(convertedElem->Attribute("attrE") != NULL); + std::string attrValue = convertedElem->Attribute("attrE"); + EXPECT_EQ(attrValue, "D"); + convertedElem = convertedElem->FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_FALSE(convertedElem->FirstChildElement("elemD")); +} + +//////////////////////////////////////////////////// +/// Ensure that Converter::Move function is working +/// Test moving from attr to attr +TEST(Converter, MoveAttrAttr) +{ + // Set up an xml string for testing + std::string xmlString = getXmlString(); + + // Test moving from attr to attr + TiXmlDocument xmlDoc3; + xmlDoc3.Parse(xmlString.c_str()); + std::stringstream convertStream; + convertStream << "" + << " " + << " " + << " " + << " " + << " " + << " " + << ""; + TiXmlDocument convertXmlDoc3; + convertXmlDoc3.Parse(convertStream.str().c_str()); + sdf::Converter::Convert(&xmlDoc3, &convertXmlDoc3); + + TiXmlElement *convertedElem = xmlDoc3.FirstChildElement(); + EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + convertedElem = convertedElem->FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_TRUE(convertedElem->Attribute("attrE") != NULL); + std::string attrValue = convertedElem->Attribute("attrE"); + EXPECT_EQ(attrValue, "C"); + convertedElem = convertedElem->FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_FALSE(convertedElem->Attribute("attrC")); + convertedElem = convertedElem->FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemD"); +} + +//////////////////////////////////////////////////// +/// Ensure that Converter::Move function is working +/// Test moving from attr to elem +TEST(Converter, MoveAttrElem) +{ + // Set up an xml string for testing + std::string xmlString = getXmlString(); + + // Test moving from attr to elem + TiXmlDocument xmlDoc4; + xmlDoc4.Parse(xmlString.c_str()); + std::stringstream convertStream; + convertStream << "" + << " " + << " " + << " " + << " " + << " " + << " " + << ""; + TiXmlDocument convertXmlDoc4; + convertXmlDoc4.Parse(convertStream.str().c_str()); + sdf::Converter::Convert(&xmlDoc4, &convertXmlDoc4); + + TiXmlElement *convertedElem = xmlDoc4.FirstChildElement(); + EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + convertedElem = convertedElem->FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_TRUE(convertedElem->FirstChildElement("elemE") != NULL); + std::string elemValue = convertedElem->FirstChildElement("elemE")->GetText(); + EXPECT_EQ(elemValue, "C"); + EXPECT_TRUE(convertedElem->FirstChildElement("elemC") != NULL); + convertedElem = convertedElem->FirstChildElement("elemC"); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_FALSE(convertedElem->Attribute("attrC")); + convertedElem = convertedElem->FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemD"); +} + +//////////////////////////////////////////////////// +/// Ensure that Converter::Move function is working +/// Test moving from elem to elem across multiple levels +TEST(Converter, MoveElemElemMultipleLevels) +{ + // Set up an xml string for testing + std::string xmlString = getXmlString(); + + // Test moving from elem to elem across multiple levels + TiXmlDocument xmlDoc5; + xmlDoc5.Parse(xmlString.c_str()); + std::stringstream convertStream; + convertStream << "" + << " " + << " " + << " " + << " " + << ""; + TiXmlDocument convertXmlDoc5; + convertXmlDoc5.Parse(convertStream.str().c_str()); + sdf::Converter::Convert(&xmlDoc5, &convertXmlDoc5); + + TiXmlElement *convertedElem = xmlDoc5.FirstChildElement(); + EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + EXPECT_TRUE(convertedElem->FirstChildElement("elemE") != NULL); + std::string elemValue = convertedElem->FirstChildElement("elemE")->GetText(); + EXPECT_EQ(elemValue, "D"); + convertedElem = convertedElem->FirstChildElement("elemB"); + ASSERT_TRUE(convertedElem != NULL); + convertedElem = convertedElem->FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_FALSE(convertedElem->FirstChildElement("elemD")); +} + +//////////////////////////////////////////////////// +/// Ensure that Converter::Move function is working +/// Test moving from attr to attr across multiple levels +TEST(Converter, MoveAttrAttrMultipleLevels) +{ + // Set up an xml string for testing + std::string xmlString = getXmlString(); + + // Test moving from attr to attr across multiple levels + TiXmlDocument xmlDoc6; + xmlDoc6.Parse(xmlString.c_str()); + std::stringstream convertStream; + convertStream << "" + << " " + << " " + << " " + << " " + << ""; + TiXmlDocument convertXmlDoc6; + convertXmlDoc6.Parse(convertStream.str().c_str()); + sdf::Converter::Convert(&xmlDoc6, &convertXmlDoc6); + + TiXmlElement *convertedElem = xmlDoc6.FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + std::string attrValue = convertedElem->Attribute("attrE"); + EXPECT_EQ(attrValue, "C"); + convertedElem = convertedElem->FirstChildElement("elemB"); + ASSERT_TRUE(convertedElem != NULL); + convertedElem = convertedElem->FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_FALSE(convertedElem->Attribute("attrC")); + convertedElem = convertedElem->FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemD"); +} + +//////////////////////////////////////////////////// +/// Ensure that Converter::Move function is working +/// Test moving from elem to attr across multiple levels +TEST(Converter, MoveElemAttrMultipleLevels) +{ + // Set up an xml string for testing + std::string xmlString = getXmlString(); + + // Test moving from elem to attr across multiple levels + TiXmlDocument xmlDoc7; + xmlDoc7.Parse(xmlString.c_str()); + std::stringstream convertStream; + convertStream << "" + << " " + << " " + << " " + << " " + << ""; + TiXmlDocument convertXmlDoc7; + convertXmlDoc7.Parse(convertStream.str().c_str()); + sdf::Converter::Convert(&xmlDoc7, &convertXmlDoc7); + + TiXmlElement *convertedElem = xmlDoc7.FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + std::string attrValue = convertedElem->Attribute("attrE"); + EXPECT_EQ(attrValue, "D"); + convertedElem = convertedElem->FirstChildElement("elemB"); + ASSERT_TRUE(convertedElem != NULL); + convertedElem = convertedElem->FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_FALSE(convertedElem->FirstChildElement("elemD")); +} + +//////////////////////////////////////////////////// +/// Ensure that Converter::Move function is working +/// Test moving from attr to elem across multiple levels +TEST(Converter, MoveAttrElemMultipleLevels) +{ + // Set up an xml string for testing + std::string xmlString = getXmlString(); + + // Test moving from attr to elem across multiple levels + TiXmlDocument xmlDoc8; + xmlDoc8.Parse(xmlString.c_str()); + std::stringstream convertStream; + convertStream << "" + << " " + << " " + << " " + << " " + << ""; + TiXmlDocument convertXmlDoc8; + convertXmlDoc8.Parse(convertStream.str().c_str()); + sdf::Converter::Convert(&xmlDoc8, &convertXmlDoc8); + + TiXmlElement *convertedElem = xmlDoc8.FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + EXPECT_TRUE(convertedElem->FirstChildElement("elemE") != NULL); + std::string elemValue = convertedElem->FirstChildElement("elemE")->GetText(); + EXPECT_EQ(elemValue, "C"); + convertedElem = convertedElem->FirstChildElement("elemB"); + ASSERT_TRUE(convertedElem != NULL); + convertedElem = convertedElem->FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemC"); + EXPECT_FALSE(convertedElem->Attribute("attrC")); + convertedElem = convertedElem->FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemD"); +} + +//////////////////////////////////////////////////// +/// Ensure that Converter::Add function is working +/// Test adding element and attribute +TEST(Converter, Add) +{ + // Set up an xml string for testing + std::string xmlString = getXmlString(); + + // Verify the xml + TiXmlDocument xmlDoc; + xmlDoc.Parse(xmlString.c_str()); + TiXmlElement *childElem = xmlDoc.FirstChildElement(); + EXPECT_TRUE(childElem != NULL); + EXPECT_EQ(childElem->ValueStr(), "elemA"); + childElem = childElem->FirstChildElement(); + EXPECT_TRUE(childElem != NULL); + EXPECT_EQ(childElem->ValueStr(), "elemB"); + childElem = childElem->FirstChildElement(); + EXPECT_TRUE(childElem != NULL); + EXPECT_EQ(childElem->ValueStr(), "elemC"); + childElem = childElem->FirstChildElement(); + EXPECT_TRUE(childElem != NULL); + EXPECT_EQ(childElem->ValueStr(), "elemD"); + + // Test adding element + // Set up a convert file + std::stringstream convertStream; + convertStream << "" + << " " + << " " + << " " + << " " + << " " + << " " + << " " + << " " + << ""; + TiXmlDocument convertXmlDoc; + convertXmlDoc.Parse(convertStream.str().c_str()); + sdf::Converter::Convert(&xmlDoc, &convertXmlDoc); + + TiXmlElement *convertedElem = xmlDoc.FirstChildElement(); + EXPECT_EQ(convertedElem->ValueStr(), "elemA"); + convertedElem = convertedElem->FirstChildElement(); + ASSERT_TRUE(convertedElem != NULL); + EXPECT_EQ(convertedElem->ValueStr(), "elemB"); + EXPECT_TRUE(convertedElem->FirstChildElement("elemC") != NULL); + EXPECT_TRUE(convertedElem->FirstChildElement("elemBB") != NULL); + std::string elemValue = convertedElem->FirstChildElement("elemBB")->GetText(); + EXPECT_EQ(elemValue, "BB"); + convertedElem = convertedElem->FirstChildElement("elemC"); + ASSERT_TRUE(convertedElem != NULL); + convertedElem = convertedElem->FirstChildElement("elemD"); + ASSERT_TRUE(convertedElem != NULL); + std::string attrValue = convertedElem->Attribute("attrDD"); + EXPECT_EQ(attrValue, "DD"); +} + +///////////////////////////////////////////////// +/// Main +int main(int argc, char **argv) +{ + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/sdformat/src/Element.cc b/sdformat/src/Element.cc new file mode 100644 index 0000000..48428e7 --- /dev/null +++ b/sdformat/src/Element.cc @@ -0,0 +1,837 @@ +/* + * Copyright 2015 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include "sdf/Assert.hh" +#include "sdf/Element.hh" + +using namespace sdf; + +///////////////////////////////////////////////// +Element::Element() + : dataPtr(new ElementPrivate) +{ + this->dataPtr->copyChildren = false; + this->dataPtr->referenceSDF = ""; +} + +///////////////////////////////////////////////// +Element::~Element() +{ + delete this->dataPtr; + this->dataPtr = NULL; +} + +///////////////////////////////////////////////// +ElementPtr Element::GetParent() const +{ + return this->dataPtr->parent.lock(); +} + +///////////////////////////////////////////////// +void Element::SetParent(const ElementPtr _parent) +{ + this->dataPtr->parent = _parent; +} + +///////////////////////////////////////////////// +void Element::SetName(const std::string &_name) +{ + this->dataPtr->name = _name; +} + +///////////////////////////////////////////////// +const std::string &Element::GetName() const +{ + return this->dataPtr->name; +} + +///////////////////////////////////////////////// +void Element::SetRequired(const std::string &_req) +{ + this->dataPtr->required = _req; +} + +///////////////////////////////////////////////// +const std::string &Element::GetRequired() const +{ + return this->dataPtr->required; +} + +///////////////////////////////////////////////// +void Element::SetCopyChildren(bool _value) +{ + this->dataPtr->copyChildren = _value; +} + +///////////////////////////////////////////////// +bool Element::GetCopyChildren() const +{ + return this->dataPtr->copyChildren; +} + +///////////////////////////////////////////////// +void Element::SetReferenceSDF(const std::string &_value) +{ + this->dataPtr->referenceSDF = _value; +} + +///////////////////////////////////////////////// +std::string Element::ReferenceSDF() const +{ + return this->dataPtr->referenceSDF; +} + +///////////////////////////////////////////////// +void Element::AddValue(const std::string &_type, + const std::string &_defaultValue, bool _required, + const std::string &_description) +{ + this->dataPtr->value = this->CreateParam(this->dataPtr->name, + _type, _defaultValue, _required, _description); +} + +///////////////////////////////////////////////// +ParamPtr Element::CreateParam(const std::string &_key, + const std::string &_type, const std::string &_defaultValue, bool _required, + const std::string &_description) +{ + return ParamPtr( + new Param(_key, _type, _defaultValue, _required, _description)); +} + +///////////////////////////////////////////////// +void Element::AddAttribute(const std::string &_key, const std::string &_type, + const std::string &_defaultValue, bool _required, + const std::string &_description) +{ + this->dataPtr->attributes.push_back( + this->CreateParam(_key, _type, _defaultValue, _required, _description)); +} + +///////////////////////////////////////////////// +ElementPtr Element::Clone() const +{ + ElementPtr clone(new Element); + clone->dataPtr->description = this->dataPtr->description; + clone->dataPtr->name = this->dataPtr->name; + clone->dataPtr->required = this->dataPtr->required; + // clone->parent = this->dataPtr->parent; + clone->dataPtr->copyChildren = this->dataPtr->copyChildren; + clone->dataPtr->includeFilename = this->dataPtr->includeFilename; + clone->dataPtr->referenceSDF = this->dataPtr->referenceSDF; + + Param_V::const_iterator aiter; + for (aiter = this->dataPtr->attributes.begin(); + aiter != this->dataPtr->attributes.end(); ++aiter) + { + clone->dataPtr->attributes.push_back((*aiter)->Clone()); + } + + ElementPtr_V::const_iterator eiter; + for (eiter = this->dataPtr->elementDescriptions.begin(); + eiter != this->dataPtr->elementDescriptions.end(); ++eiter) + { + clone->dataPtr->elementDescriptions.push_back((*eiter)->Clone()); + } + + for (eiter = this->dataPtr->elements.begin(); + eiter != this->dataPtr->elements.end(); ++eiter) + { + clone->dataPtr->elements.push_back((*eiter)->Clone()); + clone->dataPtr->elements.back()->dataPtr->parent = clone; + } + + if (this->dataPtr->value) + clone->dataPtr->value = this->dataPtr->value->Clone(); + + return clone; +} + +///////////////////////////////////////////////// +void Element::Copy(const ElementPtr _elem) +{ + this->dataPtr->name = _elem->GetName(); + this->dataPtr->description = _elem->GetDescription(); + this->dataPtr->required = _elem->GetRequired(); + this->dataPtr->copyChildren = _elem->GetCopyChildren(); + this->dataPtr->includeFilename = _elem->dataPtr->includeFilename; + this->dataPtr->referenceSDF = _elem->ReferenceSDF(); + + for (Param_V::iterator iter = _elem->dataPtr->attributes.begin(); + iter != _elem->dataPtr->attributes.end(); ++iter) + { + if (!this->HasAttribute((*iter)->GetKey())) + this->dataPtr->attributes.push_back((*iter)->Clone()); + ParamPtr param = this->GetAttribute((*iter)->GetKey()); + (*param) = (**iter); + } + + if (_elem->GetValue()) + { + if (!this->dataPtr->value) + this->dataPtr->value = _elem->GetValue()->Clone(); + else + *(this->dataPtr->value) = *(_elem->GetValue()); + } + + this->dataPtr->elementDescriptions.clear(); + for (ElementPtr_V::const_iterator iter = + _elem->dataPtr->elementDescriptions.begin(); + iter != _elem->dataPtr->elementDescriptions.end(); ++iter) + { + this->dataPtr->elementDescriptions.push_back((*iter)->Clone()); + } + + this->dataPtr->elements.clear(); + for (ElementPtr_V::iterator iter = _elem->dataPtr->elements.begin(); + iter != _elem->dataPtr->elements.end(); ++iter) + { + ElementPtr elem = (*iter)->Clone(); + elem->Copy(*iter); + elem->dataPtr->parent = shared_from_this(); + this->dataPtr->elements.push_back(elem); + } +} + +///////////////////////////////////////////////// +void Element::PrintDescription(const std::string &_prefix) +{ + std::cout << _prefix << "\n"; + + std::cout << _prefix << " " << this->dataPtr->description + << "\n"; + + Param_V::iterator aiter; + for (aiter = this->dataPtr->attributes.begin(); + aiter != this->dataPtr->attributes.end(); ++aiter) + { + std::cout << _prefix << " \n"; + std::cout << _prefix << " " << (*aiter)->GetDescription() + << "\n"; + std::cout << _prefix << " \n"; + } + + if (this->GetCopyChildren()) + std::cout << _prefix << " \n"; + + + std::string refSDF = this->ReferenceSDF(); + if (!refSDF.empty()) + { + std::cout << _prefix << " \n"; + } + + ElementPtr_V::iterator eiter; + for (eiter = this->dataPtr->elementDescriptions.begin(); + eiter != this->dataPtr->elementDescriptions.end(); ++eiter) + { + (*eiter)->PrintDescription(_prefix + " "); + } + + std::cout << _prefix << "\n"; +} + +///////////////////////////////////////////////// +void Element::PrintDocRightPane(std::string &_html, int _spacing, int &_index) +{ + std::ostringstream stream; + ElementPtr_V::iterator eiter; + + int start = _index++; + + std::string childHTML; + for (eiter = this->dataPtr->elementDescriptions.begin(); + eiter != this->dataPtr->elementDescriptions.end(); ++eiter) + { + (*eiter)->PrintDocRightPane(childHTML, _spacing + 4, _index); + } + + stream << "dataPtr->name << start + << "\"><" << this->dataPtr->name << ">"; + + stream << "
    \n"; + + stream << "
    \n"; + + stream << "Description: "; + if (!this->dataPtr->description.empty()) + stream << this->dataPtr->description << "
    \n"; + else + stream << "none
    \n"; + + stream << "Required: " + << this->dataPtr->required << "   \n"; + + stream << "Type: "; + if (this->dataPtr->value) + { + stream << this->dataPtr->value->GetTypeName() + << "   \n" + << "Default: " + << this->dataPtr->value->GetDefaultAsString() << '\n'; + } + else + stream << "n/a\n"; + + stream << "
    "; + + if (this->dataPtr->attributes.size() > 0) + { + stream << "
    \n"; + stream << "Attributes
    "; + + Param_V::iterator aiter; + for (aiter = this->dataPtr->attributes.begin(); + aiter != this->dataPtr->attributes.end(); ++aiter) + { + stream << "
    \n"; + + stream << "
    \n"; + stream << "" << (*aiter)->GetKey() + << ": "; + stream << "
    \n"; + + stream << "
    \n"; + + if (!(*aiter)->GetDescription().empty()) + stream << (*aiter)->GetDescription() << "
    \n"; + else + stream << "no description
    \n"; + + stream << "Type: " + << (*aiter)->GetTypeName() << "   " + << "Default: " + << (*aiter)->GetDefaultAsString() << "
    "; + stream << "
    \n"; + + stream << "
    \n"; + } + stream << "
    \n"; + stream << "
    \n"; + } + + _html += stream.str(); + _html += childHTML; + _html += "
    \n"; +} + +///////////////////////////////////////////////// +void Element::PrintDocLeftPane(std::string &_html, int _spacing, int &_index) +{ + std::ostringstream stream; + ElementPtr_V::iterator eiter; + + int start = _index++; + + std::string childHTML; + for (eiter = this->dataPtr->elementDescriptions.begin(); + eiter != this->dataPtr->elementDescriptions.end(); ++eiter) + { + (*eiter)->PrintDocLeftPane(childHTML, _spacing + 4, _index); + } + + stream << "dataPtr->name << start + << "\"><" << this->dataPtr->name << ">"; + + stream << "
    \n"; + + _html += stream.str(); + _html += childHTML; + _html += "
    \n"; +} + +///////////////////////////////////////////////// +void Element::PrintValues(std::string _prefix) +{ + std::cout << _prefix << "<" << this->dataPtr->name; + + Param_V::iterator aiter; + for (aiter = this->dataPtr->attributes.begin(); + aiter != this->dataPtr->attributes.end(); ++aiter) + { + std::cout << " " << (*aiter)->GetKey() << "='" + << (*aiter)->GetAsString() << "'"; + } + + if (this->dataPtr->elements.size() > 0) + { + std::cout << ">\n"; + ElementPtr_V::iterator eiter; + for (eiter = this->dataPtr->elements.begin(); + eiter != this->dataPtr->elements.end(); ++eiter) + { + (*eiter)->PrintValues(_prefix + " "); + } + std::cout << _prefix << "dataPtr->name << ">\n"; + } + else + { + if (this->dataPtr->value) + { + std::cout << ">" << this->dataPtr->value->GetAsString() + << "dataPtr->name << ">\n"; + } + else + { + std::cout << "/>\n"; + } + } +} + +///////////////////////////////////////////////// +std::string Element::ToString(const std::string &_prefix) const +{ + std::ostringstream out; + this->ToString(_prefix, out); + return out.str(); +} + +///////////////////////////////////////////////// +void Element::ToString(const std::string &_prefix, + std::ostringstream &_out) const +{ + if (this->dataPtr->includeFilename.empty()) + { + _out << _prefix << "<" << this->dataPtr->name; + + Param_V::const_iterator aiter; + for (aiter = this->dataPtr->attributes.begin(); + aiter != this->dataPtr->attributes.end(); ++aiter) + { + _out << " " << (*aiter)->GetKey() << "='" + << (*aiter)->GetAsString() << "'"; + } + + if (this->dataPtr->elements.size() > 0) + { + _out << ">\n"; + ElementPtr_V::const_iterator eiter; + for (eiter = this->dataPtr->elements.begin(); + eiter != this->dataPtr->elements.end(); ++eiter) + { + (*eiter)->ToString(_prefix + " ", _out); + } + _out << _prefix << "dataPtr->name << ">\n"; + } + else + { + if (this->dataPtr->value) + { + _out << ">" << this->dataPtr->value->GetAsString() + << "dataPtr->name << ">\n"; + } + else + { + _out << "/>\n"; + } + } + } + else + { + _out << _prefix << "\n"; + } +} + +///////////////////////////////////////////////// +bool Element::HasAttribute(const std::string &_key) +{ + return this->GetAttribute(_key) != NULL; +} + +///////////////////////////////////////////////// +bool Element::GetAttributeSet(const std::string &_key) +{ + bool result = false; + ParamPtr p = this->GetAttribute(_key); + if (p) + result = p->GetSet(); + + return result; +} + +///////////////////////////////////////////////// +ParamPtr Element::GetAttribute(const std::string &_key) +{ + Param_V::const_iterator iter; + for (iter = this->dataPtr->attributes.begin(); + iter != this->dataPtr->attributes.end(); ++iter) + { + if ((*iter)->GetKey() == _key) + return (*iter); + } + return ParamPtr(); +} + +///////////////////////////////////////////////// +size_t Element::GetAttributeCount() const +{ + return this->dataPtr->attributes.size(); +} + +///////////////////////////////////////////////// +ParamPtr Element::GetAttribute(unsigned int _index) const +{ + ParamPtr result; + if (_index < this->dataPtr->attributes.size()) + result = this->dataPtr->attributes[_index]; + + return result; +} + +///////////////////////////////////////////////// +size_t Element::GetElementDescriptionCount() const +{ + return this->dataPtr->elementDescriptions.size(); +} + +///////////////////////////////////////////////// +ElementPtr Element::GetElementDescription(unsigned int _index) const +{ + ElementPtr result; + if (_index < this->dataPtr->elementDescriptions.size()) + result = this->dataPtr->elementDescriptions[_index]; + return result; +} + +///////////////////////////////////////////////// +ElementPtr Element::GetElementDescription(const std::string &_key) const +{ + ElementPtr_V::const_iterator iter; + for (iter = this->dataPtr->elementDescriptions.begin(); + iter != this->dataPtr->elementDescriptions.end(); ++iter) + { + if ((*iter)->GetName() == _key) + return (*iter); + } + + return ElementPtr(); +} + +///////////////////////////////////////////////// +ParamPtr Element::GetValue() +{ + return this->dataPtr->value; +} + +///////////////////////////////////////////////// +bool Element::HasElement(const std::string &_name) const +{ + ElementPtr_V::const_iterator iter; + for (iter = this->dataPtr->elements.begin(); + iter != this->dataPtr->elements.end(); ++iter) + { + if ((*iter)->GetName() == _name) + return true; + } + + return false; +} + +///////////////////////////////////////////////// +ElementPtr Element::GetElementImpl(const std::string &_name) const +{ + ElementPtr_V::const_iterator iter; + for (iter = this->dataPtr->elements.begin(); + iter != this->dataPtr->elements.end(); ++iter) + { + if ((*iter)->GetName() == _name) + return (*iter); + } + + // gzdbg << "Unable to find element [" << _name << "] return empty\n"; + return ElementPtr(); +} + +///////////////////////////////////////////////// +ElementPtr Element::GetFirstElement() const +{ + if (this->dataPtr->elements.empty()) + return ElementPtr(); + else + return this->dataPtr->elements.front(); +} + +///////////////////////////////////////////////// +ElementPtr Element::GetNextElement(const std::string &_name) const +{ + auto parent = this->dataPtr->parent.lock(); + if (parent) + { + ElementPtr_V::const_iterator iter; + iter = std::find(parent->dataPtr->elements.begin(), + parent->dataPtr->elements.end(), shared_from_this()); + + if (iter == parent->dataPtr->elements.end()) + { + return ElementPtr(); + } + + ++iter; + if (iter == parent->dataPtr->elements.end()) + return ElementPtr(); + else if (_name.empty()) + return *(iter); + else + { + for (; iter != parent->dataPtr->elements.end(); ++iter) + { + if ((*iter)->GetName() == _name) + return (*iter); + } + } + } + + return ElementPtr(); +} + +///////////////////////////////////////////////// +ElementPtr Element::GetElement(const std::string &_name) +{ + if (this->HasElement(_name)) + return this->GetElementImpl(_name); + else + return this->AddElement(_name); +} + +///////////////////////////////////////////////// +void Element::InsertElement(ElementPtr _elem) +{ + this->dataPtr->elements.push_back(_elem); +} + +///////////////////////////////////////////////// +bool Element::HasElementDescription(const std::string &_name) +{ + bool result = false; + ElementPtr_V::const_iterator iter; + for (iter = this->dataPtr->elementDescriptions.begin(); + iter != this->dataPtr->elementDescriptions.end(); ++iter) + { + if ((*iter)->dataPtr->name == _name) + { + result = true; + break; + } + } + + return result; +} + +///////////////////////////////////////////////// +ElementPtr Element::AddElement(const std::string &_name) +{ + // if this element is a reference sdf and does not have any element + // descriptions then get them from its parent + auto parent = this->dataPtr->parent.lock(); + if (!this->dataPtr->referenceSDF.empty() && + this->dataPtr->elementDescriptions.empty() && parent && + parent->GetName() == this->dataPtr->name) + { + for (unsigned int i = 0; i < parent->GetElementDescriptionCount(); ++i) + { + this->dataPtr->elementDescriptions.push_back( + parent->GetElementDescription(i)->Clone()); + } + } + + ElementPtr_V::const_iterator iter, iter2; + for (iter = this->dataPtr->elementDescriptions.begin(); + iter != this->dataPtr->elementDescriptions.end(); ++iter) + { + if ((*iter)->dataPtr->name == _name) + { + ElementPtr elem = (*iter)->Clone(); + elem->SetParent(shared_from_this()); + this->dataPtr->elements.push_back(elem); + + // Add all child elements. + for (iter2 = elem->dataPtr->elementDescriptions.begin(); + iter2 != elem->dataPtr->elementDescriptions.end(); ++iter2) + { + // Add only required child element + if ((*iter2)->GetRequired() == "1") + { + elem->AddElement((*iter2)->dataPtr->name); + } + } + + return this->dataPtr->elements.back(); + } + } + + sdferr << "Missing element description for [" << _name << "]\n"; + return ElementPtr(); +} + +///////////////////////////////////////////////// +void Element::ClearElements() +{ + for (sdf::ElementPtr_V::iterator iter = this->dataPtr->elements.begin(); + iter != this->dataPtr->elements.end(); ++iter) + { + (*iter)->ClearElements(); + } + + this->dataPtr->elements.clear(); +} + +///////////////////////////////////////////////// +void Element::Update() +{ + for (sdf::Param_V::iterator iter = this->dataPtr->attributes.begin(); + iter != this->dataPtr->attributes.end(); ++iter) + { + (*iter)->Update(); + } + + for (sdf::ElementPtr_V::iterator iter = this->dataPtr->elements.begin(); + iter != this->dataPtr->elements.end(); ++iter) + { + (*iter)->Update(); + } + + if (this->dataPtr->value) + this->dataPtr->value->Update(); +} + +///////////////////////////////////////////////// +void Element::Reset() +{ + for (ElementPtr_V::iterator iter = this->dataPtr->elements.begin(); + iter != this->dataPtr->elements.end(); ++iter) + { + if (*iter) + (*iter)->Reset(); + (*iter).reset(); + } + + for (ElementPtr_V::iterator iter = this->dataPtr->elementDescriptions.begin(); + iter != this->dataPtr->elementDescriptions.end(); ++iter) + { + if (*iter) + (*iter)->Reset(); + (*iter).reset(); + } + this->dataPtr->elements.clear(); + this->dataPtr->elementDescriptions.clear(); + + this->dataPtr->value.reset(); + + this->dataPtr->parent.reset(); +} + +///////////////////////////////////////////////// +void Element::AddElementDescription(ElementPtr _elem) +{ + this->dataPtr->elementDescriptions.push_back(_elem); +} + +///////////////////////////////////////////////// +void Element::SetInclude(const std::string &_filename) +{ + this->dataPtr->includeFilename = _filename; +} + +///////////////////////////////////////////////// +std::string Element::GetInclude() const +{ + return this->dataPtr->includeFilename; +} + +///////////////////////////////////////////////// +std::string Element::GetDescription() const +{ + return this->dataPtr->description; +} + +///////////////////////////////////////////////// +void Element::SetDescription(const std::string &_desc) +{ + this->dataPtr->description = _desc; +} + +///////////////////////////////////////////////// +void Element::RemoveFromParent() +{ + auto parent = this->dataPtr->parent.lock(); + if (parent) + { + ElementPtr_V::iterator iter; + iter = std::find(parent->dataPtr->elements.begin(), + parent->dataPtr->elements.end(), shared_from_this()); + + if (iter != parent->dataPtr->elements.end()) + { + parent->dataPtr->elements.erase(iter); + parent.reset(); + } + } +} + +///////////////////////////////////////////////// +void Element::RemoveChild(ElementPtr _child) +{ + SDF_ASSERT(_child, "Cannot remove a NULL child pointer"); + + ElementPtr_V::iterator iter; + iter = std::find(this->dataPtr->elements.begin(), + this->dataPtr->elements.end(), _child); + + if (iter != this->dataPtr->elements.end()) + { + _child->SetParent(ElementPtr()); + this->dataPtr->elements.erase(iter); + } +} + +///////////////////////////////////////////////// +boost::any Element::GetAny(const std::string &_key) +{ + boost::any result; + if (_key.empty() && this->dataPtr->value) + { + if (!this->dataPtr->value->GetAny(result)) + { + sdferr << "Couldn't get element [" << this->GetName() + << "] as boost::any\n"; + } + } + else if (!_key.empty()) + { + ParamPtr param = this->GetAttribute(_key); + if (param) + { + if (!this->GetAttribute(_key)->GetAny(result)) + sdferr << "Couldn't get attribute [" << _key << "] as boost::any\n"; + } + else if (this->HasElement(_key)) + result = this->GetElementImpl(_key)->GetAny(); + else if (this->HasElementDescription(_key)) + result = this->GetElementDescription(_key)->GetAny(); + else + sdferr << "Unable to find value for key [" << _key << "]\n"; + } + return result; +} diff --git a/sdformat/src/Exception.cc b/sdformat/src/Exception.cc new file mode 100644 index 0000000..f4ed0e3 --- /dev/null +++ b/sdformat/src/Exception.cc @@ -0,0 +1,110 @@ +/* + * Copyright 2012 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include "sdf/ExceptionPrivate.hh" +#include "sdf/Console.hh" +#include "sdf/Exception.hh" + +using namespace sdf; + +////////////////////////////////////////////////// +Exception::Exception() + : dataPtr(new ExceptionPrivate) +{ +} + +////////////////////////////////////////////////// +Exception::Exception(const char *_file, int64_t _line, std::string _msg) + : dataPtr(new ExceptionPrivate) +{ + this->dataPtr->file = _file; + this->dataPtr->line = _line; + this->dataPtr->str = _msg; + this->Print(); +} + +////////////////////////////////////////////////// +Exception::Exception(const Exception &_e) + : dataPtr(new ExceptionPrivate) +{ + this->dataPtr->file = _e.dataPtr->file; + this->dataPtr->line = _e.dataPtr->line; + this->dataPtr->str = _e.dataPtr->str; +} + +////////////////////////////////////////////////// +Exception::~Exception() +{ + delete this->dataPtr; + this->dataPtr = nullptr; +} + +////////////////////////////////////////////////// +void Exception::Print() const +{ + sdf::Console::Instance()->ColorMsg("Exception", + this->dataPtr->file, + static_cast(this->dataPtr->line), 31) << *this; +} + +////////////////////////////////////////////////// +std::string Exception::GetErrorFile() const +{ + return this->dataPtr->file; +} + +////////////////////////////////////////////////// +std::string Exception::GetErrorStr() const +{ + return this->dataPtr->str; +} + +////////////////////////////////////////////////// +InternalError::InternalError() +{ +} + +////////////////////////////////////////////////// +InternalError::InternalError(const char *_file, int64_t _line, + const std::string _msg) : + Exception(_file, _line, _msg) +{ +} + +////////////////////////////////////////////////// +InternalError::~InternalError() +{ +} + +////////////////////////////////////////////////// +AssertionInternalError::AssertionInternalError( + const char * _file, int64_t _line, + const std::string _expr, + const std::string _function, + const std::string _msg) : + InternalError(_file, _line, + "SDF ASSERTION \n" + + _msg + "\n" + + "In function : " + _function + "\n" + + "Assert expression : " + _expr + "\n") +{ +} + +////////////////////////////////////////////////// +AssertionInternalError::~AssertionInternalError() +{ +} diff --git a/sdformat/src/Exception_TEST.cc b/sdformat/src/Exception_TEST.cc new file mode 100644 index 0000000..d5ba58f --- /dev/null +++ b/sdformat/src/Exception_TEST.cc @@ -0,0 +1,38 @@ +/* + * Copyright 2015 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include "sdf/Exception.hh" + +//////////////////////////////////////////////////// +/// Test exception throwing +TEST(Exception, Throwing) +{ + // This test fails on Windows +#ifndef _MSC_VER + EXPECT_ANY_THROW(sdfthrow("throw message")); + EXPECT_THROW(sdfthrow("throw message"), sdf::Exception); +#endif +} + +///////////////////////////////////////////////// +/// Main +int main(int argc, char **argv) +{ + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/sdformat/src/Param.cc b/sdformat/src/Param.cc new file mode 100644 index 0000000..1a21d76 --- /dev/null +++ b/sdformat/src/Param.cc @@ -0,0 +1,525 @@ +/* + * Copyright 2012 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include +#include "sdf/Param.hh" + +using namespace sdf; + +class string_set : public boost::static_visitor<> +{ + public: explicit string_set(const std::string &_value) + : value(_value) + {} + + public: template + void operator()(T & _operand) const + { + _operand = boost::lexical_cast(this->value); + } + public: std::string value; +}; + +class any_set : public boost::static_visitor<> +{ + public: explicit any_set(const boost::any &_value) + {this->value = _value;} + + public: template + void operator()(T & _operand) const + { + _operand = boost::any_cast(this->value); + } + public: boost::any value; +}; + +////////////////////////////////////////////////// +Param::Param(const std::string &_key, const std::string &_typeName, + const std::string &_default, bool _required, + const std::string &_description) + : dataPtr(new ParamPrivate) +{ + this->dataPtr->key = _key; + this->dataPtr->required = _required; + this->dataPtr->typeName = _typeName; + this->dataPtr->description = _description; + this->dataPtr->set = false; + + if (this->dataPtr->typeName == "bool") + this->Init(_default); + else if (this->dataPtr->typeName == "int") + this->Init(_default); + else if (this->dataPtr->typeName == "unsigned int") + this->Init(_default); + else if (this->dataPtr->typeName == "uint64_t") + this->Init(_default); + else if (this->dataPtr->typeName == "double") + this->Init(_default); + else if (this->dataPtr->typeName == "float") + this->Init(_default); + else if (this->dataPtr->typeName == "char") + this->Init(_default); + else if (this->dataPtr->typeName == "std::string" || + this->dataPtr->typeName == "string") + { + this->Init(_default); + } + else if (this->dataPtr->typeName == "sdf::Time" || + this->dataPtr->typeName == "time") + { + this->Init(_default); + } + else if (this->dataPtr->typeName == "sdf::Color" || + this->dataPtr->typeName == "color") + { + this->Init(_default); + } + else if (this->dataPtr->typeName == "ignition::math::Vector2i" || + this->dataPtr->typeName == "vector2i") + { + this->Init(_default); + } + else if (this->dataPtr->typeName == "ignition::math::Vector2d" || + this->dataPtr->typeName == "vector2d") + { + this->Init(_default); + } + else if (this->dataPtr->typeName == "ignition::math::Vector3d" || + this->dataPtr->typeName == "vector3") + { + this->Init(_default); + } + else if (this->dataPtr->typeName == "ignition::math::Pose3d" || + this->dataPtr->typeName == "pose" || + this->dataPtr->typeName == "Pose") + { + this->Init(_default); + } + else if (this->dataPtr->typeName == "ignition::math::Quaterniond" || + this->dataPtr->typeName == "quaternion") + { + this->Init(_default); +#ifndef _WIN32 +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif + } + /// \deprecated The following sdf:: are deprecated + else if (this->dataPtr->typeName == "sdf::Vector2i" || + this->dataPtr->typeName == "vector2i") + { + sdferr << "sdf::Vector2i is deprecated. Use ignition::math::Vector2i\n"; + this->Init(_default); + } + else if (this->dataPtr->typeName == "sdf::Vector2d" || + this->dataPtr->typeName == "vector2d") + { + sdferr << "sdf::Vector2d is deprecated. Use ignition::math::Vector2d\n"; + this->Init(_default); + } + else if (this->dataPtr->typeName == "sdf::Vector3" || + this->dataPtr->typeName == "vector3") + { + sdferr << "sdf::Vector3 is deprecated. Use ignition::math::Vector3d\n"; + this->Init(_default); + } + else if (this->dataPtr->typeName == "sdf::Pose" || + this->dataPtr->typeName == "pose" || + this->dataPtr->typeName == "Pose") + { + sdferr << "sdf::Pose is deprecated. Use ignition::math::Pose3d\n"; + this->Init(_default); + } + else if (this->dataPtr->typeName == "sdf::Quaternion" || + this->dataPtr->typeName == "quaternion") + { + sdferr << "sdf::Quaternion is deprecated. " + << "Use ignition::math::Quaterniond\n"; + this->Init(_default); +#ifndef _WIN32 +#pragma GCC diagnostic pop +#endif + } + else + sdferr << "Unknown parameter type[" << this->dataPtr->typeName << "]\n"; +} + +////////////////////////////////////////////////// +Param::~Param() +{ + delete this->dataPtr; + this->dataPtr = NULL; +} + +////////////////////////////////////////////////// +bool Param::GetAny(boost::any &_anyVal) const +{ + if (this->IsType()) + { + int ret = 0; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + uint64_t ret = 0; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + double ret = 0; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + float ret = 0; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + bool ret = false; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + std::string ret; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + unsigned int ret = 0; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + char ret = 0; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + sdf::Time ret; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + sdf::Color ret; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + ignition::math::Vector3d ret; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + ignition::math::Vector2i ret; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + ignition::math::Vector2d ret; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + ignition::math::Pose3d ret; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + ignition::math::Quaterniond ret; + if (!this->Get(ret)) + return false; + _anyVal = ret; +#ifndef _WIN32 +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif + } + /// \deprecated The follow sdf Types are deprecated + else if (this->IsType()) + { + sdferr << "sdf::Vector3 is deprecated. Use ignition::math::Vector3d\n"; + sdf::Vector3 ret; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + sdferr << "sdf::Vector2i is deprecated. Use ignition::math::Vector2i\n"; + sdf::Vector2i ret; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + sdferr << "sdf::Vector2d is deprecated. Use ignition::math::Vector2d\n"; + sdf::Vector2d ret; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + sdferr << "sdf::Pose is deprecated. Use ignition::math::Pose3d\n"; + sdf::Pose ret; + if (!this->Get(ret)) + return false; + _anyVal = ret; + } + else if (this->IsType()) + { + sdferr << "sdf::Quaternion is deprecated. " + << "Use ignition::math::Quaterniond\n"; + sdf::Quaternion ret; + if (!this->Get(ret)) + return false; + _anyVal = ret; +#ifndef _WIN32 +#pragma GCC diagnostic pop +#endif + } + else + { + sdferr << "Type of parameter not known: [" << this->GetTypeName() << "]\n"; + return false; + } + return true; +} + +////////////////////////////////////////////////// +void Param::Update() +{ + if (this->dataPtr->updateFunc) + { + try + { + boost::apply_visitor(any_set(this->dataPtr->updateFunc()), + this->dataPtr->value); + } + catch(boost::bad_lexical_cast &/*e*/) + { + sdferr << "Unable to set value using Update for key[" + << this->dataPtr->key << "]\n"; + } + } +} + +////////////////////////////////////////////////// +std::string Param::GetAsString() const +{ + return boost::lexical_cast(this->dataPtr->value); +} + +////////////////////////////////////////////////// +std::string Param::GetDefaultAsString() const +{ + return boost::lexical_cast(this->dataPtr->defaultValue); +} + +////////////////////////////////////////////////// +bool Param::SetFromString(const std::string &_value) +{ + // Under some circumstances, latin locales (es_ES or pt_BR) will return a + // comma for decimal position instead of a dot, making the conversion + // to fail. See bug #60 for more information. Force to use always C + setlocale(LC_NUMERIC, "C"); + + std::string str = _value; + boost::trim(str); + + if (str.empty() && this->dataPtr->required) + { + sdferr << "Empty string used when setting a required parameter. Key[" + << this->GetKey() << "]\n"; + return false; + } + else if (str.empty()) + { + this->dataPtr->value = this->dataPtr->defaultValue; + return true; + } + + std::string tmp(str); + std::string lowerTmp(str); + std::transform(lowerTmp.begin(), lowerTmp.end(), lowerTmp.begin(), ::tolower); + + // "true" and "false" doesn't work properly + if (lowerTmp == "true") + tmp = "1"; + else if (lowerTmp == "false") + tmp = "0"; + + bool isHex = tmp.compare(0, 2, "0x") == 0; + + try + { + // Try to use stoi and stoul for integers, and + // stof and stod for floating point values. + // Use boost lexical cast as a last resort. + int numericBase = 10; + if (isHex) + numericBase = 16; + + if (this->dataPtr->typeName == "int") + this->dataPtr->value = std::stoi(tmp, NULL, numericBase); + else if (this->dataPtr->typeName == "unsigned int") + { + this->dataPtr->value = static_cast( + std::stoul(tmp, NULL, numericBase)); + } + else if (this->dataPtr->typeName == "double") + this->dataPtr->value = std::stod(tmp); + else if (this->dataPtr->typeName == "float") + this->dataPtr->value = std::stof(tmp); + else + boost::apply_visitor(string_set(tmp), this->dataPtr->value); + } + + // Catch invalid argument exception from std::stoi/stoul/stod/stof + catch(std::invalid_argument &) + { + sdferr << "Invalid argument. Unable to set value [" + << str << " ] for key[" + << this->dataPtr->key << "].\n"; + return false; + } + // Catch out of range exception from std::stoi/stoul/stod/stof + catch(std::out_of_range &) + { + sdferr << "Out of range. Unable to set value [" + << str << " ] for key[" + << this->dataPtr->key << "].\n"; + return false; + } + // Catch boost lexical cast exceptions + catch(boost::bad_lexical_cast &) + { + if (str == "inf" || str == "-inf") + { + // in this case, the parser complains, but seems to assign the + // right values + sdfmsg << "INFO [sdf::Param]: boost throws when lexical casting " + << "inf's, but the values are usually passed through correctly\n"; + } + else + { + sdferr << "Unable to set value [" << str + << "] for key[" << this->dataPtr->key << "]\n"; + return false; + } + } + + this->dataPtr->set = true; + return this->dataPtr->set; +} + +////////////////////////////////////////////////// +void Param::Reset() +{ + this->dataPtr->value = this->dataPtr->defaultValue; + this->dataPtr->set = false; +} + +////////////////////////////////////////////////// +ParamPtr Param::Clone() const +{ + return ParamPtr(new Param(this->dataPtr->key, this->dataPtr->typeName, + this->GetAsString(), this->dataPtr->required, + this->dataPtr->description)); +} + +////////////////////////////////////////////////// +const std::type_info &Param::GetType() const +{ + return this->dataPtr->value.type(); +} + +////////////////////////////////////////////////// +const std::string &Param::GetTypeName() const +{ + return this->dataPtr->typeName; +} + +///////////////////////////////////////////////// +void Param::SetDescription(const std::string &_desc) +{ + this->dataPtr->description = _desc; +} + +///////////////////////////////////////////////// +std::string Param::GetDescription() const +{ + return this->dataPtr->description; +} + +///////////////////////////////////////////////// +const std::string &Param::GetKey() const +{ + return this->dataPtr->key; +} + +///////////////////////////////////////////////// +bool Param::GetRequired() const +{ + return this->dataPtr->required; +} + +///////////////////////////////////////////////// +Param &Param::operator=(const Param &_param) +{ + this->dataPtr->value = _param.dataPtr->value; + this->dataPtr->defaultValue = _param.dataPtr->defaultValue; + return *this; +} + +///////////////////////////////////////////////// +bool Param::GetSet() const +{ + return this->dataPtr->set; +} diff --git a/sdformat/src/Param_TEST.cc b/sdformat/src/Param_TEST.cc new file mode 100644 index 0000000..f6354ed --- /dev/null +++ b/sdformat/src/Param_TEST.cc @@ -0,0 +1,240 @@ +/* + * Copyright 2014 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include +#include "sdf/Param.hh" + +bool check_double(std::string num) +{ + const std::string name = "number"; + const std::string type = "double"; + const std::string def = "0.0"; + + sdf::Param param(name, type, def, true); + return param.SetFromString(num); +} + +//////////////////////////////////////////////////// +/// Test getting a bool using true/false and 1/0. +TEST(Param, Bool) +{ + sdf::Param boolParam("key", "bool", "true", false, "description"); + bool value = true; + boolParam.Get(value); + EXPECT_TRUE(value); + + boolParam.Set(false); + boolParam.Get(value); + EXPECT_FALSE(value); + + // String parameter that represents a boolean. + sdf::Param strParam("key", "string", "true", false, "description"); + + strParam.Get(value); + EXPECT_TRUE(value); + + strParam.Set("false"); + strParam.Get(value); + EXPECT_FALSE(value); + + strParam.Set("1"); + strParam.Get(value); + EXPECT_TRUE(value); + + strParam.Set("0"); + strParam.Get(value); + EXPECT_FALSE(value); + + strParam.Set("True"); + strParam.Get(value); + EXPECT_TRUE(value); + + strParam.Set("TRUE"); + strParam.Get(value); + EXPECT_TRUE(value); + + // Anything other than 1 or true is treated as a false value + strParam.Set("%"); + strParam.Get(value); + EXPECT_FALSE(value); + + boolParam.Set(true); + boost::any anyValue; + EXPECT_TRUE(boolParam.GetAny(anyValue)); + try + { + value = boost::any_cast(anyValue); + } + catch(boost::bad_any_cast &/*_e*/) + { + FAIL(); + } + EXPECT_TRUE(value); +} + +//////////////////////////////////////////////////// +/// Test decimal number +TEST(SetFromString, Decimals) +{ + ASSERT_TRUE(check_double("0.2345")); +} + +//////////////////////////////////////////////////// +/// Test setting and reading hex int values. +TEST(Param, HexInt) +{ + sdf::Param intParam("key", "int", "0", false, "description"); + int value; + EXPECT_TRUE(intParam.Get(value)); + EXPECT_EQ(value, 0); + + EXPECT_TRUE(intParam.SetFromString("0x01")); + EXPECT_TRUE(intParam.Get(value)); + EXPECT_EQ(value, 1); + + EXPECT_TRUE(intParam.SetFromString("0xff")); + EXPECT_TRUE(intParam.Get(value)); + EXPECT_EQ(value, 255); + + EXPECT_TRUE(intParam.SetFromString("0x00002")); + EXPECT_TRUE(intParam.Get(value)); + EXPECT_EQ(value, 2); + + EXPECT_FALSE(intParam.SetFromString("0xffffffffffffffffffffffffffffffffff")); + EXPECT_TRUE(intParam.Get(value)); + EXPECT_EQ(value, 2); +} + +//////////////////////////////////////////////////// +/// Test setting and reading hex unsigned int values. +TEST(Param, HexUInt) +{ + sdf::Param uintParam("key", "unsigned int", "0", false, "description"); + unsigned int value; + EXPECT_TRUE(uintParam.Get(value)); + EXPECT_EQ(value, 0u); + + EXPECT_TRUE(uintParam.SetFromString("0x01")); + EXPECT_TRUE(uintParam.Get(value)); + EXPECT_EQ(value, 1u); + + EXPECT_TRUE(uintParam.SetFromString("0xff")); + EXPECT_TRUE(uintParam.Get(value)); + EXPECT_EQ(value, 255u); + + EXPECT_TRUE(uintParam.SetFromString("0x00002")); + EXPECT_TRUE(uintParam.Get(value)); + EXPECT_EQ(value, 2u); + + EXPECT_FALSE(uintParam.SetFromString("0xffffffffffffffffffffffffffffffffff")); + EXPECT_TRUE(uintParam.Get(value)); + EXPECT_EQ(value, 2u); +} + +//////////////////////////////////////////////////// +/// Test setting and reading hex and non-hex float values. +TEST(Param, HexFloat) +{ +// Microsoft does not parse hex values properly. +// https://bitbucket.org/osrf/sdformat/issues/114 +#ifndef _MSC_VER + sdf::Param floatParam("key", "float", "0", false, "description"); + float value; + EXPECT_TRUE(floatParam.Get(value)); + EXPECT_FLOAT_EQ(value, 0.0f); + + EXPECT_TRUE(floatParam.SetFromString("0x01")); + EXPECT_TRUE(floatParam.Get(value)); + EXPECT_FLOAT_EQ(value, 1.0f); + + EXPECT_TRUE(floatParam.SetFromString("0X2A")); + EXPECT_TRUE(floatParam.Get(value)); + EXPECT_FLOAT_EQ(value, 42.0f); + + EXPECT_TRUE(floatParam.SetFromString("0.123")); + EXPECT_TRUE(floatParam.Get(value)); + EXPECT_FLOAT_EQ(value, 0.123f); + + EXPECT_FALSE(floatParam.SetFromString("1.0e100")); + EXPECT_TRUE(floatParam.Get(value)); + EXPECT_FLOAT_EQ(value, 0.123f); +#endif +} + +//////////////////////////////////////////////////// +/// Test setting and reading hex and non-hex double values. +TEST(Param, HexDouble) +{ + sdf::Param doubleParam("key", "double", "0", false, "description"); + double value; + EXPECT_TRUE(doubleParam.Get(value)); + EXPECT_DOUBLE_EQ(value, 0.0); + +// Microsoft does not parse hex values properly. +// https://bitbucket.org/osrf/sdformat/issues/114 +#ifndef _MSC_VER + EXPECT_TRUE(doubleParam.SetFromString("0x01")); + EXPECT_TRUE(doubleParam.Get(value)); + EXPECT_DOUBLE_EQ(value, 1.0); + + EXPECT_TRUE(doubleParam.SetFromString("0X2A")); + EXPECT_TRUE(doubleParam.Get(value)); + EXPECT_DOUBLE_EQ(value, 42.0); +#endif + EXPECT_TRUE(doubleParam.SetFromString("0.123456789")); + EXPECT_TRUE(doubleParam.Get(value)); + EXPECT_DOUBLE_EQ(value, 0.123456789); + + EXPECT_FALSE(doubleParam.SetFromString("1.0e1000")); + EXPECT_TRUE(doubleParam.Get(value)); + EXPECT_DOUBLE_EQ(value, 0.123456789); +} + +//////////////////////////////////////////////////// +/// Test setting and reading uint64_t values. +TEST(Param, uint64t) +{ + sdf::Param uint64tParam("key", "uint64_t", "1", false, "description"); + uint64_t value; + EXPECT_TRUE(uint64tParam.Get(value)); + EXPECT_EQ(value, 1u); + + // Max uint64_t + EXPECT_TRUE(uint64tParam.SetFromString("18446744073709551615")); + EXPECT_TRUE(uint64tParam.Get(value)); + EXPECT_EQ(value, UINT64_MAX); +} + +//////////////////////////////////////////////////// +/// Unknown type, should fall back to lexical_cast +TEST(Param, UnknownType) +{ + sdf::Param doubleParam("key", "double", "1.0", false, "description"); + ignition::math::Angle value; + EXPECT_TRUE(doubleParam.Get(value)); + EXPECT_DOUBLE_EQ(value.Radian(), 1.0); +} + +///////////////////////////////////////////////// +/// Main +int main(int argc, char **argv) +{ + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/sdformat/src/SDF.cc b/sdformat/src/SDF.cc new file mode 100644 index 0000000..cf2cd61 --- /dev/null +++ b/sdformat/src/SDF.cc @@ -0,0 +1,389 @@ +/* + * Copyright 2012 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include +#include +#include + +#include "sdf/parser.hh" +#include "sdf/Assert.hh" +#include "sdf/SDFImpl.hh" +#include "sdf/sdf_config.h" + +using namespace sdf; + +/// \todo Remove this pragma when SDF::version is removed +#ifndef _WIN32 +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif +std::string SDF::version = SDF_VERSION; +#ifndef _WIN32 +#pragma GCC diagnostic pop +#endif + +typedef std::list PathList; +typedef std::map URIPathMap; + +URIPathMap g_uriPathMap; + +std::function g_findFileCB; + +///////////////////////////////////////////////// +void sdf::setFindCallback( + std::function _cb) +{ + g_findFileCB = _cb; +} + +///////////////////////////////////////////////// +std::string sdf::findFile(const std::string &_filename, bool _searchLocalPath, + bool _useCallback) +{ + boost::filesystem::path path = _filename; + + // Check to see if _filename is URI. If so, resolve the URI path. + for (URIPathMap::iterator iter = g_uriPathMap.begin(); + iter != g_uriPathMap.end(); ++iter) + { + // Check to see if the URI in the global map is the first part of the + // given filename + if (_filename.find(iter->first) == 0) + { + std::string suffix = _filename; + boost::replace_first(suffix, iter->first, ""); + + // Check each path in the list. + for (PathList::iterator pathIter = iter->second.begin(); + pathIter != iter->second.end(); ++pathIter) + { + // Return the path string if the path + suffix exists. + if (boost::filesystem::exists((*pathIter) / suffix)) + return ((*pathIter) / suffix).string(); + } + } + } + + // Next check the install path. + path = boost::filesystem::path(SDF_SHARE_PATH) / _filename; + if (boost::filesystem::exists(path)) + return path.string(); + + // Next check the versioned install path. + path = boost::filesystem::path(SDF_SHARE_PATH) / "sdformat" / + sdf::SDF::Version() / _filename; + if (boost::filesystem::exists(path)) + return path.string(); + + // Next check SDF_PATH environment variable +#ifndef _WIN32 + char *pathCStr = getenv("SDF_PATH"); +#else + const char *pathCStr = sdf::winGetEnv("SDF_PATH"); +#endif + + if (pathCStr) + { + std::vector paths; + boost::split(paths, pathCStr, boost::is_any_of(":")); + for (std::vector::iterator iter = paths.begin(); + iter != paths.end(); ++iter) + { + path = boost::filesystem::path(*iter) / _filename; + if (boost::filesystem::exists(path)) + return path.string(); + } + } + + // Next check to see if the given file exists. + path = boost::filesystem::path(_filename); + if (boost::filesystem::exists(path)) + return path.string(); + + + // Finally check the local path, if the flag is set. + if (_searchLocalPath) + { + path = boost::filesystem::current_path() / _filename; + + if (boost::filesystem::exists(path)) + return path.string(); + } + + // If we still haven't found the file, use the registered callback if the + // flag has been set + if (_useCallback) + { + if (!g_findFileCB) + { + sdferr << "Tried to use callback in sdf::findFile(), but the callback " + "is empty. Did you call sdf::setFindCallback()?"; + return std::string(); + } + else + return g_findFileCB(_filename); + } + + return std::string(); +} + +///////////////////////////////////////////////// +void sdf::addURIPath(const std::string &_uri, const std::string &_path) +{ + // Split _path on colons. + std::list parts; + boost::split(parts, _path, boost::is_any_of(":")); + + // Add each part of the colon separated path to the global URI map. + for (std::list::iterator iter = parts.begin(); + iter != parts.end(); ++iter) + { + boost::filesystem::path path = *iter; + + // Only add valid paths + if (!(*iter).empty() && boost::filesystem::exists(path) && + boost::filesystem::is_directory(path)) + { + g_uriPathMap[_uri].push_back(path); + } + } +} + +///////////////////////////////////////////////// +/// \todo Remove this pragma once this->root is removed +#ifndef _WIN32 +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif +///////////////////////////////////////////////// +SDF::SDF() + : root(new Element) +{ +} + +///////////////////////////////////////////////// +SDF::~SDF() +{ +} +/// \todo Remove this pragma once this->root is removed +#ifndef _WIN32 +#pragma GCC diagnostic pop +#endif + +///////////////////////////////////////////////// +void SDF::PrintDescription() +{ + this->Root()->PrintDescription(""); +} + +///////////////////////////////////////////////// +void SDF::PrintValues() +{ + this->Root()->PrintValues(""); +} + +///////////////////////////////////////////////// +void SDF::PrintDoc() +{ + std::string html, html2; + int index = 0; + this->Root()->PrintDocLeftPane(html, 10, index); + + index = 0; + this->Root()->PrintDocRightPane(html2, 10, index); + + std::cout << "\n" + << "\n" + << "\n" + << " \n" + << " \n" + << " \n" + << " \n" + << " \n" + << "\n\n"; + + std::cout << "
    \n" + << "

    SDF " << SDF::Version() << "

    \n"; + + std::cout << "

    The Robot Modeling Language (SDF) is an XML file " + << "format used to describe all the elements in a simulation " + << "environment.\n

    "; + std::cout << "

    Usage

    \n"; + std::cout << "
    "; + std::cout << "
    • Left Panel: List of all the SDF elements.
    • "; + std::cout << "
    • Right Panel: Descriptions of all the SDF " + << "elements.
    • "; + std::cout << "
    • Selection: Clicking an element in the Left Panel " + << "moves the corresponding description to the top of the Right " + << "Panel.
    • "; + std::cout << "
    • Search: Use your web-browser's built in 'Find' " + << "function to locate a specific element." + << "
    "; + std::cout << "
    "; + + std::cout << "
    \n"; + + std::cout << "

    Meta-Tags

    \n"; + std::cout << "
    "; + std::cout << "Meta-tags are processed by the parser before the final " + << "SDF file is generated."; + std::cout << "
      "; + + std::cout << "
    • <include>: Include an SDF model file " + << "within the current SDF file." + << "
        " + << "
      • <uri>: URI of SDF model file to include.
      • " + << "
      • <name>: Name of the included SDF model.
      • " + << "
      • <pose>: Pose of the included SDF model, " + << "specified as <pose>x y z roll pitch yaw</pose>, " + << "with x, y, and z representing a position in meters, and roll, " + << "pitch, and yaw representing Euler angles in radians.
      • " + << "
      " + << "
    • "; + + std::cout << "
    "; + std::cout << "
    "; + + + std::cout << "
    \n"; + + std::cout << "
    \n"; + + std::cout << "
    \n"; + std::cout << html; + std::cout << "
    \n"; + + std::cout << "
    \n"; + std::cout << html2; + std::cout << "
    \n"; + + std::cout << "
    \n"; + + std::cout << "\ + \ + \n"; +} + +///////////////////////////////////////////////// +void SDF::Write(const std::string &_filename) +{ + std::string string = this->Root()->ToString(""); + + std::ofstream out(_filename.c_str(), std::ios::out); + + if (!out) + { + sdferr << "Unable to open file[" << _filename << "] for writing\n"; + return; + } + out << string; + out.close(); +} + +///////////////////////////////////////////////// +std::string SDF::ToString() const +{ + std::ostringstream stream; + + stream << "\n"; + if (this->Root()->GetName() != "sdf") + stream << "\n"; + + stream << this->Root()->ToString(""); + + if (this->Root()->GetName() != "sdf") + stream << ""; + + return stream.str(); +} + +///////////////////////////////////////////////// +void SDF::SetFromString(const std::string &_sdfData) +{ + sdf::initFile("root.sdf", this->Root()); + if (!sdf::readString(_sdfData, this->Root())) + { + sdferr << "Unable to parse sdf string[" << _sdfData << "]\n"; + } +} + +/// \todo Remove this pragma once this->root this->version is removed +#ifndef _WIN32 +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif + +///////////////////////////////////////////////// +ElementPtr SDF::Root() const +{ + return this->root; +} + +///////////////////////////////////////////////// +void SDF::Root(const ElementPtr _root) +{ + this->root = _root; +} + +///////////////////////////////////////////////// +std::string SDF::Version() +{ + return version; +} + +///////////////////////////////////////////////// +void SDF::Version(const std::string &_version) +{ + version = _version; +} + +#ifndef _WIN32 +#pragma GCC diagnostic pop +#endif diff --git a/sdformat/src/SDFExtension.cc b/sdformat/src/SDFExtension.cc new file mode 100644 index 0000000..e5420c4 --- /dev/null +++ b/sdformat/src/SDFExtension.cc @@ -0,0 +1,128 @@ +/* + * Copyright 2015 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include "sdf/SDFExtension.hh" + +using namespace sdf; + +///////////////////////////////////////////////// +SDFExtension::SDFExtension() +{ + this->material.clear(); + this->visual_blobs.clear(); + this->collision_blobs.clear(); + this->setStaticFlag = false; + this->gravity = true; + this->isDampingFactor = false; + this->isMaxContacts = false; + this->isMaxVel = false; + this->isMinDepth = false; + this->fdir1.clear(); + this->isMu1 = false; + this->isMu2 = false; + this->isKp = false; + this->isKd = false; + this->isSelfCollide = false; + this->selfCollide = false; + this->isLaserRetro = false; + this->isSpringReference = false; + this->isSpringStiffness = false; + this->isStopCfm = false; + this->isStopErp = false; + this->isStopKp = false; + this->isStopKd = false; + this->isInitialJointPosition = false; + this->isFudgeFactor = false; + this->isProvideFeedback = false; + this->isImplicitSpringDamper = false; + this->blobs.clear(); + + this->dampingFactor = 0; + this->maxContacts = 0; + this->maxVel = 0; + this->minDepth = 0; + this->mu1 = 0; + this->mu2 = 0; + this->kp = 100000000; + this->kd = 1; + this->laserRetro = 101; + this->springReference = 0; + this->springStiffness = 0; + this->stopCfm = 0; + this->stopErp = 0.1; + this->stopKp = 100000000; + this->stopKd = 1; + this->initialJointPosition = 0; + this->fudgeFactor = 1; + + this->provideFeedback = false; + this->implicitSpringDamper = false; +} + +///////////////////////////////////////////////// +SDFExtension::SDFExtension(const SDFExtension &_ge) +{ + this->material = _ge.material; + this->visual_blobs = _ge.visual_blobs; + this->collision_blobs = _ge.collision_blobs; + this->setStaticFlag = _ge.setStaticFlag; + this->gravity = _ge.gravity; + this->isDampingFactor = _ge.isDampingFactor; + this->isMaxContacts = _ge.isMaxContacts; + this->isMaxVel = _ge.isMaxVel; + this->isMinDepth = _ge.isMinDepth; + this->fdir1 = _ge.fdir1; + this->isMu1 = _ge.isMu1; + this->isMu2 = _ge.isMu2; + this->isKp = _ge.isKp; + this->isKd = _ge.isKd; + this->selfCollide = _ge.selfCollide; + this->isLaserRetro = _ge.isLaserRetro; + this->isSpringReference = _ge.isSpringReference; + this->isSpringStiffness = _ge.isSpringStiffness; + this->isStopKp = _ge.isStopKp; + this->isStopKd = _ge.isStopKd; + this->isStopCfm = _ge.isStopCfm; + this->isStopErp = _ge.isStopErp; + this->isInitialJointPosition = _ge.isInitialJointPosition; + this->isFudgeFactor = _ge.isFudgeFactor; + this->isProvideFeedback = _ge.isProvideFeedback; + this->isImplicitSpringDamper = _ge.isImplicitSpringDamper; + this->provideFeedback = _ge.provideFeedback; + this->implicitSpringDamper = _ge.implicitSpringDamper; + this->oldLinkName = _ge.oldLinkName; + this->reductionTransform = _ge.reductionTransform; + this->blobs = _ge.blobs; + + this->dampingFactor = _ge.dampingFactor; + this->maxContacts = _ge.maxContacts; + this->maxVel = _ge.maxVel; + this->minDepth = _ge.minDepth; + this->mu1 = _ge.mu1; + this->mu2 = _ge.mu2; + this->kp = _ge.kp; + this->kd = _ge.kd; + this->laserRetro = _ge.laserRetro; + this->springReference = _ge.springReference; + this->springStiffness = _ge.springStiffness; + this->stopKp = _ge.stopKp; + this->stopKd = _ge.stopKd; + this->stopCfm = _ge.stopCfm; + this->stopErp = _ge.stopErp; + this->initialJointPosition = _ge.initialJointPosition; + this->fudgeFactor = _ge.fudgeFactor; +} diff --git a/sdformat/src/SDF_TEST.cc b/sdformat/src/SDF_TEST.cc new file mode 100644 index 0000000..229578d --- /dev/null +++ b/sdformat/src/SDF_TEST.cc @@ -0,0 +1,527 @@ +/* + * Copyright 2012 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include +#include "test_config.h" +#include "sdf/sdf.hh" + +//////////////////////////////////////////////////// +// Testing fixture +class SDFUpdate : public testing::Test +{ + protected: SDFUpdate() + { + } + + protected: virtual ~SDFUpdate() + { + } +}; + +class SDFUpdateFixture +{ + public: std::string GetName() const {return this->name;} + public: bool GetFlag() const {return this->flag;} + public: ignition::math::Pose3d GetPose() const {return this->pose;} + public: std::string name; + public: bool flag; + public: ignition::math::Pose3d pose; +}; + +//////////////////////////////////////////////////// +/// Ensure that SDF::Update is working for attributes +TEST_F(SDFUpdate, UpdateAttribute) +{ + // Set up a simple sdf model file + std::ostringstream stream; + stream << "" + << "" + << " 0 1 2 0 0 0" + << " false" + << "" + << ""; + sdf::SDF sdfParsed; + sdfParsed.SetFromString(stream.str()); + + // Verify correct parsing + EXPECT_TRUE(sdfParsed.Root()->HasElement("model")); + sdf::ElementPtr modelElem = sdfParsed.Root()->GetElement("model"); + + // Read name attribute value + EXPECT_TRUE(modelElem->HasAttribute("name")); + sdf::ParamPtr nameParam = modelElem->GetAttribute("name"); + EXPECT_TRUE(nameParam->IsType()); + + // Set test class variables based on sdf values + // Set parameter update functions to test class accessors + SDFUpdateFixture fixture; + nameParam->Get(fixture.name); + nameParam->SetUpdateFunc(std::bind(&SDFUpdateFixture::GetName, &fixture)); + + std::string nameCheck; + int i; + for (i = 0; i < 4; i++) + { + // Update test class variables + fixture.name[0] = 'd' + static_cast(i); + + // Update root sdf element + sdfParsed.Root()->Update(); + + // Expect sdf values to match test class variables + nameParam->Get(nameCheck); + EXPECT_STREQ(nameCheck.c_str(), fixture.name.c_str()); + } +} + +//////////////////////////////////////////////////// +/// Ensure that SDF::Update is working for elements +TEST_F(SDFUpdate, UpdateElement) +{ + // Set up a simple sdf model file + std::ostringstream stream; + stream << "" + << "" + << " 0 1 2 0 0 0" + << " false" + << "" + << ""; + sdf::SDF sdfParsed; + sdfParsed.SetFromString(stream.str()); + + // Verify correct parsing + EXPECT_TRUE(sdfParsed.Root()->HasElement("model")); + sdf::ElementPtr modelElem = sdfParsed.Root()->GetElement("model"); + + // Read static element value + EXPECT_TRUE(modelElem->HasElement("static")); + sdf::ParamPtr staticParam = modelElem->GetElement("static")->GetValue(); + EXPECT_TRUE(staticParam->IsType()); + + // Read pose element value + EXPECT_TRUE(modelElem->HasElement("pose")); + sdf::ParamPtr poseParam = modelElem->GetElement("pose")->GetValue(); + EXPECT_TRUE(poseParam->IsType()); + + // Set test class variables based on sdf values + // Set parameter update functions to test class accessors + SDFUpdateFixture fixture; + staticParam->Get(fixture.flag); + staticParam->SetUpdateFunc(std::bind(&SDFUpdateFixture::GetFlag, &fixture)); + poseParam->Get(fixture.pose); + poseParam->SetUpdateFunc(std::bind(&SDFUpdateFixture::GetPose, &fixture)); + + bool flagCheck; + ignition::math::Pose3d poseCheck; + int i; + for (i = 0; i < 4; i++) + { + // Update test class variables + fixture.flag = !fixture.flag; + fixture.pose.Pos().X() = i; + fixture.pose.Pos().Y() = i+10; + fixture.pose.Pos().Z() = -i*i*i; + + // Update root sdf element + sdfParsed.Root()->Update(); + + // Expect sdf values to match test class variables + staticParam->Get(flagCheck); + EXPECT_EQ(flagCheck, fixture.flag); + poseParam->Get(poseCheck); + EXPECT_EQ(poseCheck, fixture.pose); + } +} + +//////////////////////////////////////////////////// +/// Ensure that SDF::Element::RemoveFromParent is working +TEST_F(SDFUpdate, ElementRemoveFromParent) +{ + // Set up a simple sdf model file + std::ostringstream stream; + stream << "" + << "" + << " 0 1 2 0 0 0" + << " false" + << "" + << "" + << " 0 1 2 0 0 0" + << " false" + << "" + << "" + << " 0 1 2 0 0 0" + << " false" + << "" + << ""; + sdf::SDF sdfParsed; + sdfParsed.SetFromString(stream.str()); + + sdf::ElementPtr elem; + + // Verify correct parsing + EXPECT_TRUE(sdfParsed.Root()->HasElement("model")); + elem = sdfParsed.Root()->GetElement("model"); + + // Select the second model named 'model2' + elem = elem->GetNextElement("model"); + EXPECT_TRUE(elem != NULL); + EXPECT_TRUE(elem->HasAttribute("name")); + EXPECT_EQ(elem->Get("name"), "model2"); + + // Remove model2 + elem->RemoveFromParent(); + + // Get first model element again + elem = sdfParsed.Root()->GetElement("model"); + // Check name == model1 + EXPECT_TRUE(elem->HasAttribute("name")); + EXPECT_EQ(elem->Get("name"), "model1"); + + // Get next model element + elem = elem->GetNextElement("model"); + // Check name == model3 + EXPECT_TRUE(elem->HasAttribute("name")); + EXPECT_EQ(elem->Get("name"), "model3"); + + // Try to get another model element + elem = elem->GetNextElement("model"); + EXPECT_FALSE(elem); +} + +//////////////////////////////////////////////////// +/// Ensure that SDF::Element::RemoveChild is working +TEST_F(SDFUpdate, ElementRemoveChild) +{ + // Set up a simple sdf model file + std::ostringstream stream; + stream << "" + << "" + << " 0 1 2 0 0 0" + << " false" + << "" + << "" + << " 0 1 2 0 0 0" + << " false" + << "" + << "" + << " 0 1 2 0 0 0" + << " false" + << "" + << ""; + sdf::SDF sdfParsed; + sdfParsed.SetFromString(stream.str()); + + sdf::ElementPtr elem, elem2; + + // Verify correct parsing + EXPECT_TRUE(sdfParsed.Root()->HasElement("model")); + elem = sdfParsed.Root()->GetElement("model"); + + // Select the static element in model1 + elem2 = elem->GetElement("static"); + EXPECT_TRUE(elem2 != NULL); + EXPECT_FALSE(elem2->Get()); + elem->RemoveChild(elem2); + + // Get first model element again + elem = sdfParsed.Root()->GetElement("model"); + // Check name == model1 + EXPECT_TRUE(elem->HasAttribute("name")); + EXPECT_EQ(elem->Get("name"), "model1"); + + // Check that we have deleted the static element in model1 + EXPECT_FALSE(elem->HasElement("static")); + + // Get model2 + elem2 = elem->GetNextElement("model"); + + // Remove model2 + sdfParsed.Root()->RemoveChild(elem2); + + // Get first model element again + elem = sdfParsed.Root()->GetElement("model"); + // Check name == model1 + EXPECT_TRUE(elem->HasAttribute("name")); + EXPECT_EQ(elem->Get("name"), "model1"); + + // Get next model element + elem = elem->GetNextElement("model"); + // Check name == model3 + EXPECT_TRUE(elem->HasAttribute("name")); + EXPECT_EQ(elem->Get("name"), "model3"); + + // Try to get another model element + elem = elem->GetNextElement("model"); + EXPECT_FALSE(elem); +} + +//////////////////////////////////////////////////// +/// Ensure that getting empty values with empty keys returns correct values. +TEST_F(SDFUpdate, EmptyValues) +{ + std::string emptyString; + sdf::ElementPtr elem; + + elem.reset(new sdf::Element()); + EXPECT_FALSE(elem->Get(emptyString)); + elem->AddValue("bool", "true", "0", "description"); + EXPECT_TRUE(elem->Get(emptyString)); + + elem.reset(new sdf::Element()); + EXPECT_EQ(elem->Get(emptyString), 0); + elem->AddValue("int", "12", "0", "description"); + EXPECT_EQ(elem->Get(emptyString), 12); + + elem.reset(new sdf::Element()); + EXPECT_EQ(elem->Get(emptyString), + static_cast(0)); + elem->AddValue("unsigned int", "123", "0", "description"); + EXPECT_EQ(elem->Get(emptyString), + static_cast(123)); + + elem.reset(new sdf::Element()); + EXPECT_EQ(elem->Get(emptyString), '\0'); + elem->AddValue("char", "a", "0", "description"); + EXPECT_EQ(elem->Get(emptyString), 'a'); + + elem.reset(new sdf::Element()); + EXPECT_EQ(elem->Get(emptyString), ""); + elem->AddValue("string", "hello", "0", "description"); + EXPECT_EQ(elem->Get(emptyString), "hello"); + + elem.reset(new sdf::Element()); + EXPECT_EQ(elem->Get(emptyString), + ignition::math::Vector2d()); + elem->AddValue("vector2d", "1 2", "0", "description"); + EXPECT_EQ(elem->Get(emptyString), + ignition::math::Vector2d(1, 2)); + + elem.reset(new sdf::Element()); + EXPECT_EQ(elem->Get(emptyString), + ignition::math::Vector3d()); + elem->AddValue("vector3", "1 2 3", "0", "description"); + EXPECT_EQ(elem->Get(emptyString), + ignition::math::Vector3d(1, 2, 3)); + + elem.reset(new sdf::Element()); + EXPECT_EQ(elem->Get(emptyString), + ignition::math::Quaterniond()); + elem->AddValue("quaternion", "1 2 3", "0", "description"); + EXPECT_EQ(elem->Get(emptyString), + ignition::math::Quaterniond(-2.14159, 1.14159, -0.141593)); + + elem.reset(new sdf::Element()); + EXPECT_EQ(elem->Get(emptyString), + ignition::math::Pose3d()); + elem->AddValue("pose", "1.0 2.0 3.0 4.0 5.0 6.0", "0", "description"); + EXPECT_EQ(elem->Get(emptyString).Pos(), + ignition::math::Pose3d(1, 2, 3, 4, 5, 6).Pos()); + EXPECT_EQ(elem->Get(emptyString).Rot().Euler(), + ignition::math::Pose3d(1, 2, 3, 4, 5, 6).Rot().Euler()); + + elem.reset(new sdf::Element()); + EXPECT_EQ(elem->Get(emptyString), sdf::Color()); + elem->AddValue("color", ".1 .2 .3 1.0", "0", "description"); + EXPECT_EQ(elem->Get(emptyString), + sdf::Color(.1f, .2f, .3f, 1.0f)); + + elem.reset(new sdf::Element()); + EXPECT_EQ(elem->Get(emptyString), sdf::Time()); + elem->AddValue("time", "1 2", "0", "description"); + EXPECT_EQ(elem->Get(emptyString), sdf::Time(1, 2)); + + elem.reset(new sdf::Element()); + EXPECT_NEAR(elem->Get(emptyString), 0.0, 1e-6); + elem->AddValue("float", "12.34", "0", "description"); + EXPECT_NEAR(elem->Get(emptyString), 12.34, 1e-6); + + elem.reset(new sdf::Element()); + EXPECT_NEAR(elem->Get(emptyString), 0.0, 1e-6); + elem->AddValue("double", "12.34", "0", "description"); + EXPECT_NEAR(elem->Get(emptyString), 12.34, 1e-6); +} + +///////////////////////////////////////////////// +TEST_F(SDFUpdate, GetAny) +{ + std::ostringstream stream; + // Test types double, bool, string, int, vector3, color, pose + stream << "" + << "" + << " 0 0 -7.1 " + << " " + << " 8" + << " 0.002" + << " " + << " " + << " 0 1 2 0 0 0" + << " true" + << " " + << " " + << " " + << " 0.1 0.1 0.1 1" + << " " + << " " + << " " + << " " + << "" + << ""; + sdf::SDF sdfParsed; + sdfParsed.SetFromString(stream.str()); + + // Verify correct parsing + EXPECT_TRUE(sdfParsed.Root()->HasElement("world")); + sdf::ElementPtr worldElem = sdfParsed.Root()->GetElement("world"); + + EXPECT_TRUE(worldElem->HasElement("model")); + sdf::ElementPtr modelElem = worldElem->GetElement("model"); + EXPECT_TRUE(worldElem->HasElement("physics")); + sdf::ElementPtr physicsElem = worldElem->GetElement("physics"); + + { + boost::any anyValue = modelElem->GetAny("name"); + try + { + EXPECT_EQ(boost::any_cast(anyValue), "test_model"); + } + catch(boost::bad_any_cast &/*_e*/) + { + FAIL(); + } + } + + { + EXPECT_TRUE(modelElem->HasElement("pose")); + sdf::ElementPtr poseElem = modelElem->GetElement("pose"); + boost::any anyValue = poseElem->GetAny(); + try + { + EXPECT_EQ(boost::any_cast(anyValue), + ignition::math::Pose3d(0, 1, 2, 0, 0, 0)); + } + catch(boost::bad_any_cast &/*_e*/) + { + FAIL(); + } + } + + { + EXPECT_TRUE(worldElem->HasElement("gravity")); + boost::any anyValue = worldElem->GetElement("gravity")->GetAny(); + try + { + EXPECT_EQ(boost::any_cast(anyValue), + ignition::math::Vector3d(0, 0, -7.1)); + } + catch(boost::bad_any_cast &/*_e*/) + { + FAIL(); + } + } + + { + EXPECT_TRUE(physicsElem->HasElement("max_step_size")); + boost::any anyValue = physicsElem->GetElement("max_step_size")->GetAny(); + try + { + EXPECT_NEAR(boost::any_cast(anyValue), 0.002, 1e-6); + } + catch(boost::bad_any_cast &/*_e*/) + { + FAIL(); + } + } + + { + EXPECT_TRUE(physicsElem->HasElement("max_contacts")); + boost::any anyValue = physicsElem->GetElement("max_contacts")->GetAny(); + try + { + EXPECT_EQ(boost::any_cast(anyValue), 8); + } + catch(boost::bad_any_cast &/*_e*/) + { + FAIL(); + } + } + + { + EXPECT_TRUE(worldElem->HasElement("gravity")); + boost::any anyValue = worldElem->GetElement("gravity")->GetAny(); + try + { + EXPECT_EQ(boost::any_cast(anyValue), + ignition::math::Vector3d(0, 0, -7.1)); + } + catch(boost::bad_any_cast &/*_e*/) + { + FAIL(); + } + } + + { + EXPECT_TRUE(modelElem->HasElement("static")); + boost::any anyValue = modelElem->GetElement("static")->GetAny(); + try + { + EXPECT_EQ(boost::any_cast(anyValue), true); + } + catch(boost::bad_any_cast &/*_e*/) + { + FAIL(); + } + } + + { + EXPECT_TRUE(modelElem->HasElement("link")); + EXPECT_TRUE(modelElem->GetElement("link")->HasElement("visual")); + EXPECT_TRUE(modelElem->GetElement("link")->GetElement("visual")-> + HasElement("material")); + sdf::ElementPtr materialElem = modelElem->GetElement("link")-> + GetElement("visual")->GetElement("material"); + EXPECT_TRUE(materialElem->HasElement("ambient")); + boost::any anyValue = materialElem->GetElement("ambient")->GetAny(); + try + { + EXPECT_EQ(boost::any_cast(anyValue), + sdf::Color(0.1f, 0.1f, 0.1f, 1.0f)); + } + catch(boost::bad_any_cast &/*_e*/) + { + FAIL(); + } + } +} + +///////////////////////////////////////////////// +TEST_F(SDFUpdate, Version) +{ + EXPECT_STREQ(SDF_VERSION, sdf::SDF::Version().c_str()); + + sdf::SDF::Version("0.2.3"); + EXPECT_STREQ("0.2.3", sdf::SDF::Version().c_str()); +} + +///////////////////////////////////////////////// +/// Main +int main(int argc, char **argv) +{ + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/sdformat/src/Types.cc b/sdformat/src/Types.cc new file mode 100644 index 0000000..a7c649f --- /dev/null +++ b/sdformat/src/Types.cc @@ -0,0 +1,47 @@ +/* + * Copyright 2015 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifdef _WIN32 +#include +#endif + +/// \todo Remove this diagnositic push/pop in version 5 +#ifndef _WIN32 +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif +#include "sdf/Types.hh" +#ifndef _WIN32 +#pragma GCC diagnostic pop +#endif + +///////////////////////////////////////////////// +#ifdef _WIN32 +const char *sdf::winGetEnv(const char *_name) +{ + const DWORD buffSize = 65535; + static char buffer[buffSize]; + if (GetEnvironmentVariable(_name, buffer, buffSize)) + return buffer; + return NULL; +} +#else +const char *sdf::winGetEnv(const char * /*_name*/) +{ + return NULL; +} +#endif diff --git a/sdformat/src/parser.cc b/sdformat/src/parser.cc new file mode 100644 index 0000000..f184afc --- /dev/null +++ b/sdformat/src/parser.cc @@ -0,0 +1,1058 @@ +/* + * Copyright 2012 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#include +#include +#include +#include +#include +#include + +#include "sdf/Console.hh" +#include "sdf/Converter.hh" +#include "sdf/SDFImpl.hh" +#include "sdf/Param.hh" +#include "sdf/parser.hh" +#include "sdf/sdf_config.h" + +#include "sdf/parser_urdf.hh" + +namespace sdf +{ +////////////////////////////////////////////////// +bool init(SDFPtr _sdf) +{ + bool result = false; + + std::string filename; + std::string fileToFind = "root.sdf"; + + if (sdf::SDF::Version() == "1.0" || sdf::SDF::Version() == "1.2") + fileToFind = "gazebo.sdf"; + + filename = sdf::findFile(fileToFind); + + FILE *ftest = fopen(filename.c_str(), "r"); + if (ftest) + { + fclose(ftest); + if (initFile(filename, _sdf)) + { + result = true; + } + else + { + sdferr << "Unable to init SDF file[" << filename << "]\n"; + } + } + else + { + sdferr << "Unable to find or open SDF file[" << fileToFind << "]\n"; + } + + return result; +} + +////////////////////////////////////////////////// +template +inline bool _initFile(const std::string &_filename, TPtr _sdf) +{ + std::string filename = sdf::findFile(_filename); + + TiXmlDocument xmlDoc; + if (xmlDoc.LoadFile(filename)) + return initDoc(&xmlDoc, _sdf); + else + sdferr << "Unable to load file[" << _filename << "]\n"; + + return false; +} + +////////////////////////////////////////////////// +bool initFile(const std::string &_filename, SDFPtr _sdf) +{ + return _initFile(_filename, _sdf); +} + +////////////////////////////////////////////////// +bool initFile(const std::string &_filename, ElementPtr _sdf) +{ + return _initFile(_filename, _sdf); +} + +////////////////////////////////////////////////// +bool initString(const std::string &_xmlString, SDFPtr _sdf) +{ + TiXmlDocument xmlDoc; + xmlDoc.Parse(_xmlString.c_str()); + if (xmlDoc.Error()) + { + sdferr << "Failed to parse string as XML: " << xmlDoc.ErrorDesc() << '\n'; + return false; + } + + return initDoc(&xmlDoc, _sdf); +} + +////////////////////////////////////////////////// +inline TiXmlElement *_initDocGetElement(TiXmlDocument *_xmlDoc) +{ + if (!_xmlDoc) + { + sdferr << "Could not parse the xml\n"; + return nullptr; + } + + TiXmlElement *element = _xmlDoc->FirstChildElement("element"); + if (!element) + { + sdferr << "Could not find the 'element' element in the xml file\n"; + return nullptr; + } + + return element; +} + +////////////////////////////////////////////////// +bool initDoc(TiXmlDocument *_xmlDoc, SDFPtr _sdf) +{ + auto element = _initDocGetElement(_xmlDoc); + if (!element) + { + return false; + } + + return initXml(element, _sdf->Root()); +} + +////////////////////////////////////////////////// +bool initDoc(TiXmlDocument *_xmlDoc, ElementPtr _sdf) +{ + auto element = _initDocGetElement(_xmlDoc); + if (!element) + { + return false; + } + + return initXml(element, _sdf); +} + +////////////////////////////////////////////////// +bool initXml(TiXmlElement *_xml, ElementPtr _sdf) +{ + const char *refString = _xml->Attribute("ref"); + if (refString) + _sdf->SetReferenceSDF(std::string(refString)); + + const char *nameString = _xml->Attribute("name"); + if (!nameString) + { + sdferr << "Element is missing the name attribute\n"; + return false; + } + _sdf->SetName(std::string(nameString)); + + const char *requiredString = _xml->Attribute("required"); + if (!requiredString) + { + sdferr << "Element is missing the required attributed\n"; + return false; + } + _sdf->SetRequired(requiredString); + + const char *elemTypeString = _xml->Attribute("type"); + if (elemTypeString) + { + bool required = std::string(requiredString) == "1" ? true : false; + const char *elemDefaultValue = _xml->Attribute("default"); + std::string description; + TiXmlElement *descChild = _xml->FirstChildElement("description"); + if (descChild && descChild->GetText()) + description = descChild->GetText(); + + _sdf->AddValue(elemTypeString, elemDefaultValue, required, description); + } + + // Get all attributes + for (TiXmlElement *child = _xml->FirstChildElement("attribute"); + child; child = child->NextSiblingElement("attribute")) + { + TiXmlElement *descriptionChild = child->FirstChildElement("description"); + const char *name = child->Attribute("name"); + const char *type = child->Attribute("type"); + const char *defaultValue = child->Attribute("default"); + + requiredString = child->Attribute("required"); + + if (!name) + { + sdferr << "Attribute is missing a name\n"; + return false; + } + if (!type) + { + sdferr << "Attribute is missing a type\n"; + return false; + } + if (!defaultValue) + { + sdferr << "Attribute[" << name << "] is missing a default\n"; + return false; + } + if (!requiredString) + { + sdferr << "Attribute is missing a required string\n"; + return false; + } + std::string requiredStr = requiredString; + boost::trim(requiredStr); + bool required = requiredStr == "1" ? true : false; + std::string description; + + if (descriptionChild && descriptionChild->GetText()) + description = descriptionChild->GetText(); + + _sdf->AddAttribute(name, type, defaultValue, required, description); + } + + // Read the element description + TiXmlElement *descChild = _xml->FirstChildElement("description"); + if (descChild && descChild->GetText()) + { + _sdf->SetDescription(descChild->GetText()); + } + + // Get all child elements + for (TiXmlElement *child = _xml->FirstChildElement("element"); + child; child = child->NextSiblingElement("element")) + { + const char *copyDataString = child->Attribute("copy_data"); + if (copyDataString && + (std::string(copyDataString) == "true" || + std::string(copyDataString) == "1")) + { + _sdf->SetCopyChildren(true); + } + else + { + ElementPtr element(new Element); + initXml(child, element); + _sdf->AddElementDescription(element); + } + } + + // Get all include elements + for (TiXmlElement *child = _xml->FirstChildElement("include"); + child; child = child->NextSiblingElement("include")) + { + std::string filename = child->Attribute("filename"); + + ElementPtr element(new Element); + + initFile(filename, element); + + // override description for include elements + TiXmlElement *description = child->FirstChildElement("description"); + if (description) + element->SetDescription(description->GetText()); + + _sdf->AddElementDescription(element); + } + + return true; +} + + +////////////////////////////////////////////////// +bool readFile(const std::string &_filename, SDFPtr _sdf) +{ + TiXmlDocument xmlDoc; + std::string filename = sdf::findFile(_filename); + + if (filename.empty()) + { + sdferr << "Error finding file [" << _filename << "].\n"; + return false; + } + + if (!xmlDoc.LoadFile(filename)) + { + sdferr << "Error parsing XML in file [" << filename << "]: " + << xmlDoc.ErrorDesc() << '\n'; + return false; + } + if (readDoc(&xmlDoc, _sdf, filename)) + return true; + else + { + sdf::URDF2SDF u2g; + TiXmlDocument doc = u2g.InitModelFile(filename); + if (sdf::readDoc(&doc, _sdf, "urdf file")) + { + sdfdbg << "parse from urdf file [" << _filename << "].\n"; + return true; + } + else + { + sdferr << "parse as old deprecated model file failed.\n"; + return false; + } + } + + return false; +} + +////////////////////////////////////////////////// +bool readString(const std::string &_xmlString, SDFPtr _sdf) +{ + TiXmlDocument xmlDoc; + xmlDoc.Parse(_xmlString.c_str()); + if (xmlDoc.Error()) + { + sdferr << "Error parsing XML from string: " << xmlDoc.ErrorDesc() << '\n'; + return false; + } + if (readDoc(&xmlDoc, _sdf, "data-string")) + return true; + else + { + sdf::URDF2SDF u2g; + TiXmlDocument doc = u2g.InitModelString(_xmlString); + if (sdf::readDoc(&doc, _sdf, "urdf string")) + { + sdfdbg << "Parsing from urdf.\n"; + return true; + } + else + { + sdferr << "parse as old deprecated model file failed.\n"; + return false; + } + } + + return false; +} + +////////////////////////////////////////////////// +bool readString(const std::string &_xmlString, ElementPtr _sdf) +{ + TiXmlDocument xmlDoc; + xmlDoc.Parse(_xmlString.c_str()); + if (xmlDoc.Error()) + { + sdferr << "Error parsing XML from string: " << xmlDoc.ErrorDesc() << '\n'; + return false; + } + if (readDoc(&xmlDoc, _sdf, "data-string")) + return true; + else + { + sdferr << "parse as sdf version " << SDF::Version() << " failed, " + << "should try to parse as old deprecated format\n"; + return false; + } +} + +////////////////////////////////////////////////// +bool readDoc(TiXmlDocument *_xmlDoc, SDFPtr _sdf, const std::string &_source) +{ + if (!_xmlDoc) + { + sdfwarn << "Could not parse the xml from source[" << _source << "]\n"; + return false; + } + + // check sdf version, use old parser if necessary + TiXmlElement *sdfNode = _xmlDoc->FirstChildElement("sdf"); + if (!sdfNode) + sdfNode = _xmlDoc->FirstChildElement("gazebo"); + + if (sdfNode && sdfNode->Attribute("version")) + { + if (strcmp(sdfNode->Attribute("version"), SDF::Version().c_str()) != 0) + { + sdfdbg << "Converting a deprecated source[" << _source << "].\n"; + Converter::Convert(_xmlDoc, SDF::Version()); + } + + // parse new sdf xml + TiXmlElement *elemXml = _xmlDoc->FirstChildElement(_sdf->Root()->GetName()); + if (!readXml(elemXml, _sdf->Root())) + { + sdferr << "Unable to read element <" << _sdf->Root()->GetName() << ">\n"; + return false; + } + } + else + { + // try to use the old deprecated parser + if (!sdfNode) + sdfdbg << "No element in file[" << _source << "]\n"; + else if (!sdfNode->Attribute("version")) + sdfdbg << "SDF element has no version in file[" + << _source << "]\n"; + else if (strcmp(sdfNode->Attribute("version"), + SDF::Version().c_str()) != 0) + sdfdbg << "SDF version [" + << sdfNode->Attribute("version") + << "] is not " << SDF::Version() << "\n"; + return false; + } + + return true; +} + +////////////////////////////////////////////////// +bool readDoc(TiXmlDocument *_xmlDoc, ElementPtr _sdf, + const std::string &_source) +{ + if (!_xmlDoc) + { + sdfwarn << "Could not parse the xml\n"; + return false; + } + + // check sdf version, use old parser if necessary + TiXmlElement *sdfNode = _xmlDoc->FirstChildElement("sdf"); + if (!sdfNode) + sdfNode = _xmlDoc->FirstChildElement("gazebo"); + + if (sdfNode && sdfNode->Attribute("version")) + { + if (strcmp(sdfNode->Attribute("version"), + SDF::Version().c_str()) != 0) + { + sdfwarn << "Converting a deprecated SDF source[" << _source << "].\n"; + Converter::Convert(_xmlDoc, SDF::Version()); + } + + TiXmlElement *elemXml = sdfNode; + if (sdfNode->Value() != _sdf->GetName() && + sdfNode->FirstChildElement(_sdf->GetName())) + { + elemXml = sdfNode->FirstChildElement(_sdf->GetName()); + } + + /* parse new sdf xml */ + if (!readXml(elemXml, _sdf)) + { + sdfwarn << "Unable to parse sdf element[" + << _sdf->GetName() << "]\n"; + return false; + } + } + else + { + // try to use the old deprecated parser + if (!sdfNode) + sdfdbg << "SDF has no element\n"; + else if (!sdfNode->Attribute("version")) + sdfdbg << " element has no version\n"; + else if (strcmp(sdfNode->Attribute("version"), + SDF::Version().c_str()) != 0) + sdfdbg << "SDF version [" + << sdfNode->Attribute("version") + << "] is not " << SDF::Version() << "\n"; + return false; + } + + return true; +} + +////////////////////////////////////////////////// +std::string getBestSupportedModelVersion(TiXmlElement *_modelXML, + std::string &_modelFileName) +{ + TiXmlElement *sdfXML = _modelXML->FirstChildElement("sdf"); + TiXmlElement *nameSearch = _modelXML->FirstChildElement("name"); + + // If a match is not found, use the latest version of the element + // that is not older than the SDF parser. + ignition::math::SemanticVersion sdfParserVersion(SDF_VERSION); + std::string bestVersionStr = "0.0"; + + TiXmlElement *sdfSearch = sdfXML; + while (sdfSearch) + { + if (sdfSearch->Attribute("version")) + { + auto version = std::string(sdfSearch->Attribute("version")); + ignition::math::SemanticVersion modelVersion(version); + ignition::math::SemanticVersion bestVersion(bestVersionStr); + if (modelVersion > bestVersion) + { + // this model is better than the previous one + if (modelVersion <= sdfParserVersion) + { + // the parser can read it + sdfXML = sdfSearch; + bestVersionStr = version; + } + else + { + sdfwarn << "Ignoring version " << version + << " for model " << nameSearch->GetText() + << " because is newer than this sdf parser" + << " (version " << SDF_VERSION << ")\n"; + } + } + } + sdfSearch = sdfSearch->NextSiblingElement("sdf"); + } + + if (!sdfXML || !sdfXML->GetText()) + { + sdferr << "Failure to detect an sdf tag in the model config file" + << " for model: " << nameSearch->GetText() << "\n"; + + _modelFileName = ""; + return ""; + } + + if (!sdfXML->Attribute("version")) + { + sdfwarn << "Can not find the XML attribute 'version'" + << " in sdf XML tag for model: " << nameSearch->GetText() << "." + << " Please specify the SDF protocol supported in the model" + << " configuration file. The first sdf tag in the config file" + << " will be used \n"; + } + + _modelFileName = sdfXML->GetText(); + return bestVersionStr; +} + +////////////////////////////////////////////////// +std::string getModelFilePath(const std::string &_modelDirPath) +{ + boost::filesystem::path configFilePath = _modelDirPath; + + /// \todo This hardcoded bit is very Gazebo centric. It should + /// be abstracted away, possible through a plugin to SDF. + if (boost::filesystem::exists(configFilePath / "model.config")) + { + configFilePath /= "model.config"; + } + else if (boost::filesystem::exists(configFilePath / "manifest.xml")) + { + sdfwarn << "The manifest.xml for a model is deprecated. " + << "Please rename configFile.xml to " + << "model.config" << ".\n"; + + configFilePath /= "manifest.xml"; + } + + TiXmlDocument configFileDoc; + if (!configFileDoc.LoadFile(configFilePath.string())) + { + sdferr << "Error parsing XML in file [" + << configFilePath.string() << "]: " + << configFileDoc.ErrorDesc() << '\n'; + return std::string(); + } + + TiXmlElement *modelXML = configFileDoc.FirstChildElement("model"); + + if (!modelXML) + { + sdferr << "No element in configFile[" << configFilePath << "]\n"; + return std::string(); + } + + std::string modelFileName; + if (getBestSupportedModelVersion(modelXML, modelFileName).empty()) + return std::string(); + + return _modelDirPath + "/" + modelFileName; +} + +////////////////////////////////////////////////// +bool readXml(TiXmlElement *_xml, ElementPtr _sdf) +{ + if (_sdf->GetRequired() == "-1") + { + sdfwarn << "SDF Element[" << _sdf->GetName() << "] is deprecated\n"; + return true; + } + + if (!_xml) + { + if (_sdf->GetRequired() == "1" || _sdf->GetRequired() =="+") + { + sdferr << "SDF Element<" << _sdf->GetName() << "> is missing\n"; + return false; + } + else + return true; + } + + if (_xml->GetText() != NULL && _sdf->GetValue()) + { + _sdf->GetValue()->SetFromString(_xml->GetText()); + } + + // check for nested sdf + std::string refSDFStr = _sdf->ReferenceSDF(); + if (!refSDFStr.empty()) + { + ElementPtr refSDF; + refSDF.reset(new Element); + std::string refFilename = refSDFStr + ".sdf"; + initFile(refFilename, refSDF); + _sdf->RemoveFromParent(); + _sdf->Copy(refSDF); + } + + TiXmlAttribute *attribute = _xml->FirstAttribute(); + + unsigned int i = 0; + + // Iterate over all the attributes defined in the give XML element + while (attribute) + { + // Find the matching attribute in SDF + for (i = 0; i < _sdf->GetAttributeCount(); ++i) + { + ParamPtr p = _sdf->GetAttribute(i); + if (p->GetKey() == attribute->Name()) + { + // Set the value of the SDF attribute + if (!p->SetFromString(attribute->ValueStr())) + { + sdferr << "Unable to read attribute[" << p->GetKey() << "]\n"; + return false; + } + break; + } + } + + if (i == _sdf->GetAttributeCount()) + { + sdfwarn << "XML Attribute[" << attribute->Name() + << "] in element[" << _xml->Value() + << "] not defined in SDF, ignoring.\n"; + } + + attribute = attribute->Next(); + } + + // Check that all required attributes have been set + for (i = 0; i < _sdf->GetAttributeCount(); ++i) + { + ParamPtr p = _sdf->GetAttribute(i); + if (p->GetRequired() && !p->GetSet()) + { + sdferr << "Required attribute[" << p->GetKey() + << "] in element[" << _xml->Value() << "] is not specified in SDF.\n"; + return false; + } + } + + if (_sdf->GetCopyChildren()) + { + copyChildren(_sdf, _xml); + } + else + { + std::string filename; + + // Iterate over all the child elements + TiXmlElement *elemXml = NULL; + for (elemXml = _xml->FirstChildElement(); elemXml; + elemXml = elemXml->NextSiblingElement()) + { + if (std::string("include") == elemXml->Value()) + { + std::string modelPath; + + if (elemXml->FirstChildElement("uri")) + { + std::string uri = elemXml->FirstChildElement("uri")->GetText(); + modelPath = sdf::findFile(uri, true, true); + + // Test the model path + if (modelPath.empty()) + { + sdferr << "Unable to find uri[" << uri << "]\n"; + + size_t modelFound = uri.find("model://"); + if ( modelFound != 0u) + { + sdferr << "Invalid uri[" << uri << "]. Should be model://" + << uri << "\n"; + } + continue; + } + else + { + boost::filesystem::path dir(modelPath); + if (!boost::filesystem::exists(dir) || + !boost::filesystem::is_directory(dir)) + { + sdferr << "Directory doesn't exist[" << modelPath << "]\n"; + continue; + } + } + + // Get the config.xml filename + filename = getModelFilePath(modelPath); + } + else + { + if (elemXml->Attribute("filename")) + { + sdferr << " is deprecated. Should be " + << "...Attribute("filename"), false); + } + else + { + sdferr << " element missing 'uri' attribute\n"; + continue; + } + } + + // NOTE: sdf::init is an expensive call. For performance reason, + // a new sdf pointer is created here by cloning a fresh sdf template + // pointer instead of calling init every iteration. + // SDFPtr includeSDF(new SDF); + // init(includeSDF); + static SDFPtr includeSDFTemplate; + if (!includeSDFTemplate) + { + includeSDFTemplate.reset(new SDF); + init(includeSDFTemplate); + } + SDFPtr includeSDF(new SDF); + includeSDF->Root(includeSDFTemplate->Root()->Clone()); + + if (!readFile(filename, includeSDF)) + { + sdferr << "Unable to read file[" << filename << "]\n"; + return false; + } + + if (elemXml->FirstChildElement("name")) + { + includeSDF->Root()->GetElement("model")->GetAttribute( + "name")->SetFromString( + elemXml->FirstChildElement("name")->GetText()); + } + + TiXmlElement *poseElemXml = elemXml->FirstChildElement("pose"); + if (poseElemXml) + { + sdf::ElementPtr poseElem = + includeSDF->Root()->GetElement("model")->GetElement("pose"); + + poseElem->GetValue()->SetFromString(poseElemXml->GetText()); + + const char *frame = poseElemXml->Attribute("frame"); + if (frame) + poseElem->GetAttribute("frame")->SetFromString(frame); + } + + if (elemXml->FirstChildElement("static")) + { + includeSDF->Root()->GetElement("model")->GetElement( + "static")->GetValue()->SetFromString( + elemXml->FirstChildElement("static")->GetText()); + } + + for (TiXmlElement *childElemXml = elemXml->FirstChildElement(); + childElemXml; childElemXml = childElemXml->NextSiblingElement()) + { + if (std::string("plugin") == childElemXml->Value()) + { + sdf::ElementPtr pluginElem; + pluginElem = includeSDF->Root()->GetElement( + "model")->AddElement("plugin"); + + if (!readXml(childElemXml, pluginElem)) + { + sdferr << "Error reading plugin element\n"; + return false; + } + } + } + + if (_sdf->GetName() == "model") + { + addNestedModel(_sdf, includeSDF->Root()); + } + else + { + includeSDF->Root()->GetFirstElement()->SetParent(_sdf); + _sdf->InsertElement(includeSDF->Root()->GetFirstElement()); + // TODO: This was used to store the included filename so that when + // a world is saved, the included model's SDF is not stored in the + // world file. This highlights the need to make model inclusion + // a core feature of SDF, and not a hack that that parser handles + // includeSDF->Root()->GetFirstElement()->SetInclude( + // elemXml->Attribute("filename")); + } + + continue; + } + + // Find the matching element in SDF + unsigned int descCounter = 0; + for (descCounter = 0; + descCounter != _sdf->GetElementDescriptionCount(); ++descCounter) + { + ElementPtr elemDesc = _sdf->GetElementDescription(descCounter); + if (elemDesc->GetName() == elemXml->Value()) + { + ElementPtr element = elemDesc->Clone(); + element->SetParent(_sdf); + if (readXml(elemXml, element)) + _sdf->InsertElement(element); + else + { + sdferr << "Error reading element <" << elemXml->Value() << ">\n"; + return false; + } + break; + } + } + + if (descCounter == _sdf->GetElementDescriptionCount()) + { + sdfwarn << "XML Element[" << elemXml->Value() + << "], child of element[" << _xml->Value() + << "] not defined in SDF. Ignoring[" << elemXml->Value() << "]. " + << "You may have an incorrect SDF file, or an sdformat version " + << "that doesn't support this element.\n"; + continue; + } + } + + // Check that all required elements have been set + unsigned int descCounter = 0; + for (descCounter = 0; + descCounter != _sdf->GetElementDescriptionCount(); ++descCounter) + { + ElementPtr elemDesc = _sdf->GetElementDescription(descCounter); + + if (elemDesc->GetRequired() == "1" || elemDesc->GetRequired() == "+") + { + if (!_sdf->HasElement(elemDesc->GetName())) + { + if (_sdf->GetName() == "joint" && + _sdf->Get("type") != "ball") + { + sdferr << "XML Missing required element[" << elemDesc->GetName() + << "], child of element[" << _sdf->GetName() << "]\n"; + return false; + } + else + { + // Add default element + _sdf->AddElement(elemDesc->GetName()); + } + } + } + } + } + + return true; +} + +///////////////////////////////////////////////// +void copyChildren(ElementPtr _sdf, TiXmlElement *_xml) +{ + // Iterate over all the child elements + TiXmlElement *elemXml = NULL; + for (elemXml = _xml->FirstChildElement(); elemXml; + elemXml = elemXml->NextSiblingElement()) + { + std::string elem_name = elemXml->ValueStr(); + + if (_sdf->HasElementDescription(elem_name)) + { + sdf::ElementPtr element = _sdf->AddElement(elem_name); + + // FIXME: copy attributes + for (TiXmlAttribute *attribute = elemXml->FirstAttribute(); + attribute; attribute = attribute->Next()) + { + element->GetAttribute(attribute->Name())->SetFromString( + attribute->ValueStr()); + } + + // copy value + std::string value = elemXml->GetText(); + if (!value.empty()) + element->GetValue()->SetFromString(value); + copyChildren(element, elemXml); + } + else + { + ElementPtr element(new Element); + element->SetParent(_sdf); + element->SetName(elem_name); + if (elemXml->GetText() != NULL) + element->AddValue("string", elemXml->GetText(), "1"); + + for (TiXmlAttribute *attribute = elemXml->FirstAttribute(); + attribute; attribute = attribute->Next()) + { + element->AddAttribute(attribute->Name(), "string", "", 1, ""); + element->GetAttribute(attribute->Name())->SetFromString( + attribute->ValueStr()); + } + + copyChildren(element, elemXml); + _sdf->InsertElement(element); + } + } +} + +///////////////////////////////////////////////// +void addNestedModel(ElementPtr _sdf, ElementPtr _includeSDF) +{ + ElementPtr modelPtr = _includeSDF->GetElement("model"); + ElementPtr elem = modelPtr->GetFirstElement(); + std::map replace; + + ignition::math::Pose3d modelPose = + modelPtr->Get("pose"); + + std::string modelName = modelPtr->Get("name"); + while (elem) + { + if (elem->GetName() == "link") + { + std::string elemName = elem->Get("name"); + std::string newName = modelName + "::" + elemName; + replace[elemName] = newName; + if (elem->HasElementDescription("pose")) + { + ignition::math::Pose3d offsetPose = + elem->Get("pose"); + ignition::math::Pose3d newPose = ignition::math::Pose3d( + modelPose.Pos() + + modelPose.Rot().RotateVector(offsetPose.Pos()), + modelPose.Rot() * offsetPose.Rot()); + elem->GetElement("pose")->Set(newPose); + } + } + else if (elem->GetName() == "joint") + { + // for joints, we need to + // prefix name like we did with links, and + std::string elemName = elem->Get("name"); + std::string newName = modelName + "::" + elemName; + replace[elemName] = newName; + // rotate the joint axis because they are model-global + if (elem->HasElement("axis")) + { + ElementPtr axisElem = elem->GetElement("axis"); + ignition::math::Vector3d newAxis = modelPose.Rot().RotateVector( + axisElem->Get("xyz")); + axisElem->GetElement("xyz")->Set(newAxis); + } + } + elem = elem->GetNextElement(); + } + + std::string str = _includeSDF->ToString(""); + for (std::map::iterator iter = replace.begin(); + iter != replace.end(); ++iter) + { + boost::replace_all(str, std::string("\"")+iter->first + "\"", + std::string("\"") + iter->second + "\""); + boost::replace_all(str, std::string("'")+iter->first + "'", + std::string("'") + iter->second + "'"); + boost::replace_all(str, std::string(">")+iter->first + "<", + std::string(">") + iter->second + "<"); + } + + _includeSDF->ClearElements(); + readString(str, _includeSDF); + + elem = _includeSDF->GetElement("model")->GetFirstElement(); + ElementPtr nextElem; + while (elem) + { + nextElem = elem->GetNextElement(); + + if (elem->GetName() != "pose") + { + elem->SetParent(_sdf); + _sdf->InsertElement(elem); + } + elem = nextElem; + } +} + +///////////////////////////////////////////////// +bool convertFile(const std::string &_filename, const std::string &_version, + SDFPtr _sdf) +{ + std::string filename = sdf::findFile(_filename); + + if (filename.empty()) + { + sdferr << "Error finding file [" << _filename << "].\n"; + return false; + } + + TiXmlDocument xmlDoc; + if (xmlDoc.LoadFile(filename)) + { + if (sdf::Converter::Convert(&xmlDoc, _version, true)) + { + return sdf::readDoc(&xmlDoc, _sdf, filename); + } + } + else + { + sdferr << "Error parsing file[" << filename << "]\n"; + } + + return false; +} + +///////////////////////////////////////////////// +bool convertString(const std::string &_sdfString, const std::string &_version, + SDFPtr _sdf) +{ + if (_sdfString.empty()) + { + sdferr << "SDF string is empty.\n"; + return false; + } + + TiXmlDocument xmlDoc; + xmlDoc.Parse(_sdfString.c_str()); + + if (!xmlDoc.Error()) + { + if (sdf::Converter::Convert(&xmlDoc, _version, true)) + { + return sdf::readDoc(&xmlDoc, _sdf, "data-string"); + } + } + else + { + sdferr << "Error parsing XML from string[" << _sdfString << "]\n"; + } + + return false; +} +} diff --git a/sdformat/src/parser_urdf.cc b/sdformat/src/parser_urdf.cc new file mode 100644 index 0000000..af41ee6 --- /dev/null +++ b/sdformat/src/parser_urdf.cc @@ -0,0 +1,3942 @@ +/* + * Copyright 2012 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#include +#include +#include +#include +#include +#include +#include + +#include "urdf_model/model.h" +#include "urdf_model/link.h" +#include "urdf_parser/urdf_parser.h" + +#include "sdf/SDFExtension.hh" +#include "sdf/parser_urdf.hh" +#include "sdf/sdf.hh" + +using namespace sdf; + +typedef boost::shared_ptr UrdfCollisionPtr; +typedef boost::shared_ptr UrdfVisualPtr; +typedef boost::shared_ptr UrdfLinkPtr; +typedef boost::shared_ptr ConstUrdfLinkPtr; +typedef std::shared_ptr TiXmlElementPtr; +typedef std::shared_ptr SDFExtensionPtr; +typedef std::map > + StringSDFExtensionPtrMap; + +/// create SDF geometry block based on URDF +StringSDFExtensionPtrMap g_extensions; +bool g_reduceFixedJoints; +bool g_enforceLimits; +std::string g_collisionExt = "_collision"; +std::string g_visualExt = "_visual"; +std::string g_lumpPrefix = "_fixed_joint_lump__"; +urdf::Pose g_initialRobotPose; +bool g_initialRobotPoseValid = false; +std::set g_fixedJointsTransformedInRevoluteJoints; +std::set g_fixedJointsTransformedInFixedJoints; + + +/// \brief parser xml string into urdf::Vector3 +/// \param[in] _key XML key where vector3 value might be +/// \param[in] _scale scalar scale for the vector3 +/// \return a urdf::Vector3 +urdf::Vector3 ParseVector3(TiXmlNode* _key, double _scale = 1.0); +urdf::Vector3 ParseVector3(const std::string &_str, double _scale = 1.0); + +/// insert extensions into collision geoms +void InsertSDFExtensionCollision(TiXmlElement *_elem, + const std::string &_linkName); + +/// insert extensions into model +void InsertSDFExtensionRobot(TiXmlElement *_elem); + +/// insert extensions into visuals +void InsertSDFExtensionVisual(TiXmlElement *_elem, + const std::string &_linkName); + + +/// insert extensions into joints +void InsertSDFExtensionJoint(TiXmlElement *_elem, + const std::string &_jointName); + +/// reduced fixed joints: check if a fixed joint should be lumped +/// checking both the joint type and if disabledFixedJointLumping +/// option is set +bool FixedJointShouldBeReduced(boost::shared_ptr _jnt); + +/// reduced fixed joints: apply transform reduction for ray sensors +/// in extensions when doing fixed joint reduction +void ReduceSDFExtensionSensorTransformReduction( + std::vector::iterator _blobIt, + ignition::math::Pose3d _reductionTransform); + +/// reduced fixed joints: apply transform reduction for projectors in +/// extensions when doing fixed joint reduction +void ReduceSDFExtensionProjectorTransformReduction( + std::vector::iterator _blobIt, + ignition::math::Pose3d _reductionTransform); + + +/// reduced fixed joints: apply transform reduction to extensions +/// when doing fixed joint reduction +void ReduceSDFExtensionsTransform(SDFExtensionPtr _ge); + +/// reduce fixed joints: lump joints to parent link +void ReduceJointsToParent(UrdfLinkPtr _link); + +/// reduce fixed joints: lump collisions to parent link +void ReduceCollisionsToParent(UrdfLinkPtr _link); + +/// reduce fixed joints: lump visuals to parent link +void ReduceVisualsToParent(UrdfLinkPtr _link); + +/// reduce fixed joints: lump inertial to parent link +void ReduceInertialToParent(UrdfLinkPtr /*_link*/); + +/// create SDF Collision block based on URDF +void CreateCollision(TiXmlElement* _elem, ConstUrdfLinkPtr _link, + UrdfCollisionPtr _collision, + const std::string &_oldLinkName = std::string("")); + +/// create SDF Visual block based on URDF +void CreateVisual(TiXmlElement *_elem, ConstUrdfLinkPtr _link, + UrdfVisualPtr _visual, const std::string &_oldLinkName = std::string("")); + +/// create SDF Joint block based on URDF +void CreateJoint(TiXmlElement *_root, ConstUrdfLinkPtr _link, + ignition::math::Pose3d &_currentTransform); + +/// insert extensions into links +void InsertSDFExtensionLink(TiXmlElement *_elem, const std::string &_linkName); + +/// create visual blocks from urdf visuals +void CreateVisuals(TiXmlElement* _elem, ConstUrdfLinkPtr _link); + +/// create collision blocks from urdf collisions +void CreateCollisions(TiXmlElement* _elem, ConstUrdfLinkPtr _link); + +/// create SDF Inertial block based on URDF +void CreateInertial(TiXmlElement *_elem, ConstUrdfLinkPtr _link); + +/// append transform (pose) to the end of the xml element +void AddTransform(TiXmlElement *_elem, const ignition::math::Pose3d &_transform); + +/// create SDF from URDF link +void CreateSDF(TiXmlElement *_root, ConstUrdfLinkPtr _link, + const ignition::math::Pose3d &_transform); + +/// create SDF Link block based on URDF +void CreateLink(TiXmlElement *_root, ConstUrdfLinkPtr _link, + ignition::math::Pose3d &_currentTransform); + + +/// print collision groups for debugging purposes +void PrintCollisionGroups(UrdfLinkPtr _link); + +/// reduced fixed joints: apply appropriate frame updates in joint +/// inside urdf extensions when doing fixed joint reduction +void ReduceSDFExtensionJointFrameReplace( + std::vector::iterator _blobIt, + UrdfLinkPtr _link); + +/// reduced fixed joints: apply appropriate frame updates in gripper +/// inside urdf extensions when doing fixed joint reduction +void ReduceSDFExtensionGripperFrameReplace( + std::vector::iterator _blobIt, + UrdfLinkPtr _link); + +/// reduced fixed joints: apply appropriate frame updates in projector +/// inside urdf extensions when doing fixed joint reduction +void ReduceSDFExtensionProjectorFrameReplace( + std::vector::iterator _blobIt, + UrdfLinkPtr _link); + +/// reduced fixed joints: apply appropriate frame updates in plugins +/// inside urdf extensions when doing fixed joint reduction +void ReduceSDFExtensionPluginFrameReplace( + std::vector::iterator _blobIt, + UrdfLinkPtr _link, const std::string &_pluginName, + const std::string &_elementName, + ignition::math::Pose3d _reductionTransform); + +/// reduced fixed joints: apply appropriate frame updates in urdf +/// extensions when doing fixed joint reduction +void ReduceSDFExtensionContactSensorFrameReplace( + std::vector::iterator _blobIt, + UrdfLinkPtr _link); + +/// \brief reduced fixed joints: apply appropriate updates to urdf +/// extensions when doing fixed joint reduction +/// +/// Take the link's existing list of gazebo extensions, transfer them +/// into parent link. Along the way, update local transforms by adding +/// the additional transform to parent. Also, look through all +/// referenced link names with plugins and update references to current +/// link to the parent link. (ReduceSDFExtensionFrameReplace()) +/// +/// \param[in] _link pointer to urdf link, its extensions will be reduced +void ReduceSDFExtensionToParent(UrdfLinkPtr _link); + +/// reduced fixed joints: apply appropriate frame updates +/// in urdf extensions when doing fixed joint reduction +void ReduceSDFExtensionFrameReplace(SDFExtensionPtr _ge, UrdfLinkPtr _link); + + +/// get value from pair and return it as string +std::string GetKeyValueAsString(TiXmlElement* _elem); + + +/// \brief append key value pair to the end of the xml element +/// \param[in] _elem pointer to xml element +/// \param[in] _key string containing key to add to xml element +/// \param[in] _value string containing value for the key added +void AddKeyValue(TiXmlElement *_elem, const std::string &_key, + const std::string &_value); + +/// \brief convert values to string +/// \param[in] _count number of values in _values array +/// \param[in] _values array of double values +/// \return a string +std::string Values2str(unsigned int _count, const double *_values); + + +void CreateGeometry(TiXmlElement* _elem, + boost::shared_ptr _geometry); + +std::string GetGeometryBoundingBox(boost::shared_ptr _geometry, + double *_sizeVals); + +ignition::math::Pose3d inverseTransformToParentFrame( + ignition::math::Pose3d _transformInLinkFrame, + urdf::Pose _parentToLinkTransform); + +/// reduced fixed joints: transform to parent frame +urdf::Pose TransformToParentFrame(urdf::Pose _transformInLinkFrame, + urdf::Pose _parentToLinkTransform); + +/// reduced fixed joints: transform to parent frame +ignition::math::Pose3d TransformToParentFrame( + ignition::math::Pose3d _transformInLinkFrame, + urdf::Pose _parentToLinkTransform); + +/// reduced fixed joints: transform to parent frame +ignition::math::Pose3d TransformToParentFrame( + ignition::math::Pose3d _transformInLinkFrame, + ignition::math::Pose3d _parentToLinkTransform); + +/// reduced fixed joints: utility to copy between urdf::Pose and +/// math::Pose +ignition::math::Pose3d CopyPose(urdf::Pose _pose); + +/// reduced fixed joints: utility to copy between urdf::Pose and +/// math::Pose +urdf::Pose CopyPose(ignition::math::Pose3d _pose); + +///////////////////////////////////////////////// +urdf::Vector3 ParseVector3(const std::string &_str, double _scale) +{ + std::vector pieces; + std::vector vals; + + boost::split(pieces, _str, boost::is_any_of(" ")); + for (unsigned int i = 0; i < pieces.size(); ++i) + { + if (pieces[i] != "") + { + try + { + vals.push_back(_scale + * boost::lexical_cast(pieces[i].c_str())); + } + catch(boost::bad_lexical_cast &) + { + sdferr << "xml key [" << _str + << "][" << i << "] value [" << pieces[i] + << "] is not a valid double from a 3-tuple\n"; + return urdf::Vector3(0, 0, 0); + } + } + } + + if (vals.size() == 3) + return urdf::Vector3(vals[0], vals[1], vals[2]); + else + return urdf::Vector3(0, 0, 0); +} + +///////////////////////////////////////////////// +urdf::Vector3 ParseVector3(TiXmlNode *_key, double _scale) +{ + if (_key != NULL) + { + TiXmlElement *key = _key->ToElement(); + if (key != NULL) + { + return ParseVector3(GetKeyValueAsString(key), _scale); + } + sdferr << "key[" << _key->Value() << "] does not contain a Vector3\n"; + } + else + { + sdferr << "Pointer to XML node _key is NULL\n"; + } + + return urdf::Vector3(0, 0, 0); +} + +///////////////////////////////////////////////// +/// \brief convert Vector3 to string +/// \param[in] _vector a urdf::Vector3 +/// \return a string +std::string Vector32Str(const urdf::Vector3 _vector) +{ + std::stringstream ss; + ss << _vector.x; + ss << " "; + ss << _vector.y; + ss << " "; + ss << _vector.z; + return ss.str(); +} + +//////////////////////////////////////////////////////////////////////////////// +/// \brief Check and add collision to parent link +/// \param[in] _parentLink destination for _collision +/// \param[in] _name urdfdom 0.3+: urdf collision group name with lumped +/// collision info (see ReduceCollisionsToParent). +/// urdfdom 0.2: collision name with lumped +/// collision info (see ReduceCollisionsToParent). +/// \param[in] _collision move this collision to _parentLink +//////////////////////////////////////////////////////////////// +// IMPORTANT NOTE: URDF_GE_OP3 +// IMPORTANT NOTE: on change from urdfdom_headers 0.2.x to 0.3.x +//////////////////////////////////////////////////////////////// +// In urdfdom_headers 0.2.x, there are group names for +// visuals and collisions in Link class: +// std::map > > +// > visual_groups; +// std::map > > +// > collision_groups; +// and we have Visual::group_name and +// Collision::group_name +// In urdfdom_headers 0.3.x, +// - Link::visual_groups and Link::collision_groups are removed +// - method Link::getVisuals(group_name) has been removed +// - method Link::getCollisions(group_name) has been removed +// - Visual::group_name renamed to Visual::name +// - Collision::group_name renamed to Collision::name +//////////////////////////////////////////////////////////////// +void ReduceCollisionToParent(UrdfLinkPtr _parentLink, + const std::string &_name, + UrdfCollisionPtr _collision) +{ +#ifndef URDF_GE_0P3 + boost::shared_ptr > cols; + cols = _parentLink->getCollisions(_name); + + if (!cols) + { + // group does not exist, create one and add to map + cols.reset(new std::vector); + // new group name, create add vector to map and add Collision to the vector + _parentLink->collision_groups.insert(make_pair(_name, cols)); + } + + // group exists, add Collision to the vector in the map + std::vector::iterator colIt = + find(cols->begin(), cols->end(), _collision); + if (colIt != cols->end()) + sdfwarn << "attempted to add collision to link [" + << _parentLink->name + << "], but it already exists under group [" + << _name << "]\n"; + else + cols->push_back(_collision); +#else + // added a check to see if _collision already exist in + // _parentLink::collision_array if not, add it. + _collision->name = _name; + std::vector::iterator collisionIt = + find(_parentLink->collision_array.begin(), + _parentLink->collision_array.end(), + _collision); + if (collisionIt != _parentLink->collision_array.end()) + { + sdfwarn << "attempted to add collision [" << _collision->name + << "] to link [" + << _parentLink->name + << "], but it already exists in collision_array under name [" + << (*collisionIt)->name << "]\n"; + } + else + { + _parentLink->collision_array.push_back(_collision); + } +#endif +} + +//////////////////////////////////////////////////////////////////////////////// +/// \brief Check and add visual to parent link +/// \param[in] _parentLink destination for _visual +/// \param[in] _name urdfdom 0.3+: urdf visual group name with lumped +/// visual info (see ReduceVisualsToParent). +/// urdfdom 0.2: visual name with lumped +/// visual info (see ReduceVisualsToParent). +/// \param[in] _visual move this visual to _parentLink +//////////////////////////////////////////////////////////////// +// IMPORTANT NOTE: URDF_GE_OP3 +// IMPORTANT NOTE: on change from urdfdom_headers 0.2.x to 0.3.x +//////////////////////////////////////////////////////////////// +// In urdfdom_headers 0.2.x, there are group names for +// visuals and collisions in Link class: +// std::map > > +// > visual_groups; +// std::map > > +// > collision_groups; +// and we have Visual::group_name and +// Collision::group_name +// In urdfdom_headers 0.3.x, +// - Link::visual_groups and Link::collision_groups are removed +// - method Link::getVisuals(group_name) has been removed +// - method Link::getCollisions(group_name) has been removed +// - Visual::group_name renamed to Visual::name +// - Collision::group_name renamed to Collision::name +//////////////////////////////////////////////////////////////// +void ReduceVisualToParent(UrdfLinkPtr _parentLink, + const std::string &_name, + UrdfVisualPtr _visual) +{ +#ifndef URDF_GE_0P3 + boost::shared_ptr > viss; + viss = _parentLink->getVisuals(_name); + + if (!viss) + { + // group does not exist, create one and add to map + viss.reset(new std::vector); + // new group name, create vector, add vector to map and + // add Visual to the vector + _parentLink->visual_groups.insert(make_pair(_name, viss)); + sdfdbg << "successfully added a new visual group name [" + << _name << "]\n"; + } + + // group exists, add Visual to the vector in the map if it's not there + std::vector::iterator visIt + = find(viss->begin(), viss->end(), _visual); + if (visIt != viss->end()) + sdfwarn << "attempted to add visual to link [" + << _parentLink->name + << "], but it already exists under group [" + << _name << "]\n"; + else + viss->push_back(_visual); +#else + // added a check to see if _visual already exist in + // _parentLink::visual_array if not, add it. + _visual->name = _name; + std::vector::iterator visualIt = + find(_parentLink->visual_array.begin(), + _parentLink->visual_array.end(), + _visual); + if (visualIt != _parentLink->visual_array.end()) + { + sdfwarn << "attempted to add visual [" << _visual->name + << "] to link [" + << _parentLink->name + << "], but it already exists in visual_array under name [" + << (*visualIt)->name << "]\n"; + } + else + { + _parentLink->visual_array.push_back(_visual); + } +#endif +} + +//////////////////////////////////////////////////////////////////////////////// +/// reduce fixed joints by lumping inertial, visual and +// collision elements of the child link into the parent link +void ReduceFixedJoints(TiXmlElement *_root, UrdfLinkPtr _link) +{ + // if child is attached to self by fixed _link first go up the tree, + // check it's children recursively + for (unsigned int i = 0 ; i < _link->child_links.size() ; ++i) + if (FixedJointShouldBeReduced(_link->child_links[i]->parent_joint)) + ReduceFixedJoints(_root, _link->child_links[i]); + + // reduce this _link's stuff up the tree to parent but skip first joint + // if it's the world + if (_link->getParent() && _link->getParent()->name != "world" && + _link->parent_joint && FixedJointShouldBeReduced(_link->parent_joint) ) + { + sdfdbg << "Fixed Joint Reduction: extension lumping from [" + << _link->name << "] to [" << _link->getParent()->name << "]\n"; + + // lump sdf extensions to parent, (give them new reference _link names) + ReduceSDFExtensionToParent(_link); + + // reduce _link elements to parent + ReduceInertialToParent(_link); + ReduceVisualsToParent(_link); + ReduceCollisionsToParent(_link); + ReduceJointsToParent(_link); + } + + // continue down the tree for non-fixed joints + for (unsigned int i = 0 ; i < _link->child_links.size() ; ++i) + if (!FixedJointShouldBeReduced(_link->child_links[i]->parent_joint)) + ReduceFixedJoints(_root, _link->child_links[i]); +} + +// ODE dMatrix +typedef double dMatrix3[4*3]; +typedef double dVector3[4]; +#define _R(i,j) R[(i)*4+(j)] +#define _I(i,j) I[(i)*4+(j)] +#define dRecip(x) ((1.0f/(x))) + +struct dMass; +void dMassSetZero (dMass *m); +void dMassSetParameters (dMass *, double themass, + double cgx, double cgy, double cgz, + double I11, double I22, double I33, + double I12, double I13, double I23); + +struct dMass +{ + double mass; + dVector3 c; + dMatrix3 I; + + dMass() + { dMassSetZero (this); } + + void setZero() + { dMassSetZero (this); } + + void setParameters (double themass, double cgx, double cgy, double cgz, + double I11, double I22, double I33, + double I12, double I13, double I23) + { dMassSetParameters (this,themass,cgx,cgy,cgz,I11,I22,I33,I12,I13,I23); } +}; + +void dSetZero (double *a, int n) +{ + // dAASSERT (a && n >= 0); + double *acurr = a; + int ncurr = n; + while (ncurr > 0) + { + *(acurr++) = 0; + --ncurr; + } +} + +void dMassSetZero (dMass *m) +{ + // dAASSERT (m); + m->mass = 0.0; + dSetZero(m->c, sizeof(m->c) / sizeof(double)); + dSetZero(m->I, sizeof(m->I) / sizeof(double)); +} + + +void dMassSetParameters (dMass *m, double themass, + double cgx, double cgy, double cgz, + double I11, double I22, double I33, + double I12, double I13, double I23) +{ + // dAASSERT (m); + dMassSetZero (m); + m->mass = themass; + m->c[0] = cgx; + m->c[1] = cgy; + m->c[2] = cgz; + m->_I(0,0) = I11; + m->_I(1,1) = I22; + m->_I(2,2) = I33; + m->_I(0,1) = I12; + m->_I(0,2) = I13; + m->_I(1,2) = I23; + m->_I(1,0) = I12; + m->_I(2,0) = I13; + m->_I(2,1) = I23; + // dMassCheck (m); +} + +void dRFromEulerAngles (dMatrix3 R, double phi, double theta, double psi) +{ + double sphi,cphi,stheta,ctheta,spsi,cpsi; + // dAASSERT (R); + sphi = sin(phi); + cphi = cos(phi); + stheta = sin(theta); + ctheta = cos(theta); + spsi = sin(psi); + cpsi = cos(psi); + _R(0,0) = cpsi*ctheta; + _R(0,1) = spsi*ctheta; + _R(0,2) =-stheta; + _R(0,3) = 0.0; + _R(1,0) = cpsi*stheta*sphi - spsi*cphi; + _R(1,1) = spsi*stheta*sphi + cpsi*cphi; + _R(1,2) = ctheta*sphi; + _R(1,3) = 0.0; + _R(2,0) = cpsi*stheta*cphi + spsi*sphi; + _R(2,1) = spsi*stheta*cphi - cpsi*sphi; + _R(2,2) = ctheta*cphi; + _R(2,3) = 0.0; +} + +double _dCalcVectorDot3(const double *a, const double *b, unsigned step_a, +unsigned step_b) +{ + return a[0] * b[0] + a[step_a] * b[step_b] + a[2 * step_a] * b[2 * step_b]; +} + +double dCalcVectorDot3 (const double *a, const double *b) +{ + return _dCalcVectorDot3(a,b,1,1); +} + +double dCalcVectorDot3_41 (const double *a, const double *b) +{ + return _dCalcVectorDot3(a,b,4,1); +} + +void dMultiply0_331(double *res, const double *a, const double *b) +{ + double res_0, res_1, res_2; + res_0 = dCalcVectorDot3(a, b); + res_1 = dCalcVectorDot3(a + 4, b); + res_2 = dCalcVectorDot3(a + 8, b); + res[0] = res_0; res[1] = res_1; res[2] = res_2; +} + +void dMultiply1_331(double *res, const double *a, const double *b) +{ + double res_0, res_1, res_2; + res_0 = dCalcVectorDot3_41(a, b); + res_1 = dCalcVectorDot3_41(a + 1, b); + res_2 = dCalcVectorDot3_41(a + 2, b); + res[0] = res_0; res[1] = res_1; res[2] = res_2; +} + +void dMultiply0_133(double *res, const double *a, const double *b) +{ + dMultiply1_331(res, b, a); +} + +void dMultiply0_333(double *res, const double *a, const double *b) +{ + dMultiply0_133(res + 0, a + 0, b); + dMultiply0_133(res + 4, a + 4, b); + dMultiply0_133(res + 8, a + 8, b); +} + +void dMultiply2_333(double *res, const double *a, const double *b) +{ + dMultiply0_331(res + 0, b, a + 0); + dMultiply0_331(res + 4, b, a + 4); + dMultiply0_331(res + 8, b, a + 8); +} + +void dMassRotate (dMass *m, const dMatrix3 R) +{ + // if the body is rotated by `R' relative to its point of reference, + // the new inertia about the point of reference is: + // + // R * I * R' + // + // where I is the old inertia. + + dMatrix3 t1; + double t2[3]; + + // dAASSERT (m); + + // rotate inertia matrix + dMultiply2_333 (t1,m->I,R); + dMultiply0_333 (m->I,R,t1); + + // ensure perfect symmetry + m->_I(1,0) = m->_I(0,1); + m->_I(2,0) = m->_I(0,2); + m->_I(2,1) = m->_I(1,2); + + // rotate center of mass + dMultiply0_331 (t2,R,m->c); + m->c[0] = t2[0]; + m->c[1] = t2[1]; + m->c[2] = t2[2]; +} + +void dSetCrossMatrixPlus(double *res, const double *a, unsigned skip) +{ + const double a_0 = a[0], a_1 = a[1], a_2 = a[2]; + res[1] = -a_2; + res[2] = +a_1; + res[skip+0] = +a_2; + res[skip+2] = -a_0; + res[2*skip+0] = -a_1; + res[2*skip+1] = +a_0; +} + +void dMassTranslate (dMass *m, double x, double y, double z) +{ + // if the body is translated by `a' relative to its point of reference, + // the new inertia about the point of reference is: + // + // I + mass*(crossmat(c)^2 - crossmat(c+a)^2) + // + // where c is the existing center of mass and I is the old inertia. + + int i,j; + dMatrix3 ahat,chat,t1,t2; + double a[3]; + + // dAASSERT (m); + + // adjust inertia matrix + dSetZero (chat,12); + dSetCrossMatrixPlus (chat,m->c,4); + a[0] = x + m->c[0]; + a[1] = y + m->c[1]; + a[2] = z + m->c[2]; + dSetZero (ahat,12); + dSetCrossMatrixPlus (ahat,a,4); + dMultiply0_333 (t1,ahat,ahat); + dMultiply0_333 (t2,chat,chat); + for (i=0; i<3; i++) for (j=0; j<3; j++) + m->_I(i,j) += m->mass * (t2[i*4+j]-t1[i*4+j]); + + // ensure perfect symmetry + m->_I(1,0) = m->_I(0,1); + m->_I(2,0) = m->_I(0,2); + m->_I(2,1) = m->_I(1,2); + + // adjust center of mass + m->c[0] += x; + m->c[1] += y; + m->c[2] += z; +} + +void dMassAdd (dMass *a, const dMass *b) +{ + int i; + double denom = dRecip (a->mass + b->mass); + for (i=0; i<3; i++) a->c[i] = (a->c[i]*a->mass + b->c[i]*b->mass)*denom; + a->mass += b->mass; + for (i=0; i<12; i++) a->I[i] += b->I[i]; +} + +///////////////////////////////////////////////// +/// print mass for link for debugging +void PrintMass(const std::string &_linkName, const dMass &_mass) +{ + sdfdbg << "LINK NAME: [" << _linkName << "] from dMass\n"; + sdfdbg << " MASS: [" << _mass.mass << "]\n"; + sdfdbg << " CG: [" << _mass.c[0] << ", " << _mass.c[1] << ", " + << _mass.c[2] << "]\n"; + sdfdbg << " I: [" << _mass.I[0] << ", " << _mass.I[1] << ", " + << _mass.I[2] << "]\n"; + sdfdbg << " [" << _mass.I[4] << ", " << _mass.I[5] << ", " + << _mass.I[6] << "]\n"; + sdfdbg << " [" << _mass.I[8] << ", " << _mass.I[9] << ", " + << _mass.I[10] << "]\n"; +} + +///////////////////////////////////////////////// +/// print mass for link for debugging +void PrintMass(const UrdfLinkPtr _link) +{ + sdfdbg << "LINK NAME: [" << _link->name << "] from dMass\n"; + sdfdbg << " MASS: [" << _link->inertial->mass << "]\n"; + sdfdbg << " CG: [" << _link->inertial->origin.position.x << ", " + << _link->inertial->origin.position.y << ", " + << _link->inertial->origin.position.z << "]\n"; + sdfdbg << " I: [" << _link->inertial->ixx << ", " + << _link->inertial->ixy << ", " + << _link->inertial->ixz << "]\n"; + sdfdbg << " [" << _link->inertial->ixy << ", " + << _link->inertial->iyy << ", " + << _link->inertial->iyz << "]\n"; + sdfdbg << " [" << _link->inertial->ixz << ", " + << _link->inertial->iyz << ", " + << _link->inertial->izz << "]\n"; +} + +///////////////////////////////////////////////// +/// reduce fixed joints: lump inertial to parent link +void ReduceInertialToParent(UrdfLinkPtr _link) +{ + // now lump all contents of this _link to parent + if (_link->inertial) + { + dMatrix3 R; + double phi, theta, psi; + + // get parent mass (in parent link cg frame) + dMass parentMass; + + if (!_link->getParent()->inertial) + _link->getParent()->inertial.reset(new urdf::Inertial); + + dMassSetParameters(&parentMass, _link->getParent()->inertial->mass, + 0, 0, 0, + _link->getParent()->inertial->ixx, _link->getParent()->inertial->iyy, + _link->getParent()->inertial->izz, _link->getParent()->inertial->ixy, + _link->getParent()->inertial->ixz, _link->getParent()->inertial->iyz); + + // transform parent inertia to parent link origin + _link->getParent()->inertial->origin.rotation.getRPY(phi, theta, psi); + dRFromEulerAngles(R, -phi, 0, 0); + dMassRotate(&parentMass, R); + dRFromEulerAngles(R, 0, -theta, 0); + dMassRotate(&parentMass, R); + dRFromEulerAngles(R, 0, 0, -psi); + dMassRotate(&parentMass, R); + + // un-translate link mass from cg(inertial frame) into link frame + dMassTranslate(&parentMass, + _link->getParent()->inertial->origin.position.x, + _link->getParent()->inertial->origin.position.y, + _link->getParent()->inertial->origin.position.z); + + PrintMass("parent: " + _link->getParent()->name, parentMass); + // PrintMass(_link->getParent()); + + ////////////////////////////////////////////// + // // + // create a_link mass (in _link's cg frame) // + // // + ////////////////////////////////////////////// + dMass linkMass; + dMassSetParameters(&linkMass, _link->inertial->mass, + 0, 0, 0, + _link->inertial->ixx, _link->inertial->iyy, _link->inertial->izz, + _link->inertial->ixy, _link->inertial->ixz, _link->inertial->iyz); + + PrintMass("link : " + _link->name, linkMass); + + //////////////////////////////////////////// + // // + // from cg (inertial frame) to link frame // + // // + //////////////////////////////////////////// + + // Un-rotate _link mass from cg(inertial frame) into link frame + _link->inertial->origin.rotation.getRPY(phi, theta, psi); + dRFromEulerAngles(R, -phi, 0, 0); + dMassRotate(&linkMass, R); + dRFromEulerAngles(R, 0, -theta, 0); + dMassRotate(&linkMass, R); + dRFromEulerAngles(R, 0, 0, -psi); + dMassRotate(&linkMass, R); + + // un-translate link mass from cg(inertial frame) into link frame + dMassTranslate(&linkMass, + _link->inertial->origin.position.x, + _link->inertial->origin.position.y, + _link->inertial->origin.position.z); + + //////////////////////////////////////////// + // // + // from link frame to parent link frame // + // // + //////////////////////////////////////////// + + // un-rotate _link mass into parent link frame + _link->parent_joint->parent_to_joint_origin_transform.rotation.getRPY( + phi, theta, psi); + dRFromEulerAngles(R, -phi, 0, 0); + dMassRotate(&linkMass, R); + dRFromEulerAngles(R, 0, -theta, 0); + dMassRotate(&linkMass, R); + dRFromEulerAngles(R, 0, 0, -psi); + dMassRotate(&linkMass, R); + + // un-translate _link mass into parent link frame + dMassTranslate(&linkMass, + _link->parent_joint->parent_to_joint_origin_transform.position.x, + _link->parent_joint->parent_to_joint_origin_transform.position.y, + _link->parent_joint->parent_to_joint_origin_transform.position.z); + + PrintMass("link in parent link: " + _link->name, linkMass); + + // + // now linkMass is in the parent frame, add linkMass to parentMass + // new parentMass should be combined inertia, + // centered at parent link inertial frame. + // + + dMassAdd(&parentMass, &linkMass); + + PrintMass("combined: " + _link->getParent()->name, parentMass); + + // + // Set new combined inertia in parent link frame into parent link urdf + // + + // save combined mass + _link->getParent()->inertial->mass = parentMass.mass; + + // save CoG location + _link->getParent()->inertial->origin.position.x = parentMass.c[0]; + _link->getParent()->inertial->origin.position.y = parentMass.c[1]; + _link->getParent()->inertial->origin.position.z = parentMass.c[2]; + + // get MOI at new CoG location + dMassTranslate(&parentMass, + -_link->getParent()->inertial->origin.position.x, + -_link->getParent()->inertial->origin.position.y, + -_link->getParent()->inertial->origin.position.z); + + // rotate MOI at new CoG location + _link->getParent()->inertial->origin.rotation.getRPY(phi, theta, psi); + dRFromEulerAngles(R, phi, theta, psi); + dMassRotate(&parentMass, R); + + // save new combined MOI + _link->getParent()->inertial->ixx = parentMass.I[0+4*0]; + _link->getParent()->inertial->iyy = parentMass.I[1+4*1]; + _link->getParent()->inertial->izz = parentMass.I[2+4*2]; + _link->getParent()->inertial->ixy = parentMass.I[0+4*1]; + _link->getParent()->inertial->ixz = parentMass.I[0+4*2]; + _link->getParent()->inertial->iyz = parentMass.I[1+4*2]; + + // final urdf inertia check + PrintMass(_link->getParent()); + } +} + +///////////////////////////////////////////////// +/// \brief reduce fixed joints: lump visuals to parent link +/// \param[in] _link take all visuals from _link and lump/move them +/// to the parent link (_link->getParentLink()). +void ReduceVisualsToParent(UrdfLinkPtr _link) +{ + // lump all visuals of _link to _link->getParent(). + // modify visual name (urdf 0.3.x) or + // visual group name (urdf 0.2.x) + // to indicate that it was lumped (fixed joint reduced) + // from another descendant link connected by a fixed joint. + // + // Algorithm for generating new name (or group name) is: + // original name + g_lumpPrefix+original link name (urdf 0.3.x) + // original group name + g_lumpPrefix+original link name (urdf 0.2.x) + // The purpose is to track where this visual came from + // (original parent link name before lumping/reducing). +#ifndef URDF_GE_0P3 + for (std::map > >::iterator + visualsIt = _link->visual_groups.begin(); + visualsIt != _link->visual_groups.end(); ++visualsIt) + { + if (visualsIt->first.find(g_lumpPrefix) == 0) + { + // it's a previously lumped mesh, re-lump under same _groupName + std::string lumpGroupName = visualsIt->first; + sdfdbg << "re-lumping group name [" << lumpGroupName + << "] to link [" << _link->getParent()->name << "]\n"; + for (std::vector::iterator + visualIt = visualsIt->second->begin(); + visualIt != visualsIt->second->end(); ++visualIt) + { + // transform visual origin from _link frame to parent link + // frame before adding to parent + (*visualIt)->origin = TransformToParentFrame((*visualIt)->origin, + _link->parent_joint->parent_to_joint_origin_transform); + // add the modified visual to parent + ReduceVisualToParent(_link->getParent(), lumpGroupName, + *visualIt); + } + } + else + { + // default and any other groups meshes + std::string lumpGroupName = g_lumpPrefix+_link->name; + sdfdbg << "adding modified lump group name [" << lumpGroupName + << "] to link [" << _link->getParent()->name << "].\n"; + for (std::vector::iterator + visualIt = visualsIt->second->begin(); + visualIt != visualsIt->second->end(); ++visualIt) + { + // transform visual origin from _link frame to + // parent link frame before adding to parent + (*visualIt)->origin = TransformToParentFrame((*visualIt)->origin, + _link->parent_joint->parent_to_joint_origin_transform); + // add the modified visual to parent + ReduceVisualToParent(_link->getParent(), lumpGroupName, + *visualIt); + } + } + } +#else + for (std::vector::iterator + visualIt = _link->visual_array.begin(); + visualIt != _link->visual_array.end(); ++visualIt) + { + // 20151116: changelog for pull request #235 + std::string newVisualName; + std::size_t lumpIndex = (*visualIt)->name.find(g_lumpPrefix); + if (lumpIndex != std::string::npos) + { + newVisualName = (*visualIt)->name; + sdfdbg << "re-lumping visual [" << (*visualIt)->name + << "] for link [" << _link->name + << "] to parent [" << _link->getParent()->name + << "] with name [" << newVisualName << "]\n"; + } + else + { + if ((*visualIt)->name.empty()) + { + newVisualName = _link->name; + } + else + { + newVisualName = (*visualIt)->name; + } + sdfdbg << "lumping visual [" << (*visualIt)->name + << "] for link [" << _link->name + << "] to parent [" << _link->getParent()->name + << "] with name [" << newVisualName << "]\n"; + } + + // transform visual origin from _link frame to + // parent link frame before adding to parent + (*visualIt)->origin = TransformToParentFrame( + (*visualIt)->origin, + _link->parent_joint->parent_to_joint_origin_transform); + + // add the modified visual to parent + ReduceVisualToParent(_link->getParent(), newVisualName, + *visualIt); + } +#endif +} + +///////////////////////////////////////////////// +/// \brief reduce fixed joints: lump collisions to parent link +/// \param[in] _link take all collisions from _link and lump/move them +/// to the parent link (_link->getParentLink()). +void ReduceCollisionsToParent(UrdfLinkPtr _link) +{ + // lump all collisions of _link to _link->getParent(). + // modify collision name (urdf 0.3.x) or + // collision group name (urdf 0.2.x) + // to indicate that it was lumped (fixed joint reduced) + // from another descendant link connected by a fixed joint. + // + // Algorithm for generating new name (or group name) is: + // original name + g_lumpPrefix+original link name (urdf 0.3.x) + // original group name + g_lumpPrefix+original link name (urdf 0.2.x) + // The purpose is to track where this collision came from + // (original parent link name before lumping/reducing). +#ifndef URDF_GE_0P3 + for (std::map > >::iterator + collisionsIt = _link->collision_groups.begin(); + collisionsIt != _link->collision_groups.end(); ++collisionsIt) + { + if (collisionsIt->first.find(g_lumpPrefix) == 0) + { + // if it's a previously lumped mesh, relump under same _groupName + std::string lumpGroupName = collisionsIt->first; + sdfdbg << "re-lumping collision [" << collisionsIt->first + << "] for link [" << _link->name + << "] to parent [" << _link->getParent()->name + << "] with group name [" << lumpGroupName << "]\n"; + for (std::vector::iterator + collisionIt = collisionsIt->second->begin(); + collisionIt != collisionsIt->second->end(); ++collisionIt) + { + // transform collision origin from _link frame to + // parent link frame before adding to parent + (*collisionIt)->origin = TransformToParentFrame( + (*collisionIt)->origin, + _link->parent_joint->parent_to_joint_origin_transform); + // add the modified collision to parent + ReduceCollisionToParent(_link->getParent(), lumpGroupName, + *collisionIt); + } + } + else + { + // default and any other group meshes + std::string lumpGroupName = g_lumpPrefix+_link->name; + sdfdbg << "lumping collision [" << collisionsIt->first + << "] for link [" << _link->name + << "] to parent [" << _link->getParent()->name + << "] with group name [" << lumpGroupName << "]\n"; + for (std::vector::iterator + collisionIt = collisionsIt->second->begin(); + collisionIt != collisionsIt->second->end(); ++collisionIt) + { + // transform collision origin from _link frame to + // parent link frame before adding to parent + (*collisionIt)->origin = TransformToParentFrame( + (*collisionIt)->origin, + _link->parent_joint->parent_to_joint_origin_transform); + + // add the modified collision to parent + ReduceCollisionToParent(_link->getParent(), lumpGroupName, + *collisionIt); + } + } + } + // this->PrintCollisionGroups(_link->getParent()); +#else + for (std::vector::iterator + collisionIt = _link->collision_array.begin(); + collisionIt != _link->collision_array.end(); ++collisionIt) + { + std::string newCollisionName; + std::size_t lumpIndex = + (*collisionIt)->name.find(g_lumpPrefix); + if (lumpIndex != std::string::npos) + { + newCollisionName = (*collisionIt)->name; + sdfdbg << "re-lumping collision [" << (*collisionIt)->name + << "] for link [" << _link->name + << "] to parent [" << _link->getParent()->name + << "] with name [" << newCollisionName << "]\n"; + } + else + { + if ((*collisionIt)->name.empty()) + { + newCollisionName = _link->name; + } + else + { + newCollisionName = (*collisionIt)->name; + } + sdfdbg << "lumping collision [" << (*collisionIt)->name + << "] for link [" << _link->name + << "] to parent [" << _link->getParent()->name + << "] with name [" << newCollisionName << "]\n"; + } + // transform collision origin from _link frame to + // parent link frame before adding to parent + (*collisionIt)->origin = TransformToParentFrame( + (*collisionIt)->origin, + _link->parent_joint->parent_to_joint_origin_transform); + + // add the modified collision to parent + ReduceCollisionToParent(_link->getParent(), newCollisionName, + *collisionIt); + } +#endif +} + +///////////////////////////////////////////////// +/// reduce fixed joints: lump joints to parent link +void ReduceJointsToParent(UrdfLinkPtr _link) +{ + // set child link's parentJoint's parent link to + // a parent link up stream that does not have a fixed parentJoint + for (unsigned int i = 0 ; i < _link->child_links.size() ; ++i) + { + boost::shared_ptr parentJoint = + _link->child_links[i]->parent_joint; + if (!FixedJointShouldBeReduced(parentJoint)) + { + // go down the tree until we hit a parent joint that is not fixed + UrdfLinkPtr newParentLink = _link; + ignition::math::Pose3d jointAnchorTransform; + while (newParentLink->parent_joint && + newParentLink->getParent()->name != "world" && + FixedJointShouldBeReduced(newParentLink->parent_joint) ) + { + jointAnchorTransform = jointAnchorTransform * jointAnchorTransform; + parentJoint->parent_to_joint_origin_transform = + TransformToParentFrame( + parentJoint->parent_to_joint_origin_transform, + newParentLink->parent_joint->parent_to_joint_origin_transform); + newParentLink = newParentLink->getParent(); + } + // now set the _link->child_links[i]->parent_joint's parent link to + // the newParentLink + _link->child_links[i]->setParent(newParentLink); + parentJoint->parent_link_name = newParentLink->name; + // and set the _link->child_links[i]->parent_joint's + // parent_to_joint_origin_transform as the aggregated anchor transform? + } + } +} + +//////////////////////////////////////////////////////////////////////////////// +std::string lowerStr(const std::string &_str) +{ + std::string out = _str; + std::transform(out.begin(), out.end(), out.begin(), ::tolower); + return out; +} + +//////////////////////////////////////////////////////////////////////////////// +URDF2SDF::URDF2SDF() +{ + // default options + g_enforceLimits = true; + g_reduceFixedJoints = true; +} + +//////////////////////////////////////////////////////////////////////////////// +URDF2SDF::~URDF2SDF() +{ +} + + + +//////////////////////////////////////////////////////////////////////////////// +std::string Values2str(unsigned int _count, const double *_values) +{ + std::stringstream ss; + for (unsigned int i = 0 ; i < _count ; ++i) + { + if (i > 0) + ss << " "; + ss << _values[i]; + } + return ss.str(); +} + +//////////////////////////////////////////////////////////////////////////////// +void AddKeyValue(TiXmlElement *_elem, const std::string &_key, + const std::string &_value) +{ + TiXmlElement* childElem = _elem->FirstChildElement(_key); + if (childElem) + { + std::string oldValue = GetKeyValueAsString(childElem); + if (oldValue != _value) + sdfwarn << "multiple inconsistent <" << _key + << "> exists due to fixed joint reduction" + << " overwriting previous value [" << oldValue + << "] with [" << _value << "].\n"; + else + sdfdbg << "multiple consistent <" << _key + << "> exists with [" << _value + << "] due to fixed joint reduction.\n"; + _elem->RemoveChild(childElem); // remove old _elem + } + + TiXmlElement *ekey = new TiXmlElement(_key); + TiXmlText *textEkey = new TiXmlText(_value); + ekey->LinkEndChild(textEkey); + _elem->LinkEndChild(ekey); +} + +//////////////////////////////////////////////////////////////////////////////// +void AddTransform(TiXmlElement *_elem, const ignition::math::Pose3d &_transform) +{ + ignition::math::Vector3d e = _transform.Rot().Euler(); + double cpose[6] = { _transform.Pos().X(), _transform.Pos().Y(), + _transform.Pos().Z(), e.X(), e.Y(), e.Z() }; + + // set geometry transform + AddKeyValue(_elem, "pose", Values2str(6, cpose)); +} + +//////////////////////////////////////////////////////////////////////////////// +std::string GetKeyValueAsString(TiXmlElement* _elem) +{ + std::string valueStr; + if (_elem->Attribute("value")) + { + valueStr = _elem->Attribute("value"); + } + else if (_elem->FirstChild()) + /// @todo: FIXME: comment out check for now, different tinyxml + /// versions fails to compile: + // && _elem->FirstChild()->Type() == TiXmlNode::TINYXML_TEXT) + { + valueStr = _elem->FirstChild()->ValueStr(); + } + return valueStr; +} + +///////////////////////////////////////////////// +void ParseRobotOrigin(TiXmlDocument &_urdfXml) +{ + TiXmlElement *robotXml = _urdfXml.FirstChildElement("robot"); + TiXmlElement *originXml = robotXml->FirstChildElement("origin"); + if (originXml) + { + g_initialRobotPose.position = ParseVector3( + std::string(originXml->Attribute("xyz"))); + urdf::Vector3 rpy = ParseVector3(std::string(originXml->Attribute("rpy"))); + g_initialRobotPose.rotation.setFromRPY(rpy.x, rpy.y, rpy.z); + g_initialRobotPoseValid = true; + } +} + +///////////////////////////////////////////////// +void InsertRobotOrigin(TiXmlElement *_elem) +{ + if (g_initialRobotPoseValid) + { + // set transform + double pose[6]; + pose[0] = g_initialRobotPose.position.x; + pose[1] = g_initialRobotPose.position.y; + pose[2] = g_initialRobotPose.position.z; + g_initialRobotPose.rotation.getRPY(pose[3], pose[4], pose[5]); + AddKeyValue(_elem, "pose", Values2str(6, pose)); + } +} + +//////////////////////////////////////////////////////////////////////////////// +void URDF2SDF::ParseSDFExtension(TiXmlDocument &_urdfXml) +{ + TiXmlElement* robotXml = _urdfXml.FirstChildElement("robot"); + + // Get all SDF extension elements, put everything in + // g_extensions map, containing a key string + // (link/joint name) and values + for (TiXmlElement* sdfXml = robotXml->FirstChildElement("gazebo"); + sdfXml; sdfXml = sdfXml->NextSiblingElement("gazebo")) + { + const char* ref = sdfXml->Attribute("reference"); + std::string refStr; + if (!ref) + { + // copy extensions for robot (outside of link/joint) + refStr.clear(); + } + else + { + // copy extensions for link/joint + refStr = std::string(ref); + } + + if (g_extensions.find(refStr) == + g_extensions.end()) + { + // create extension map for reference + std::vector ge; + g_extensions.insert(std::make_pair(refStr, ge)); + } + + // create and insert a new SDFExtension into the map + SDFExtensionPtr sdf(new SDFExtension()); + + // begin parsing xml node + for (TiXmlElement *childElem = sdfXml->FirstChildElement(); + childElem; childElem = childElem->NextSiblingElement()) + { + sdf->oldLinkName = refStr; + + // go through all elements of the extension, + // extract what we know, and save the rest in blobs + // @todo: somehow use sdf definitions here instead of hard coded + // objects + + // material + if (childElem->ValueStr() == "material") + { + sdf->material = GetKeyValueAsString(childElem); + } + else if (childElem->ValueStr() == "collision" + || childElem->ValueStr() == "visual") + { + // anything inside of collision or visual tags: + // + // + // + // + // + // + // + // + // are treated as blobs that gets inserted + // into all collisions and visuals for the link + // + // + // + // + // + // + // + // + + // a place to store converted doc + for (TiXmlElement* e = childElem->FirstChildElement(); e; + e = e->NextSiblingElement()) + { + TiXmlDocument xmlNewDoc; + + std::ostringstream origStream; + origStream << *e; + xmlNewDoc.Parse(origStream.str().c_str()); + + // save all unknown stuff in a vector of blobs + TiXmlElementPtr blob( + new TiXmlElement(*xmlNewDoc.FirstChildElement())); + if (childElem->ValueStr() == "collision") + { + sdf->collision_blobs.push_back(blob); + } + else + { + sdf->visual_blobs.push_back(blob); + } + } + } + else if (childElem->ValueStr() == "static") + { + std::string valueStr = GetKeyValueAsString(childElem); + + // default of setting static flag is false + if (lowerStr(valueStr) == "true" || lowerStr(valueStr) == "yes" || + valueStr == "1") + sdf->setStaticFlag = true; + else + sdf->setStaticFlag = false; + } + else if (childElem->ValueStr() == "turnGravityOff") + { + std::string valueStr = GetKeyValueAsString(childElem); + + // default of gravity is true + if (lowerStr(valueStr) == "false" || lowerStr(valueStr) == "no" || + valueStr == "0") + sdf->gravity = true; + else + sdf->gravity = false; + } + else if (childElem->ValueStr() == "dampingFactor") + { + sdf->isDampingFactor = true; + sdf->dampingFactor = boost::lexical_cast( + GetKeyValueAsString(childElem).c_str()); + } + else if (childElem->ValueStr() == "maxVel") + { + sdf->isMaxVel = true; + sdf->maxVel = boost::lexical_cast( + GetKeyValueAsString(childElem).c_str()); + } + else if (childElem->ValueStr() == "minDepth") + { + sdf->isMinDepth = true; + sdf->minDepth = boost::lexical_cast( + GetKeyValueAsString(childElem).c_str()); + } + else if (childElem->ValueStr() == "mu1") + { + sdf->isMu1 = true; + sdf->mu1 = boost::lexical_cast( + GetKeyValueAsString(childElem).c_str()); + } + else if (childElem->ValueStr() == "mu2") + { + sdf->isMu2 = true; + sdf->mu2 = boost::lexical_cast( + GetKeyValueAsString(childElem).c_str()); + } + else if (childElem->ValueStr() == "fdir1") + { + sdf->fdir1 = GetKeyValueAsString(childElem); + } + else if (childElem->ValueStr() == "kp") + { + sdf->isKp = true; + sdf->kp = boost::lexical_cast( + GetKeyValueAsString(childElem).c_str()); + } + else if (childElem->ValueStr() == "kd") + { + sdf->isKd = true; + sdf->kd = boost::lexical_cast( + GetKeyValueAsString(childElem).c_str()); + } + else if (childElem->ValueStr() == "selfCollide") + { + sdf->isSelfCollide = true; + std::string valueStr = GetKeyValueAsString(childElem); + + // default of selfCollide is false + if (lowerStr(valueStr) == "true" || lowerStr(valueStr) == "yes" || + valueStr == "1") + sdf->selfCollide = true; + else + sdf->selfCollide = false; + } + else if (childElem->ValueStr() == "maxContacts") + { + sdf->isMaxContacts = true; + sdf->maxContacts = boost::lexical_cast( + GetKeyValueAsString(childElem).c_str()); + } + else if (childElem->ValueStr() == "laserRetro") + { + sdf->isLaserRetro = true; + sdf->laserRetro = boost::lexical_cast( + GetKeyValueAsString(childElem).c_str()); + } + else if (childElem->ValueStr() == "springReference") + { + sdf->isSpringReference = true; + sdf->springReference = std::stod(GetKeyValueAsString(childElem)); + } + else if (childElem->ValueStr() == "springStiffness") + { + sdf->isSpringStiffness = true; + sdf->springStiffness = std::stod(GetKeyValueAsString(childElem)); + } + else if (childElem->ValueStr() == "stopCfm") + { + sdf->isStopCfm = true; + sdf->stopCfm = boost::lexical_cast( + GetKeyValueAsString(childElem).c_str()); + } + else if (childElem->ValueStr() == "stopErp") + { + sdf->isStopErp = true; + sdf->stopErp = boost::lexical_cast( + GetKeyValueAsString(childElem).c_str()); + } + else if (childElem->ValueStr() == "stopKp") + { + sdf->isStopKp = true; + sdf->stopKp = boost::lexical_cast( + GetKeyValueAsString(childElem).c_str()); + } + else if (childElem->ValueStr() == "stopKd") + { + sdf->isStopKd = true; + sdf->stopKd = boost::lexical_cast( + GetKeyValueAsString(childElem).c_str()); + } + else if (childElem->ValueStr() == "initialJointPosition") + { + sdf->isInitialJointPosition = true; + sdf->initialJointPosition = boost::lexical_cast( + GetKeyValueAsString(childElem).c_str()); + } + else if (childElem->ValueStr() == "fudgeFactor") + { + sdf->isFudgeFactor = true; + sdf->fudgeFactor = boost::lexical_cast( + GetKeyValueAsString(childElem).c_str()); + } + else if (childElem->ValueStr() == "provideFeedback") + { + sdf->isProvideFeedback = true; + std::string valueStr = GetKeyValueAsString(childElem); + + if (lowerStr(valueStr) == "true" || lowerStr(valueStr) == "yes" || + valueStr == "1") + sdf->provideFeedback = true; + else + sdf->provideFeedback = false; + } + else if (childElem->ValueStr() == "canonicalBody") + { + sdfdbg << "do nothing with canonicalBody\n"; + } + else if (childElem->ValueStr() == "cfmDamping" || + childElem->ValueStr() == "implicitSpringDamper") + { + if (childElem->ValueStr() == "cfmDamping") + sdfwarn << "Note that cfmDamping is being deprecated by " + << "implicitSpringDamper, please replace instances " + << "of cfmDamping with implicitSpringDamper in your model.\n"; + + sdf->isImplicitSpringDamper = true; + std::string valueStr = GetKeyValueAsString(childElem); + + if (lowerStr(valueStr) == "true" || lowerStr(valueStr) == "yes" || + valueStr == "1") + sdf->implicitSpringDamper = true; + else + sdf->implicitSpringDamper = false; + } + else if (childElem->ValueStr() == "disableFixedJointLumping") + { + std::string valueStr = GetKeyValueAsString(childElem); + + if (lowerStr(valueStr) == "true" || lowerStr(valueStr) == "yes" || + valueStr == "1") + { + g_fixedJointsTransformedInRevoluteJoints.insert(refStr); + } + } + else if (childElem->ValueStr() == "preserveFixedJoint") + { + std::string valueStr = GetKeyValueAsString(childElem); + + if (lowerStr(valueStr) == "true" || lowerStr(valueStr) == "yes" || + valueStr == "1") + { + g_fixedJointsTransformedInFixedJoints.insert(refStr); + } + } + else + { + // a place to store converted doc + TiXmlDocument xmlNewDoc; + + std::ostringstream stream; + stream << *childElem; + sdfdbg << "extension [" << stream.str() << + "] not converted from URDF, probably already in SDF format.\n"; + xmlNewDoc.Parse(stream.str().c_str()); + + // save all unknown stuff in a vector of blobs + TiXmlElementPtr blob(new TiXmlElement(*xmlNewDoc.FirstChildElement())); + sdf->blobs.push_back(blob); + } + } + + // insert into my map + (g_extensions.find(refStr))->second.push_back(sdf); + } + + // Handle fixed joints for which both disableFixedJointLumping + // and preserveFixedJoint options are present + for (auto& fixedJointConvertedToFixed: + g_fixedJointsTransformedInFixedJoints) + { + // If both options are present, the model creator is aware of the + // existence of the preserveFixedJoint option and the + // disableFixedJointLumping option is there only for backward compatibility + // For this reason, if both options are present then the preserveFixedJoint + // option has the precedence + g_fixedJointsTransformedInRevoluteJoints.erase(fixedJointConvertedToFixed); + } +} + +//////////////////////////////////////////////////////////////////////////////// +void InsertSDFExtensionCollision(TiXmlElement *_elem, + const std::string &_linkName) +{ + // loop through extensions for the whole model + // and see which ones belong to _linkName + // This might be complicated since there's: + // - urdf collision name -> sdf collision name conversion + // - fixed joint reduction / lumping + for (StringSDFExtensionPtrMap::iterator + sdfIt = g_extensions.begin(); + sdfIt != g_extensions.end(); ++sdfIt) + { + if (sdfIt->first == _linkName) + { + // std::cerr << "============================\n"; + // std::cerr << "working on g_extensions for link [" + // << sdfIt->first << "]\n"; + // if _elem already has a surface element, use it + TiXmlNode *surface = _elem->FirstChild("surface"); + TiXmlNode *friction = NULL; + TiXmlNode *frictionOde = NULL; + TiXmlNode *contact = NULL; + TiXmlNode *contactOde = NULL; + + // loop through all the gazebo extensions stored in sdfIt->second + for (std::vector::iterator ge = sdfIt->second.begin(); + ge != sdfIt->second.end(); ++ge) + { + // Check if this blob belongs to _elem based on + // - blob's reference link name (_linkName or sdfIt->first) + // - _elem (destination for blob, which is a collision sdf). + + if (!_elem->Attribute("name")) + { + sdferr << "ERROR: collision _elem has no name," + << " something is wrong" << "\n"; + } + + std::string sdfCollisionName(_elem->Attribute("name")); + + // std::cerr << "----------------------------\n"; + // std::cerr << "blob belongs to [" << _linkName + // << "] with old parent LinkName [" << (*ge)->oldLinkName + // << "]\n"; + // std::cerr << "_elem sdf collision name [" << sdfCollisionName + // << "]\n"; + // std::cerr << "----------------------------\n"; + + std::string lumpCollisionName = g_lumpPrefix + + (*ge)->oldLinkName + g_collisionExt; + + bool wasReduced = (_linkName == (*ge)->oldLinkName); + bool collisionNameContainsLinkname = + sdfCollisionName.find(_linkName) != std::string::npos; + bool collisionNameContainsLumpedLinkname = + sdfCollisionName.find(lumpCollisionName) != std::string::npos; + bool collisionNameContainsLumpedRef = + sdfCollisionName.find(g_lumpPrefix) != std::string::npos; + + if (!collisionNameContainsLinkname) + { + sdferr << "collision name does not contain link name," + << " file an issue.\n"; + } + + // if the collision _elem was not reduced, + // its name should not have g_lumpPrefix in it. + // otherwise, its name should have + // "g_lumpPrefix+[original link name before reduction]". + if ((wasReduced && !collisionNameContainsLumpedRef) || + (!wasReduced && collisionNameContainsLumpedLinkname)) + { + // insert any blobs (including visual plugins) + // warning, if you insert a sdf here, it might + // duplicate what was constructed above. + // in the future, we should use blobs (below) in place of + // explicitly specified fields (above). + if (!(*ge)->collision_blobs.empty()) + { + std::vector::iterator blob; + for (blob = (*ge)->collision_blobs.begin(); + blob != (*ge)->collision_blobs.end(); ++blob) + { + // find elements and assign pointers if they exist + // for mu1, mu2, minDepth, maxVel, fdir1, kp, kd + // otherwise, they are allocated by 'new' below. + // std::cerr << ">>>>> working on extension blob: [" + // << (*blob)->Value() << "]\n"; + + // print for debug + std::ostringstream origStream; + std::unique_ptr blobClone((*blob)->Clone()); + origStream << *blobClone; + // std::cerr << "collision extension [" + // << origStream.str() << "]\n"; + + if (strcmp((*blob)->Value(), "surface") == 0) + { + // blob is a , tread carefully otherwise + // we end up with multiple copies of . + // Also, get pointers (contact[Ode], friction[Ode]) + // below for backwards (non-blob) compatibility. + if (surface == NULL) + { + // do not exist, it simple, + // just add it to the current collision + // and it's done. + _elem->LinkEndChild((*blob)->Clone()); + surface = _elem->LastChild("surface"); + // std::cerr << " --- surface created " + // << (void*)surface << "\n"; + } + else + { + // exist already, remove it and + // overwrite with the blob. + _elem->RemoveChild(surface); + _elem->LinkEndChild((*blob)->Clone()); + surface = _elem->FirstChild("surface"); + // std::cerr << " --- surface exists, replace with blob.\n"; + } + + // Extra code for backwards compatibility, to + // deal with old way of specifying collision attributes + // using individual elements listed below: + // "mu" + // "mu2" + // "fdir1" + // "kp" + // "kd" + // "max_vel" + // "min_depth" + // "laser_retro" + // "max_contacts" + // Get contact[Ode] and friction[Ode] node pointers + // if they exist. + contact = surface->FirstChild("contact"); + if (contact != NULL) + { + contactOde = contact->FirstChild("ode"); + } + friction = surface->FirstChild("friction"); + if (friction != NULL) + { + frictionOde = friction->FirstChild("ode"); + } + } + else + { + // If the blob is not a , we don't have + // to worry about backwards compatibility. + // Simply add to master element. + _elem->LinkEndChild((*blob)->Clone()); + } + } + } + + // Extra code for backwards compatibility, to + // deal with old way of specifying collision attributes + // using individual elements listed below: + // "mu" + // "mu2" + // "fdir1" + // "kp" + // "kd" + // "max_vel" + // "min_depth" + // "laser_retro" + // "max_contacts" + // The new way to do this is to specify everything + // in collision blobs by using the tag. + // So there's no need for custom code for each property. + + // construct new elements if not in blobs + if (surface == NULL) + { + surface = new TiXmlElement("surface"); + if (!surface) + { + // Memory allocation error + sdferr << "Memory allocation error while" + << " processing .\n"; + } + _elem->LinkEndChild(surface); + } + + // construct new elements if not in blobs + if (contact == NULL) + { + if (surface->FirstChild("contact") == NULL) + { + contact = new TiXmlElement("contact"); + if (!contact) + { + // Memory allocation error + sdferr << "Memory allocation error while" + << " processing .\n"; + } + surface->LinkEndChild(contact); + } + else + { + contact = surface->FirstChild("contact"); + } + } + + if (contactOde == NULL) + { + + if (contact->FirstChild("ode") == NULL) + { + contactOde = new TiXmlElement("ode"); + if (!contactOde) + { + // Memory allocation error + sdferr << "Memory allocation error while" + << " processing .\n"; + } + contact->LinkEndChild(contactOde); + } + else + { + contactOde = contact->FirstChild("ode"); + } + } + + if (friction == NULL) + { + if (surface->FirstChild("friction") == NULL) + { + friction = new TiXmlElement("friction"); + if (!friction) + { + // Memory allocation error + sdferr << "Memory allocation error while" + << " processing .\n"; + } + surface->LinkEndChild(friction); + } + else + { + friction = surface->FirstChild("friction"); + } + } + + if (frictionOde == NULL) + { + if (friction->FirstChild("ode") == NULL) + { + frictionOde = new TiXmlElement("ode"); + if (!frictionOde) + { + // Memory allocation error + sdferr << "Memory allocation error while" + << " processing .\n"; + } + friction->LinkEndChild(frictionOde); + } + else + { + frictionOde = friction->FirstChild("ode"); + } + } + + // insert mu1, mu2, kp, kd for collision + if ((*ge)->isMu1) + { + AddKeyValue(frictionOde->ToElement(), "mu", + Values2str(1, &(*ge)->mu1)); + } + if ((*ge)->isMu2) + { + AddKeyValue(frictionOde->ToElement(), "mu2", + Values2str(1, &(*ge)->mu2)); + } + if (!(*ge)->fdir1.empty()) + { + AddKeyValue(frictionOde->ToElement(), "fdir1", (*ge)->fdir1); + } + if ((*ge)->isKp) + { + AddKeyValue(contactOde->ToElement(), "kp", + Values2str(1, &(*ge)->kp)); + } + if ((*ge)->isKd) + { + AddKeyValue(contactOde->ToElement(), "kd", + Values2str(1, &(*ge)->kd)); + } + // max contact interpenetration correction velocity + if ((*ge)->isMaxVel) + { + AddKeyValue(contactOde->ToElement(), "max_vel", + Values2str(1, &(*ge)->maxVel)); + } + // contact interpenetration margin tolerance + if ((*ge)->isMinDepth) + { + AddKeyValue(contactOde->ToElement(), "min_depth", + Values2str(1, &(*ge)->minDepth)); + } + if ((*ge)->isLaserRetro) + { + AddKeyValue(_elem, "laser_retro", + Values2str(1, &(*ge)->laserRetro)); + } + if ((*ge)->isMaxContacts) + { + AddKeyValue(_elem, "max_contacts", + boost::lexical_cast((*ge)->maxContacts)); + } + } + } + } + } +} + +//////////////////////////////////////////////////////////////////////////////// +void InsertSDFExtensionVisual(TiXmlElement *_elem, + const std::string &_linkName) +{ + // loop through extensions for the whole model + // and see which ones belong to _linkName + // This might be complicated since there's: + // - urdf visual name -> sdf visual name conversion + // - fixed joint reduction / lumping + for (StringSDFExtensionPtrMap::iterator + sdfIt = g_extensions.begin(); + sdfIt != g_extensions.end(); ++sdfIt) + { + if (sdfIt->first == _linkName) + { + // std::cerr << "============================\n"; + // std::cerr << "working on g_extensions for link [" + // << sdfIt->first << "]\n"; + // if _elem already has a material element, use it + TiXmlNode *material = _elem->FirstChild("material"); + TiXmlElement *script = NULL; + + // loop through all the gazebo extensions stored in sdfIt->second + for (std::vector::iterator ge = sdfIt->second.begin(); + ge != sdfIt->second.end(); ++ge) + { + // Check if this blob belongs to _elem based on + // - blob's reference link name (_linkName or sdfIt->first) + // - _elem (destination for blob, which is a visual sdf). + + if (!_elem->Attribute("name")) + sdferr << "ERROR: visual _elem has no name," + << " something is wrong" << "\n"; + + std::string sdfVisualName(_elem->Attribute("name")); + + // std::cerr << "----------------------------\n"; + // std::cerr << "blob belongs to [" << _linkName + // << "] with old parent LinkName [" << (*ge)->oldLinkName + // << "]\n"; + // std::cerr << "_elem sdf visual name [" << sdfVisualName + // << "]\n"; + // std::cerr << "----------------------------\n"; + + std::string lumpVisualName = g_lumpPrefix + + (*ge)->oldLinkName + g_visualExt; + + bool wasReduced = (_linkName == (*ge)->oldLinkName); + bool visualNameContainsLinkname = + sdfVisualName.find(_linkName) != std::string::npos; + bool visualNameContainsLumpedLinkname = + sdfVisualName.find(lumpVisualName) != std::string::npos; + bool visualNameContainsLumpedRef = + sdfVisualName.find(g_lumpPrefix) != std::string::npos; + + if (!visualNameContainsLinkname) + sdferr << "visual name does not contain link name," + << " file an issue.\n"; + + // if the visual _elem was not reduced, + // its name should not have g_lumpPrefix in it. + // otherwise, its name should have + // "g_lumpPrefix+[original link name before reduction]". + if ((wasReduced && !visualNameContainsLumpedRef) || + (!wasReduced && visualNameContainsLumpedLinkname)) + { + // insert any blobs (including visual plugins) + // warning, if you insert a sdf here, it might + // duplicate what was constructed above. + // in the future, we should use blobs (below) in place of + // explicitly specified fields (above). + if (!(*ge)->visual_blobs.empty()) + { + std::vector::iterator blob; + for (blob = (*ge)->visual_blobs.begin(); + blob != (*ge)->visual_blobs.end(); ++blob) + { + // find elements and assign pointers if they exist + // for mu1, mu2, minDepth, maxVel, fdir1, kp, kd + // otherwise, they are allocated by 'new' below. + // std::cerr << ">>>>> working on extension blob: [" + // << (*blob)->Value() << "]\n"; + + // print for debug + // std::ostringstream origStream; + // origStream << *(*blob)->Clone(); + // std::cerr << "visual extension [" + // << origStream.str() << "]\n"; + + if (strcmp((*blob)->Value(), "material") == 0) + { + // blob is a , tread carefully otherwise + // we end up with multiple copies of . + // Also, get pointers (script) + // below for backwards (non-blob) compatibility. + if (material == NULL) + { + // do not exist, it simple, + // just add it to the current visual + // and it's done. + _elem->LinkEndChild((*blob)->Clone()); + material = _elem->LastChild("material"); + // std::cerr << " --- material created " + // << (void*)material << "\n"; + } + else + { + // exist already, remove it and + // overwrite with the blob. + _elem->RemoveChild(material); + _elem->LinkEndChild((*blob)->Clone()); + material = _elem->FirstChild("material"); + // std::cerr << " --- material exists, replace with blob.\n"; + } + + // Extra code for backwards compatibility, to + // deal with old way of specifying visual attributes + // using individual element: + // "script" + // Get script node pointers + // if they exist. + script = material->FirstChildElement("script"); + } + else + { + // std::cerr << "***** working on extension blob: [" + // << (*blob)->Value() << "]\n"; + // If the blob is not a , we don't have + // to worry about backwards compatibility. + // Simply add to master element. + _elem->LinkEndChild((*blob)->Clone()); + } + } + } + + // Extra code for backwards compatibility, to + // deal with old way of specifying visual attributes + // using individual element: + // "script" + // The new way to do this is to specify everything + // in visual blobs by using the tag. + // So there's no need for custom code for each property. + + // construct new elements if not in blobs + if (material == NULL) + { + material = new TiXmlElement("material"); + if (!material) + { + // Memory allocation error + sdferr << "Memory allocation error while" + << " processing .\n"; + } + _elem->LinkEndChild(material); + } + + if (script == NULL) + { + if (material->FirstChildElement("script") == NULL) + { + script = new TiXmlElement("script"); + if (!script) + { + // Memory allocation error + sdferr << "Memory allocation error while" + << " processing + EXPECT_EQ(urdf_child_link_1_col->Get("max_contacts"), 177); + EXPECT_EQ(urdf_child_link_1_col->Get("max_contacts"), + sdf_child_link_1_col->Get("max_contacts")); + + double urdf_mu1 = urdf_child_link_1_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu"); + double sdf_mu1 = sdf_child_link_1_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu"); + sdfmsg << "urdf mu1: " << urdf_mu1 << "\n"; + EXPECT_DOUBLE_EQ(urdf_mu1, 0.7); + EXPECT_DOUBLE_EQ(urdf_mu1, sdf_mu1); + + double urdf_mu2 = urdf_child_link_1_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu2"); + double sdf_mu2 = sdf_child_link_1_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu2"); + sdfmsg << "urdf mu2: " << urdf_mu2 << "\n"; + EXPECT_DOUBLE_EQ(urdf_mu2, 0.71); + EXPECT_DOUBLE_EQ(urdf_mu2, sdf_mu2); + + EXPECT_EQ(urdf_child_link_1_vis->GetElement("material")-> + GetElement("script")->Get("name"), + "script_uri_71_name"); + EXPECT_EQ(urdf_child_link_1_vis->GetElement("material")-> + GetElement("script")->Get("name"), + sdf_child_link_1_vis->GetElement("material")-> + GetElement("script")->Get("name")); + + EXPECT_EQ(urdf_child_link_1_vis->GetElement("material")-> + GetElement("script")->Get("uri"), + "file://media/materials/scripts/gazebo.material"); + + EXPECT_EQ(urdf_child_link_1_vis->GetElement("material")-> + Get("ambient"), sdf::Color(0, 1, 0, 1)); + EXPECT_EQ(urdf_child_link_1_vis->GetElement("material")-> + Get("ambient"), + sdf_child_link_1_vis->GetElement("material")-> + Get("ambient")); + + // child_link_1a + // + // 166 + // 0.6 + // 0.61 + // + // + // + // + EXPECT_EQ(urdf_child_link_1a_col->Get("max_contacts"), 166); + EXPECT_EQ(urdf_child_link_1a_col->Get("max_contacts"), + sdf_child_link_1a_col->Get("max_contacts")); + + EXPECT_DOUBLE_EQ(urdf_child_link_1a_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu"), 0.6); + EXPECT_DOUBLE_EQ(urdf_child_link_1a_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu"), + sdf_child_link_1a_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu")); + + EXPECT_DOUBLE_EQ(urdf_child_link_1a_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu2"), 0.61); + EXPECT_DOUBLE_EQ(urdf_child_link_1a_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu2"), + sdf_child_link_1a_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu2")); + + EXPECT_EQ(urdf_child_link_1a_vis->GetElement("material")-> + GetElement("script")->Get("name"), + "__default__"); + EXPECT_EQ(urdf_child_link_1a_vis->GetElement("material")-> + GetElement("script")->Get("name"), + sdf_child_link_1a_vis->GetElement("material")-> + GetElement("script")->Get("name")); + + EXPECT_EQ(urdf_child_link_1a_vis->GetElement("material")-> + GetElement("script")->Get("uri"), + "__default__"); + + // ambient unassigned should be 0, 0, 0, 1 + EXPECT_EQ(urdf_child_link_1a_vis->GetElement("material")-> + Get("ambient"), sdf::Color(0, 0, 0, 1)); + EXPECT_EQ(urdf_child_link_1a_vis->GetElement("material")-> + Get("ambient"), + sdf_child_link_1a_vis->GetElement("material")-> + Get("ambient")); + + // child_link_2 + // + // 0.5 + // 0.51 + // + // script_uri_51 + // script_name_51 + // unassigne max_contacts defaut is 10 + EXPECT_EQ(urdf_child_link_2_col->Get("max_contacts"), 10); + EXPECT_EQ(urdf_child_link_2_col->Get("max_contacts"), + sdf_child_link_2_col->Get("max_contacts")); + + EXPECT_DOUBLE_EQ(urdf_child_link_2_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu"), 0.5); + EXPECT_DOUBLE_EQ(urdf_child_link_2_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu"), + sdf_child_link_2_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu")); + + EXPECT_DOUBLE_EQ(urdf_child_link_2_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu2"), 0.51); + EXPECT_DOUBLE_EQ(urdf_child_link_2_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu2"), + sdf_child_link_2_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu2")); + + EXPECT_EQ(urdf_child_link_2_vis->GetElement("material")-> + GetElement("script")->Get("name"), + "script_name_51"); + EXPECT_EQ(urdf_child_link_2_vis->GetElement("material")-> + GetElement("script")->Get("name"), + sdf_child_link_2_vis->GetElement("material")-> + GetElement("script")->Get("name")); + + EXPECT_EQ(urdf_child_link_2_vis->GetElement("material")-> + GetElement("script")->Get("uri"), + "script_uri_51"); + + // ambient unassigned should be 0, 0, 0, 1 + EXPECT_EQ(urdf_child_link_2_vis->GetElement("material")-> + Get("ambient"), sdf::Color(0, 0, 0, 1)); + EXPECT_EQ(urdf_child_link_2_vis->GetElement("material")-> + Get("ambient"), + sdf_child_link_2_vis->GetElement("material")-> + Get("ambient")); +} + +///////////////////////////////////////////////// +void FixedJointReductionCollisionVisualExtensionEmptyRoot( + const std::string &_urdfFile, const std::string &_sdfFile) +{ + // load urdf file, load sdf file. + // check to see that urdf load results are consistent with sdf load. + + // load urdf + sdf::SDFPtr urdfRobot(new sdf::SDF()); + sdf::init(urdfRobot); + ASSERT_TRUE(sdf::readFile(_urdfFile, urdfRobot)); + + // load sdf + sdf::SDFPtr sdfRobot(new sdf::SDF()); + sdf::init(sdfRobot); + ASSERT_TRUE(sdf::readFile(_sdfFile, sdfRobot)); + + // check two loaded files, make sure they are the same + sdf::ElementPtr urdfModel = urdfRobot->Root()->GetElement("model"); + sdf::ElementPtr urdf_child_link_1_col; + sdf::ElementPtr urdf_child_link_1_vis; + for (sdf::ElementPtr link = urdfModel->GetElement("link"); link; + link = link->GetNextElement("link")) + { + for (sdf::ElementPtr col = link->GetElement("collision"); col; + col = col->GetNextElement("collision")) + { + std::string colName = col->Get("name"); + // note that if there is only one child visual, no _1 is appended + // compare this with FixedJointReductionCollisionVisualExtension test + if (colName == "base_link_fixed_joint_lump__child_link_1_collision") + { + urdf_child_link_1_col = col; + } + sdfmsg << "col: " << colName << "\n"; + } + for (sdf::ElementPtr vis = link->GetElement("visual"); vis; + vis = vis->GetNextElement("visual")) + { + std::string visName = vis->Get("name"); + // note that if there is only one child visual, no _1 is appended + // compare this with FixedJointReductionCollisionVisualExtension test + if (visName == "base_link_fixed_joint_lump__child_link_1_visual") + { + urdf_child_link_1_vis = vis; + } + sdfmsg << "vis: " << visName << "\n"; + } + } + sdf::ElementPtr sdfModel = sdfRobot->Root()->GetElement("model"); + sdf::ElementPtr sdf_child_link_1_col; + sdf::ElementPtr sdf_child_link_1_vis; + for (sdf::ElementPtr link = sdfModel->GetElement("link"); link; + link = link->GetNextElement("link")) + { + for (sdf::ElementPtr col = link->GetElement("collision"); col; + col = col->GetNextElement("collision")) + { + std::string colName = col->Get("name"); + // note that if there is only one child visual, no _1 is appended + // compare this with FixedJointReductionCollisionVisualExtension test + if (colName == "base_link_fixed_joint_lump__child_link_1_collision") + { + sdf_child_link_1_col = col; + } + sdfmsg << "col: " << colName << "\n"; + } + for (sdf::ElementPtr vis = link->GetElement("visual"); vis; + vis = vis->GetNextElement("visual")) + { + std::string visName = vis->Get("name"); + // note that if there is only one child visual, no _1 is appended + // compare this with FixedJointReductionCollisionVisualExtension test + if (visName == "base_link_fixed_joint_lump__child_link_1_visual") + { + sdf_child_link_1_vis = vis; + } + sdfmsg << "vis: " << visName << "\n"; + } + } + // child_link_1 + // + // 0.007 + // 0.7 + // 0.71 + // + // 0 1 0 1 + // + EXPECT_EQ(urdf_child_link_1_col->Get("max_contacts"), 177); + EXPECT_EQ(urdf_child_link_1_col->Get("max_contacts"), + sdf_child_link_1_col->Get("max_contacts")); + + double urdf_mu1 = urdf_child_link_1_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu"); + double sdf_mu1 = sdf_child_link_1_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu"); + sdfmsg << "urdf mu1: " << urdf_mu1 << "\n"; + EXPECT_DOUBLE_EQ(urdf_mu1, 0.7); + EXPECT_DOUBLE_EQ(urdf_mu1, sdf_mu1); + + double urdf_mu2 = urdf_child_link_1_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu2"); + double sdf_mu2 = sdf_child_link_1_col->GetElement("surface") + ->GetElement("friction")->GetElement("ode")->Get("mu2"); + sdfmsg << "urdf mu2: " << urdf_mu2 << "\n"; + EXPECT_DOUBLE_EQ(urdf_mu2, 0.71); + EXPECT_DOUBLE_EQ(urdf_mu2, sdf_mu2); + + EXPECT_EQ(urdf_child_link_1_vis->GetElement("material")-> + GetElement("script")->Get("name"), + "script_uri_71_name"); + EXPECT_EQ(urdf_child_link_1_vis->GetElement("material")-> + GetElement("script")->Get("name"), + sdf_child_link_1_vis->GetElement("material")-> + GetElement("script")->Get("name")); + + EXPECT_EQ(urdf_child_link_1_vis->GetElement("material")-> + GetElement("script")->Get("uri"), + "file://media/materials/scripts/gazebo.material"); + + EXPECT_EQ(urdf_child_link_1_vis->GetElement("material")-> + Get("ambient"), sdf::Color(0, 1, 0, 1)); + EXPECT_EQ(urdf_child_link_1_vis->GetElement("material")-> + Get("ambient"), + sdf_child_link_1_vis->GetElement("material")-> + Get("ambient")); +} + +///////////////////////////////////////////////// +void FixedJointReductionEquivalence(const std::string &_file) +{ + sdf::SDFPtr robot(new sdf::SDF()); + sdf::init(robot); + ASSERT_TRUE(sdf::readFile(_file, robot)); + + std::map linkMasses; + std::map linkPoses; + std::map mapIxxIyyIzz; + std::map mapIxyIxzIyz; + + { + std::string linkName = "link0"; + linkMasses[linkName] = 1000; + linkPoses[linkName] = ignition::math::Pose3d(0, 0, -0.5, 0, -0, 0); + mapIxxIyyIzz[linkName] = ignition::math::Vector3d(1, 1, 1); + mapIxyIxzIyz[linkName] = ignition::math::Vector3d(0, 0, 0); + } + + { + std::string linkName = "link1"; + linkMasses[linkName] = 100; + linkPoses[linkName] = + ignition::math::Pose3d(0, -1.5, 0, -2.14159, 0.141593, 0.858407); + mapIxxIyyIzz[linkName] = ignition::math::Vector3d(2, 3, 4); + mapIxyIxzIyz[linkName] = ignition::math::Vector3d(0, 0, 0); + } + + { + std::string linkName = "link2"; + linkMasses[linkName] = 200; + linkPoses[linkName] = + ignition::math::Pose3d(0.2, 0.4, 1, -1.14159, -0.141593, 1.5708); + mapIxxIyyIzz[linkName] = ignition::math::Vector3d(5, 6, 7); + mapIxyIxzIyz[linkName] = ignition::math::Vector3d(0, 0, 0); + } + + { + std::string linkName = "link3"; + linkMasses[linkName] = 400; + linkPoses[linkName] = + ignition::math::Pose3d(0.1, 0.2, 0.3, -1.14159, 0.141593, 0.858407); + mapIxxIyyIzz[linkName] = ignition::math::Vector3d(8, 9, 10); + mapIxyIxzIyz[linkName] = ignition::math::Vector3d(0, 0, 0); + } + + { + std::string linkName = "link1a"; + linkMasses[linkName] = 700; + linkPoses[linkName] = ignition::math::Pose3d( + 1.6, -2.72857, -0.342857, -2.14159, 0.141593, 0.858407); + mapIxxIyyIzz[linkName] = + ignition::math::Vector3d(576.477, 527.681, 420.127); + mapIxyIxzIyz[linkName] = + ignition::math::Vector3d(-65.6808, 134.562, 264.781); + } + + // Count collisions and visuals + unsigned int countVisuals = 0; + unsigned int countCollisions = 0; + + sdf::ElementPtr model = robot->Root()->GetElement("model"); + for (sdf::ElementPtr link = model->GetElement("link"); link; + link = link->GetNextElement("link")) + { + std::string linkName = link->Get("name"); + sdf::ElementPtr inertial = link->GetElement("inertial"); + double linkMass = inertial->Get("mass"); + ignition::math::Pose3d linkPose = + inertial->Get("pose"); + sdf::ElementPtr inertia = inertial->GetElement("inertia"); + double ixx = inertia->Get("ixx"); + double iyy = inertia->Get("iyy"); + double izz = inertia->Get("izz"); + double ixy = inertia->Get("ixy"); + double ixz = inertia->Get("ixz"); + double iyz = inertia->Get("iyz"); + + sdfmsg << "name [" << linkName + << "] m[" << linkMass + << "] p[" << linkPose + << "] ixx[" << ixx + << "] iyy[" << iyy + << "] izz[" << izz + << "] ixy[" << ixy + << "] ixz[" << ixz + << "] iyz[" << iyz + << "]\n"; + + EXPECT_NEAR(linkMass, linkMasses[linkName], gc_tolerance); + EXPECT_EQ(linkPose, linkPoses[linkName]); + EXPECT_NEAR(ixx, mapIxxIyyIzz[linkName].X(), gc_tolerance); + EXPECT_NEAR(iyy, mapIxxIyyIzz[linkName].Y(), gc_tolerance); + EXPECT_NEAR(izz, mapIxxIyyIzz[linkName].Z(), gc_tolerance); + EXPECT_NEAR(ixy, mapIxyIxzIyz[linkName].X(), gc_tolerance); + EXPECT_NEAR(ixz, mapIxyIxzIyz[linkName].Y(), gc_tolerance); + EXPECT_NEAR(iyz, mapIxyIxzIyz[linkName].Z(), gc_tolerance); + + if (link->HasElement("collision")) + { + for (sdf::ElementPtr coll = link->GetElement("collision"); coll; + coll = coll->GetNextElement("collision")) + { + ++countCollisions; + } + } + if (link->HasElement("visual")) + { + for (sdf::ElementPtr vis = link->GetElement("visual"); vis; + vis = vis->GetNextElement("visual")) + { + ++countVisuals; + } + } + } + + if (_file.compare(SDF_TEST_FILE) == 0) + { + EXPECT_EQ(countCollisions, 7u); + EXPECT_EQ(countVisuals, 7u); + } + else if (_file.compare(SDF_TEST_FILE_COLLISION) == 0) + { + EXPECT_EQ(countCollisions, 6u); + EXPECT_EQ(countVisuals, 0u); + } + else if (_file.compare(SDF_TEST_FILE_VISUAL) == 0) + { + EXPECT_EQ(countCollisions, 0u); + EXPECT_EQ(countVisuals, 6u); + } +} + +///////////////////////////////////////////////// +TEST(SDFParser, FixedJointReductionSimple) +{ + sdf::SDFPtr robot(new sdf::SDF()); + sdf::init(robot); + ASSERT_TRUE(sdf::readFile(SDF_TEST_FILE_SIMPLE, robot)); + + std::map linkMasses; + std::map linkPoses; + std::map mapIxxIyyIzz; + std::map mapIxyIxzIyz; + + const ignition::math::Vector3d defaultIxxIyyIzz(7, 9, 11); + { + std::string linkName = "link1"; + linkMasses[linkName] = 300; + linkPoses[linkName] = ignition::math::Pose3d(); + mapIxxIyyIzz[linkName] = defaultIxxIyyIzz; + mapIxyIxzIyz[linkName] = ignition::math::Vector3d(); + } + + { + std::string linkName = "link1a"; + linkMasses[linkName] = 300; + linkPoses[linkName] = ignition::math::Pose3d(); + mapIxxIyyIzz[linkName] = defaultIxxIyyIzz; + mapIxyIxzIyz[linkName] = ignition::math::Vector3d(); + } + + { + std::string linkName = "link1b"; + linkMasses[linkName] = 300; + linkPoses[linkName] = ignition::math::Pose3d(); + mapIxxIyyIzz[linkName] = defaultIxxIyyIzz; + mapIxyIxzIyz[linkName] = ignition::math::Vector3d(); + } + + { + std::string linkName = "link1c"; + linkMasses[linkName] = 300; + linkPoses[linkName] = ignition::math::Pose3d(0.2, 0, 0, 0, 0, 0); + mapIxxIyyIzz[linkName] = + defaultIxxIyyIzz + ignition::math::Vector3d(0, 6, 6); + mapIxyIxzIyz[linkName] = ignition::math::Vector3d(); + } + + { + std::string linkName = "link1d"; + linkMasses[linkName] = 300; + linkPoses[linkName] = ignition::math::Pose3d(0.2, 0, 0, 0, 0, 0); + mapIxxIyyIzz[linkName] = + defaultIxxIyyIzz + ignition::math::Vector3d(0, 6, 6); + mapIxyIxzIyz[linkName] = ignition::math::Vector3d(); + } + + { + std::string linkName = "link1e"; + linkMasses[linkName] = 300; + linkPoses[linkName] = ignition::math::Pose3d(0.2, 0, 0, 0, 0, 0); + mapIxxIyyIzz[linkName] = + defaultIxxIyyIzz + ignition::math::Vector3d(0, 6, 6); + mapIxyIxzIyz[linkName] = ignition::math::Vector3d(); + } + + sdf::ElementPtr model = robot->Root()->GetElement("model"); + for (sdf::ElementPtr link = model->GetElement("link"); link; + link = link->GetNextElement("link")) + { + std::string linkName = link->Get("name"); + sdf::ElementPtr inertial = link->GetElement("inertial"); + double linkMass = inertial->Get("mass"); + ignition::math::Pose3d linkPose = + inertial->Get("pose"); + sdf::ElementPtr inertia = inertial->GetElement("inertia"); + double ixx = inertia->Get("ixx"); + double iyy = inertia->Get("iyy"); + double izz = inertia->Get("izz"); + double ixy = inertia->Get("ixy"); + double ixz = inertia->Get("ixz"); + double iyz = inertia->Get("iyz"); + + sdfmsg << "name [" << linkName + << "] m[" << linkMass + << "] p[" << linkPose + << "] ixx[" << ixx + << "] iyy[" << iyy + << "] izz[" << izz + << "] ixy[" << ixy + << "] ixz[" << ixz + << "] iyz[" << iyz + << "]\n"; + + EXPECT_NEAR(linkMass, linkMasses[linkName], gc_tolerance); + EXPECT_EQ(linkPose, linkPoses[linkName]); + EXPECT_NEAR(ixx, mapIxxIyyIzz[linkName].X(), gc_tolerance); + EXPECT_NEAR(iyy, mapIxxIyyIzz[linkName].Y(), gc_tolerance); + EXPECT_NEAR(izz, mapIxxIyyIzz[linkName].Z(), gc_tolerance); + EXPECT_NEAR(ixy, mapIxyIxzIyz[linkName].X(), gc_tolerance); + EXPECT_NEAR(ixz, mapIxyIxzIyz[linkName].Y(), gc_tolerance); + EXPECT_NEAR(iyz, mapIxyIxzIyz[linkName].Z(), gc_tolerance); + } +} diff --git a/sdformat/test/integration/fixed_joint_reduction.urdf b/sdformat/test/integration/fixed_joint_reduction.urdf new file mode 100644 index 0000000..a37b90a --- /dev/null +++ b/sdformat/test/integration/fixed_joint_reduction.urdf @@ -0,0 +1,199 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/test/integration/fixed_joint_reduction_collision.urdf b/sdformat/test/integration/fixed_joint_reduction_collision.urdf new file mode 100644 index 0000000..210a668 --- /dev/null +++ b/sdformat/test/integration/fixed_joint_reduction_collision.urdf @@ -0,0 +1,151 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/test/integration/fixed_joint_reduction_collision_visual_empty_root.sdf b/sdformat/test/integration/fixed_joint_reduction_collision_visual_empty_root.sdf new file mode 100644 index 0000000..1921346 --- /dev/null +++ b/sdformat/test/integration/fixed_joint_reduction_collision_visual_empty_root.sdf @@ -0,0 +1,59 @@ + + + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + + 0.001 + 0 + 0 + 0.001 + 0 + 0.001 + + + + 0 0 0 0 -0 0 + + + 0.03 + + + 177 + + + + 0.007 + + + + + 0.71 + 0.7 + + + + + + 0 0 0 0 -0 0 + + + 0.03 + + + + 0 1 0 1 + + + + 1 + + 0 + + + diff --git a/sdformat/test/integration/fixed_joint_reduction_collision_visual_empty_root.urdf b/sdformat/test/integration/fixed_joint_reduction_collision_visual_empty_root.urdf new file mode 100644 index 0000000..8358b47 --- /dev/null +++ b/sdformat/test/integration/fixed_joint_reduction_collision_visual_empty_root.urdf @@ -0,0 +1,57 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.007 + 0.7 + + 177 + + + + + + + 0.71 + + + + + + + 0 1 0 1 + + + + script_uri_71_name + + + + diff --git a/sdformat/test/integration/fixed_joint_reduction_collision_visual_extension.sdf b/sdformat/test/integration/fixed_joint_reduction_collision_visual_extension.sdf new file mode 100644 index 0000000..37d798b --- /dev/null +++ b/sdformat/test/integration/fixed_joint_reduction_collision_visual_extension.sdf @@ -0,0 +1,143 @@ + + + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 4 + + 0.004 + 0 + 0 + 0.004 + 0 + 0.004 + + + + 0 0 0 0 -0 0 + + + 0.02 + + + + + 0 0 0 0 -0 0 + + + 0.03 + + + 177 + + + + 0.007 + + + + + 0.71 + 0.7 + + + + + + 0 0 0 0 -0 0 + + + 0.05 + + + + + + + + + 0.51 + 0.5 + + + + + + 0 0 0 0 -0 0 + + + 0.03 + + + + + + + + + 0.61 + 0.6 + + + + 166 + + + 0 0 0 0 -0 0 + + + 0.02 + + + + + 0 0 0 0 -0 0 + + + 0.03 + + + + 0 1 0 1 + + + + + 0 0 0 0 -0 0 + + + 0.05 + + + + + + + + 0 0 0 0 -0 0 + + + 0.03 + + + + + + + + + 1 + + + + diff --git a/sdformat/test/integration/fixed_joint_reduction_collision_visual_extension.urdf b/sdformat/test/integration/fixed_joint_reduction_collision_visual_extension.urdf new file mode 100644 index 0000000..edcbe96 --- /dev/null +++ b/sdformat/test/integration/fixed_joint_reduction_collision_visual_extension.urdf @@ -0,0 +1,170 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.007 + 0.7 + + 177 + + + + + + + 0.71 + + + + + + + 0 1 0 1 + + + + script_uri_71_name + + + + 0.6 + 166 + + + + + + + + 0.61 + + + + + + + 0.5 + + + + + + + + 0.51 + + + + + + + + + + + + diff --git a/sdformat/test/integration/fixed_joint_reduction_disabled.urdf b/sdformat/test/integration/fixed_joint_reduction_disabled.urdf new file mode 100644 index 0000000..e16e65e --- /dev/null +++ b/sdformat/test/integration/fixed_joint_reduction_disabled.urdf @@ -0,0 +1,160 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/test/integration/fixed_joint_reduction_simple.urdf b/sdformat/test/integration/fixed_joint_reduction_simple.urdf new file mode 100644 index 0000000..3d5773e --- /dev/null +++ b/sdformat/test/integration/fixed_joint_reduction_simple.urdf @@ -0,0 +1,212 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/test/integration/fixed_joint_reduction_visual.urdf b/sdformat/test/integration/fixed_joint_reduction_visual.urdf new file mode 100644 index 0000000..340ab80 --- /dev/null +++ b/sdformat/test/integration/fixed_joint_reduction_visual.urdf @@ -0,0 +1,151 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/test/integration/force_torque_sensor.cc b/sdformat/test/integration/force_torque_sensor.cc new file mode 100644 index 0000000..59ab717 --- /dev/null +++ b/sdformat/test/integration/force_torque_sensor.cc @@ -0,0 +1,50 @@ +/* + * Copyright 2013 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include "sdf/sdf.hh" + +#include "test_config.h" + +const std::string SDF_TEST_FILE = std::string(PROJECT_SOURCE_PATH) + + "/test/integration/force_torque_sensor.urdf"; + +///////////////////////////////////////////////// +TEST(SDFParser, ForceTorqueSensorTest) +{ + sdf::SDFPtr robot(new sdf::SDF()); + sdf::init(robot); + ASSERT_TRUE(sdf::readFile(SDF_TEST_FILE, robot)); + + sdf::ElementPtr model = robot->Root()->GetElement("model"); + for (sdf::ElementPtr joint = model->GetElement("joint"); joint; + joint = joint->GetNextElement("joint")) + { + std::string jointName = joint->Get("name"); + if (jointName == "joint_1") + { + // Sensor tag was specified + EXPECT_TRUE(joint->HasElement("sensor")); + } + else if (jointName == "joint_2") + { + // No sensor tag was specified + EXPECT_FALSE(joint->HasElement("sensor")); + } + } +} diff --git a/sdformat/test/integration/force_torque_sensor.urdf b/sdformat/test/integration/force_torque_sensor.urdf new file mode 100644 index 0000000..4b96add --- /dev/null +++ b/sdformat/test/integration/force_torque_sensor.urdf @@ -0,0 +1,54 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + 1 + 100.0 + 1 + + child + + + + + + diff --git a/sdformat/test/integration/frame.cc b/sdformat/test/integration/frame.cc new file mode 100644 index 0000000..e02bb8d --- /dev/null +++ b/sdformat/test/integration/frame.cc @@ -0,0 +1,1252 @@ +/* + * Copyright 2015 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include "sdf/sdf.hh" + +#include "test_config.h" + +//////////////////////////////////////// +// Test parsing a model element that has a frame element +TEST(Frame, ModelFrame) +{ + std::ostringstream stream; + std::string version = SDF_VERSION; + stream + << "" + << "" + << " " + << " 1 1 0 0 0 0" + << " " + << " 1 0 0 0 0 0" + << " " + << "" + << ""; + + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readString(stream.str(), sdfParsed)); + + // Verify correct parsing + + // model + EXPECT_TRUE(sdfParsed->Root()->HasElement("model")); + sdf::ElementPtr modelElem = sdfParsed->Root()->GetElement("model"); + EXPECT_TRUE(modelElem->HasAttribute("name")); + EXPECT_EQ(modelElem->Get("name"), "my_model"); + + // model frame + EXPECT_TRUE(modelElem->HasElement("frame")); + sdf::ElementPtr frameElem = modelElem->GetElement("frame"); + EXPECT_TRUE(frameElem->HasAttribute("name")); + EXPECT_EQ(frameElem->Get("name"), "mframe"); + + // model frame pose + EXPECT_TRUE(frameElem->HasElement("pose")); + sdf::ElementPtr poseElem = frameElem->GetElement("pose"); + EXPECT_TRUE(poseElem->HasAttribute("frame")); + EXPECT_EQ(poseElem->Get("frame"), "/world"); + EXPECT_EQ(poseElem->Get(), + ignition::math::Pose3d(1, 1, 0, 0, 0, 0)); + + // model pose + EXPECT_TRUE(modelElem->HasElement("pose")); + sdf::ElementPtr modelPoseElem = modelElem->GetElement("pose"); + EXPECT_TRUE(modelPoseElem->HasAttribute("frame")); + EXPECT_EQ(modelPoseElem->Get("frame"), "mframe"); + EXPECT_EQ(modelPoseElem->Get(), + ignition::math::Pose3d(1, 0, 0, 0, 0, 0)); + + // link + EXPECT_TRUE(modelElem->HasElement("link")); + sdf::ElementPtr linkElem = modelElem->GetElement("link"); + EXPECT_TRUE(linkElem->HasAttribute("name")); + EXPECT_EQ(linkElem->Get("name"), "link"); +} + +//////////////////////////////////////// +// Test parsing a model element with an empty frame element +TEST(Frame, FrameDefaultPose) +{ + std::ostringstream stream; + std::string version = SDF_VERSION; + stream + << "" + << "" + << " " + << " " + << "" + << ""; + + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readString(stream.str(), sdfParsed)); + + // Verify correct parsing + + // model + EXPECT_TRUE(sdfParsed->Root()->HasElement("model")); + sdf::ElementPtr modelElem = sdfParsed->Root()->GetElement("model"); + EXPECT_TRUE(modelElem->HasAttribute("name")); + EXPECT_EQ(modelElem->Get("name"), "my_model"); + + // model frame + EXPECT_TRUE(modelElem->HasElement("frame")); + sdf::ElementPtr frameElem = modelElem->GetElement("frame"); + EXPECT_TRUE(frameElem->HasAttribute("name")); + EXPECT_EQ(frameElem->Get("name"), "mframe"); + + // model frame pose + EXPECT_TRUE(!frameElem->HasElement("pose")); + sdf::ElementPtr poseElem = frameElem->GetElement("pose"); + EXPECT_TRUE(poseElem->HasAttribute("frame")); + EXPECT_EQ(poseElem->Get("frame"), ""); + EXPECT_EQ(poseElem->Get(), + ignition::math::Pose3d(0, 0, 0, 0, 0, 0)); + + // link + EXPECT_TRUE(modelElem->HasElement("link")); + sdf::ElementPtr linkElem = modelElem->GetElement("link"); + EXPECT_TRUE(linkElem->HasAttribute("name")); + EXPECT_EQ(linkElem->Get("name"), "link"); +} + +//////////////////////////////////////// +// Test parsing a model element with no frames - for backward compatibility +TEST(Frame, NoFrame) +{ + std::ostringstream stream; + std::string version = SDF_VERSION; + stream + << "" + << "" + << " " + << "" + << ""; + + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readString(stream.str(), sdfParsed)); + + // Verify correct parsing + + // model + EXPECT_TRUE(sdfParsed->Root()->HasElement("model")); + sdf::ElementPtr modelElem = sdfParsed->Root()->GetElement("model"); + EXPECT_TRUE(modelElem->HasAttribute("name")); + EXPECT_EQ(modelElem->Get("name"), "my_model"); + + { + // model frame + EXPECT_TRUE(!modelElem->HasElement("frame")); + sdf::ElementPtr frameElem = modelElem->GetElement("frame"); + EXPECT_TRUE(frameElem->HasAttribute("name")); + EXPECT_EQ(frameElem->Get("name"), ""); + + // model frame pose + EXPECT_TRUE(!frameElem->HasElement("pose")); + sdf::ElementPtr poseElem = frameElem->GetElement("pose"); + EXPECT_TRUE(poseElem->HasAttribute("frame")); + EXPECT_EQ(poseElem->Get("frame"), ""); + EXPECT_EQ(poseElem->Get(), + ignition::math::Pose3d(0, 0, 0, 0, 0, 0)); + } + + // link + EXPECT_TRUE(modelElem->HasElement("link")); + sdf::ElementPtr linkElem = modelElem->GetElement("link"); + EXPECT_TRUE(linkElem->HasAttribute("name")); + EXPECT_EQ(linkElem->Get("name"), "link"); + + { + // link frame + EXPECT_TRUE(!linkElem->HasElement("frame")); + sdf::ElementPtr frameElem = linkElem->GetElement("frame"); + EXPECT_TRUE(frameElem->HasAttribute("name")); + EXPECT_EQ(frameElem->Get("name"), ""); + + // link frame pose + EXPECT_TRUE(!frameElem->HasElement("pose")); + sdf::ElementPtr poseElem = frameElem->GetElement("pose"); + EXPECT_TRUE(poseElem->HasAttribute("frame")); + EXPECT_EQ(poseElem->Get("frame"), ""); + EXPECT_EQ(poseElem->Get(), + ignition::math::Pose3d(0, 0, 0, 0, 0, 0)); + } +} + +//////////////////////////////////////// +// Test parsing a link element that has a frame element +TEST(Frame, LinkFrame) +{ + std::ostringstream stream; + std::string version = SDF_VERSION; + stream + << "" + << "" + << " " + << " " + << " 1 0 2 0 0 0" + << " " + << " 0 5 0 0 0 0" + << " " + << "" + << ""; + + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readString(stream.str(), sdfParsed)); + + // Verify correct parsing + + // model + EXPECT_TRUE(sdfParsed->Root()->HasElement("model")); + sdf::ElementPtr modelElem = sdfParsed->Root()->GetElement("model"); + EXPECT_TRUE(modelElem->HasAttribute("name")); + EXPECT_EQ(modelElem->Get("name"), "my_model"); + + // link + EXPECT_TRUE(modelElem->HasElement("link")); + sdf::ElementPtr linkElem = modelElem->GetElement("link"); + EXPECT_TRUE(linkElem->HasAttribute("name")); + EXPECT_EQ(linkElem->Get("name"), "link"); + + // link frame + EXPECT_TRUE(linkElem->HasElement("frame")); + sdf::ElementPtr frameElem = linkElem->GetElement("frame"); + EXPECT_TRUE(frameElem->HasAttribute("name")); + EXPECT_EQ(frameElem->Get("name"), "lframe"); + + // link frame pose + EXPECT_TRUE(frameElem->HasElement("pose")); + sdf::ElementPtr poseElem = frameElem->GetElement("pose"); + EXPECT_TRUE(poseElem->HasAttribute("frame")); + EXPECT_EQ(poseElem->Get("frame"), "model"); + EXPECT_EQ(poseElem->Get(), + ignition::math::Pose3d(1, 0, 2, 0, 0, 0)); + + // link pose + EXPECT_TRUE(linkElem->HasElement("pose")); + sdf::ElementPtr linkPoseElem = linkElem->GetElement("pose"); + EXPECT_TRUE(linkPoseElem->HasAttribute("frame")); + EXPECT_EQ(linkPoseElem->Get("frame"), "lframe"); + EXPECT_EQ(linkPoseElem->Get(), + ignition::math::Pose3d(0, 5, 0, 0, 0, 0)); +} + +//////////////////////////////////////// +// Test parsing a joint element that has a frame element +TEST(Frame, JointFrame) +{ + std::ostringstream stream; + std::string version = SDF_VERSION; + stream + << "" + << "" + << " " + << " " + << " " + << " parent" + << " child" + << " " + << " 1 0 0" + << " " + << " " + << " 0 0 1 0 0 0" + << " " + << " 0 2 1 0 0 0" + << " " + << "" + << ""; + + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readString(stream.str(), sdfParsed)); + + // Verify correct parsing + + // model + EXPECT_TRUE(sdfParsed->Root()->HasElement("model")); + sdf::ElementPtr modelElem = sdfParsed->Root()->GetElement("model"); + EXPECT_TRUE(modelElem->HasAttribute("name")); + EXPECT_EQ(modelElem->Get("name"), "my_model"); + + // link + EXPECT_TRUE(modelElem->HasElement("link")); + sdf::ElementPtr linkElem = modelElem->GetElement("link"); + EXPECT_TRUE(linkElem->HasAttribute("name")); + EXPECT_EQ(linkElem->Get("name"), "parent"); + linkElem = linkElem->GetNextElement("link"); + EXPECT_TRUE(linkElem != NULL); + EXPECT_TRUE(linkElem->HasAttribute("name")); + EXPECT_EQ(linkElem->Get("name"), "child"); + + // joint + EXPECT_TRUE(modelElem->HasElement("joint")); + sdf::ElementPtr jointElem = modelElem->GetElement("joint"); + EXPECT_TRUE(jointElem->HasAttribute("name")); + EXPECT_EQ(jointElem->Get("name"), "revjoint"); + EXPECT_TRUE(jointElem->HasAttribute("type")); + EXPECT_EQ(jointElem->Get("type"), "revolute"); + + // joint links + EXPECT_TRUE(jointElem->HasElement("parent")); + EXPECT_EQ(jointElem->Get("parent"), "parent"); + EXPECT_TRUE(jointElem->HasElement("child")); + EXPECT_EQ(jointElem->Get("child"), "child"); + + // joint axis + EXPECT_TRUE(jointElem->HasElement("axis")); + sdf::ElementPtr axisElem = jointElem->GetElement("axis"); + + EXPECT_TRUE(axisElem->HasElement("xyz")); + EXPECT_EQ(axisElem->Get("xyz"), + ignition::math::Vector3d(1, 0, 0)); + + // joint frame + EXPECT_TRUE(jointElem->HasElement("frame")); + sdf::ElementPtr frameElem = jointElem->GetElement("frame"); + EXPECT_TRUE(frameElem->HasAttribute("name")); + EXPECT_EQ(frameElem->Get("name"), "jframe"); + + // joint frame pose + EXPECT_TRUE(frameElem->HasElement("pose")); + sdf::ElementPtr poseElem = frameElem->GetElement("pose"); + EXPECT_TRUE(poseElem->HasAttribute("frame")); + EXPECT_EQ(poseElem->Get("frame"), "child"); + EXPECT_EQ(poseElem->Get(), + ignition::math::Pose3d(0, 0, 1, 0, 0, 0)); + + // joint pose + EXPECT_TRUE(jointElem->HasElement("pose")); + sdf::ElementPtr jointPoseElem = jointElem->GetElement("pose"); + EXPECT_TRUE(jointPoseElem->HasAttribute("frame")); + EXPECT_EQ(jointPoseElem->Get("frame"), "jframe"); + EXPECT_EQ(jointPoseElem->Get(), + ignition::math::Pose3d(0, 2, 1, 0, 0, 0)); +} + +//////////////////////////////////////// +// Test parsing a collision element that has a frame element +TEST(Frame, CollisionFrame) +{ + std::ostringstream stream; + std::string version = SDF_VERSION; + stream + << "" + << "" + << " " + << " " + << " " + << " 1 3 1 0 0 0" + << " " + << " 0 2 0 0 0 0" + << " " + << " " + << "" + << ""; + + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readString(stream.str(), sdfParsed)); + + // Verify correct parsing + + // model + EXPECT_TRUE(sdfParsed->Root()->HasElement("model")); + sdf::ElementPtr modelElem = sdfParsed->Root()->GetElement("model"); + EXPECT_TRUE(modelElem->HasAttribute("name")); + EXPECT_EQ(modelElem->Get("name"), "my_model"); + + // link + EXPECT_TRUE(modelElem->HasElement("link")); + sdf::ElementPtr linkElem = modelElem->GetElement("link"); + EXPECT_TRUE(linkElem->HasAttribute("name")); + EXPECT_EQ(linkElem->Get("name"), "link"); + + // collision + EXPECT_TRUE(linkElem->HasElement("collision")); + sdf::ElementPtr collisionElem = linkElem->GetElement("collision"); + EXPECT_TRUE(collisionElem->HasAttribute("name")); + EXPECT_EQ(collisionElem->Get("name"), "collision"); + + // collision frame + EXPECT_TRUE(collisionElem->HasElement("frame")); + sdf::ElementPtr frameElem = collisionElem->GetElement("frame"); + EXPECT_TRUE(frameElem->HasAttribute("name")); + EXPECT_EQ(frameElem->Get("name"), "cframe"); + + // collision frame pose + EXPECT_TRUE(frameElem->HasElement("pose")); + sdf::ElementPtr poseElem = frameElem->GetElement("pose"); + EXPECT_TRUE(poseElem->HasAttribute("frame")); + EXPECT_EQ(poseElem->Get("frame"), "link"); + EXPECT_EQ(poseElem->Get(), + ignition::math::Pose3d(1, 3, 1, 0, 0, 0)); + + // collision pose + EXPECT_TRUE(collisionElem->HasElement("pose")); + sdf::ElementPtr collisionPoseElem = collisionElem->GetElement("pose"); + EXPECT_TRUE(collisionPoseElem->HasAttribute("frame")); + EXPECT_EQ(collisionPoseElem->Get("frame"), "cframe"); + EXPECT_EQ(collisionPoseElem->Get(), + ignition::math::Pose3d(0, 2, 0, 0, 0, 0)); +} + +//////////////////////////////////////// +// Test parsing a visual element that has a frame element +TEST(Frame, VisualFrame) +{ + std::ostringstream stream; + std::string version = SDF_VERSION; + stream + << "" + << "" + << " " + << " " + << " " + << " 1 1 1 0 0 0" + << " " + << " 2 2 2 0 0 0" + << " " + << " " + << "" + << ""; + + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readString(stream.str(), sdfParsed)); + + // Verify correct parsing + + // model + EXPECT_TRUE(sdfParsed->Root()->HasElement("model")); + sdf::ElementPtr modelElem = sdfParsed->Root()->GetElement("model"); + EXPECT_TRUE(modelElem->HasAttribute("name")); + EXPECT_EQ(modelElem->Get("name"), "my_model"); + + // link + EXPECT_TRUE(modelElem->HasElement("link")); + sdf::ElementPtr linkElem = modelElem->GetElement("link"); + EXPECT_TRUE(linkElem->HasAttribute("name")); + EXPECT_EQ(linkElem->Get("name"), "link"); + + // visual + EXPECT_TRUE(linkElem->HasElement("visual")); + sdf::ElementPtr visualElem = linkElem->GetElement("visual"); + EXPECT_TRUE(visualElem->HasAttribute("name")); + EXPECT_EQ(visualElem->Get("name"), "visual"); + + // visual frame + EXPECT_TRUE(visualElem->HasElement("frame")); + sdf::ElementPtr frameElem = visualElem->GetElement("frame"); + EXPECT_TRUE(frameElem->HasAttribute("name")); + EXPECT_EQ(frameElem->Get("name"), "vframe"); + + // visual frame pose + EXPECT_TRUE(frameElem->HasElement("pose")); + sdf::ElementPtr poseElem = frameElem->GetElement("pose"); + EXPECT_TRUE(poseElem->HasAttribute("frame")); + EXPECT_EQ(poseElem->Get("frame"), "link"); + EXPECT_EQ(poseElem->Get(), + ignition::math::Pose3d(1, 1, 1, 0, 0, 0)); + + // visual pose + EXPECT_TRUE(visualElem->HasElement("pose")); + sdf::ElementPtr visualPoseElem = visualElem->GetElement("pose"); + EXPECT_TRUE(visualPoseElem->HasAttribute("frame")); + EXPECT_EQ(visualPoseElem->Get("frame"), "vframe"); + EXPECT_EQ(visualPoseElem->Get(), + ignition::math::Pose3d(2, 2, 2, 0, 0, 0)); +} + +//////////////////////////////////////// +// Test parsing an inertial element that has a frame element +TEST(Frame, InertialFrame) +{ + std::ostringstream stream; + std::string version = SDF_VERSION; + stream + << "" + << "" + << " " + << " " + << " " + << " 1 2 3 0 0 0" + << " " + << " 3 2 1 0 0 0" + << " " + << " " + << "" + << ""; + + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readString(stream.str(), sdfParsed)); + + // Verify correct parsing + + // model + EXPECT_TRUE(sdfParsed->Root()->HasElement("model")); + sdf::ElementPtr modelElem = sdfParsed->Root()->GetElement("model"); + EXPECT_TRUE(modelElem->HasAttribute("name")); + EXPECT_EQ(modelElem->Get("name"), "my_model"); + + // link + EXPECT_TRUE(modelElem->HasElement("link")); + sdf::ElementPtr linkElem = modelElem->GetElement("link"); + EXPECT_TRUE(linkElem->HasAttribute("name")); + EXPECT_EQ(linkElem->Get("name"), "link"); + + // inertial + EXPECT_TRUE(linkElem->HasElement("inertial")); + sdf::ElementPtr inertialElem = linkElem->GetElement("inertial"); + + // inertial frame + EXPECT_TRUE(inertialElem->HasElement("frame")); + sdf::ElementPtr frameElem = inertialElem->GetElement("frame"); + EXPECT_TRUE(frameElem->HasAttribute("name")); + EXPECT_EQ(frameElem->Get("name"), "iframe"); + + // inertial frame pose + EXPECT_TRUE(frameElem->HasElement("pose")); + sdf::ElementPtr poseElem = frameElem->GetElement("pose"); + EXPECT_TRUE(poseElem->HasAttribute("frame")); + EXPECT_EQ(poseElem->Get("frame"), "link"); + EXPECT_EQ(poseElem->Get(), + ignition::math::Pose3d(1, 2, 3, 0, 0, 0)); + + // inertial pose + EXPECT_TRUE(inertialElem->HasElement("pose")); + sdf::ElementPtr inertialPoseElem = inertialElem->GetElement("pose"); + EXPECT_TRUE(inertialPoseElem->HasAttribute("frame")); + EXPECT_EQ(inertialPoseElem->Get("frame"), "iframe"); + EXPECT_EQ(inertialPoseElem->Get(), + ignition::math::Pose3d(3, 2, 1, 0, 0, 0)); +} + +//////////////////////////////////////// +// Test parsing a light element that has a frame element +TEST(Frame, LightFrame) +{ + std::ostringstream stream; + std::string version = SDF_VERSION; + stream + << "" + << "" + << " " + << " 0.1 10 0 0 0 0" + << " " + << " 0.1 0 0 0 0 0" + << " 0.2 0.3 0.4 1" + << " 0.3 0.4 0.5 1" + << "" + << ""; + + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readString(stream.str(), sdfParsed)); + + // Verify correct parsing + + // light + EXPECT_TRUE(sdfParsed->Root()->HasElement("light")); + sdf::ElementPtr lightElem = sdfParsed->Root()->GetElement("light"); + EXPECT_TRUE(lightElem->HasAttribute("name")); + EXPECT_EQ(lightElem->Get("name"), "my_light"); + EXPECT_TRUE(lightElem->HasAttribute("type")); + EXPECT_EQ(lightElem->Get("type"), "directional"); + + // light frame + EXPECT_TRUE(lightElem->HasElement("frame")); + sdf::ElementPtr frameElem = lightElem->GetElement("frame"); + EXPECT_TRUE(frameElem->HasAttribute("name")); + EXPECT_EQ(frameElem->Get("name"), "lframe"); + + // light frame pose + EXPECT_TRUE(frameElem->HasElement("pose")); + sdf::ElementPtr poseElem = frameElem->GetElement("pose"); + EXPECT_TRUE(poseElem->HasAttribute("frame")); + EXPECT_EQ(poseElem->Get("frame"), "/world"); + EXPECT_EQ(poseElem->Get(), + ignition::math::Pose3d(0.1, 10, 0, 0, 0, 0)); + + // light pose + EXPECT_TRUE(lightElem->HasElement("pose")); + sdf::ElementPtr lightPoseElem = lightElem->GetElement("pose"); + EXPECT_TRUE(lightPoseElem->HasAttribute("frame")); + EXPECT_EQ(lightPoseElem->Get("frame"), "lframe"); + EXPECT_EQ(lightPoseElem->Get(), + ignition::math::Pose3d(0.1, 0, 0, 0, 0, 0)); + + // diffuse + EXPECT_TRUE(lightElem->HasElement("diffuse")); + sdf::ElementPtr diffuseElem = lightElem->GetElement("diffuse"); + EXPECT_EQ(diffuseElem->Get(), sdf::Color(0.2f, 0.3f, 0.4f, 1.0f)); + + // specular + EXPECT_TRUE(lightElem->HasElement("specular")); + sdf::ElementPtr specularElem = lightElem->GetElement("specular"); + EXPECT_EQ(specularElem->Get(), + sdf::Color(0.3f, 0.4f, 0.5f, 1.0f)); +} + +//////////////////////////////////////// +// Test parsing an actor element that has a frame element +TEST(Frame, ActorFrame) +{ + std::ostringstream stream; + std::string version = SDF_VERSION; + stream + << "" + << "" + << " " + << " 1 5 0 0 0 0" + << " " + << " 0.1 3 0 0 0 0" + << " " + << " moonwalk.dae" + << " " + << " " + << " walk.dae" + << " " + << " + + + + + diff --git a/sdformat/test/integration/model/cococan/model-1_2.sdf b/sdformat/test/integration/model/cococan/model-1_2.sdf new file mode 100644 index 0000000..525d59c --- /dev/null +++ b/sdformat/test/integration/model/cococan/model-1_2.sdf @@ -0,0 +1,25 @@ + + + + 0 0 0.5 0 0 0 + + + + + 1 1 1 + + + + + + + 1 1 1 + + + + + + + + + diff --git a/sdformat/test/integration/model/cococan/model-1_4.sdf b/sdformat/test/integration/model/cococan/model-1_4.sdf new file mode 100644 index 0000000..2eda8a6 --- /dev/null +++ b/sdformat/test/integration/model/cococan/model-1_4.sdf @@ -0,0 +1,25 @@ + + + + 0 0 0.5 0 0 0 + + + + + 1 1 1 + + + + + + + 1 1 1 + + + + + + + + + diff --git a/sdformat/test/integration/model/cococan/model.config b/sdformat/test/integration/model/cococan/model.config new file mode 100644 index 0000000..59fa966 --- /dev/null +++ b/sdformat/test/integration/model/cococan/model.config @@ -0,0 +1,17 @@ + + + + cococan + 1.0 + model-1_2.sdf + model-1_4.sdf + model-100.sdf + + Testo + testo@osrfoundation.org + + + + A simple box with multiple versions + + diff --git a/sdformat/test/integration/model/cococan_malformed/model.config b/sdformat/test/integration/model/cococan_malformed/model.config new file mode 100644 index 0000000..bfe8525 --- /dev/null +++ b/sdformat/test/integration/model/cococan_malformed/model.config @@ -0,0 +1,14 @@ + + + + cococan + 1.0 + + Testo + testo@osrfoundation.org + + + + A simple box with multiple versions + + diff --git a/sdformat/test/integration/model/cococan_noversiontag/model-1_2.sdf b/sdformat/test/integration/model/cococan_noversiontag/model-1_2.sdf new file mode 100644 index 0000000..525d59c --- /dev/null +++ b/sdformat/test/integration/model/cococan_noversiontag/model-1_2.sdf @@ -0,0 +1,25 @@ + + + + 0 0 0.5 0 0 0 + + + + + 1 1 1 + + + + + + + 1 1 1 + + + + + + + + + diff --git a/sdformat/test/integration/model/cococan_noversiontag/model-1_4.sdf b/sdformat/test/integration/model/cococan_noversiontag/model-1_4.sdf new file mode 100644 index 0000000..2eda8a6 --- /dev/null +++ b/sdformat/test/integration/model/cococan_noversiontag/model-1_4.sdf @@ -0,0 +1,25 @@ + + + + 0 0 0.5 0 0 0 + + + + + 1 1 1 + + + + + + + 1 1 1 + + + + + + + + + diff --git a/sdformat/test/integration/model/cococan_noversiontag/model.config b/sdformat/test/integration/model/cococan_noversiontag/model.config new file mode 100644 index 0000000..70c91e9 --- /dev/null +++ b/sdformat/test/integration/model/cococan_noversiontag/model.config @@ -0,0 +1,16 @@ + + + + cococan + 1.0 + model-1_2.sdf + model-1_4.sdf + + Testo + testo@osrfoundation.org + + + + A simple box with multiple versions + + diff --git a/sdformat/test/integration/model/double_pendulum.sdf b/sdformat/test/integration/model/double_pendulum.sdf new file mode 100644 index 0000000..0d6890c --- /dev/null +++ b/sdformat/test/integration/model/double_pendulum.sdf @@ -0,0 +1,204 @@ + + + + + + 100 + + + 0 0 0.01 0 0 0 + + + 0.8 + 0.02 + + + + + + + + -0.275 0 1.1 0 0 0 + + 0.2 0.2 2.2 + + + + + + + 0 0 0.01 0 0 0 + + + 0.8 + 0.02 + + + + + -0.275 0 1.1 0 0 0 + + 0.2 0.2 2.2 + + + + + + 0 0 2.1 -1.5708 0 0 + 0 + + 0 0 0.5 0 0 0 + + + -0.05 0 0 0 1.5708 0 + + + 0.1 + 0.3 + + + + + + + + 0 0 1.0 0 1.5708 0 + + + 0.1 + 0.2 + + + + + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + + + + + -0.05 0 0 0 1.5708 0 + + + 0.1 + 0.3 + + + + + 0 0 1.0 0 1.5708 0 + + + 0.1 + 0.2 + + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + + + + 0.25 1.0 2.1 -2 0 0 + 0 + + 0 0 0.5 0 0 0 + + + 0 0 0 0 1.5708 0 + + + 0.08 + 0.3 + + + + + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + + + + + 0 0 0 0 1.5708 0 + + + 0.08 + 0.3 + + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + + + + base + upper_link + + 1.0 0 0 + + + + + upper_link + lower_link + + 1.0 0 0 + + + + diff --git a/sdformat/test/integration/model/pr2.sdf b/sdformat/test/integration/model/pr2.sdf new file mode 100644 index 0000000..7a5ad82 --- /dev/null +++ b/sdformat/test/integration/model/pr2.sdf @@ -0,0 +1,3036 @@ + + + + 0 + + 0 + + 118.001000 + -0.062421 0.000000 0.201365 0.000000 -0.000000 0.000000 + + 8.431730 + -0.009720 + 1.901570 + 8.533050 + -0.007380 + 3.787470 + + + + 0.000000 0.000000 0.071000 0.000000 -0.000000 0.000000 + + + 0.001000 0.001000 0.001000 + + + + + + + 0.010000 0.010000 0.010000 + + + + + -0.290000 0.000000 0.851000 0.000000 -0.000000 0.000000 + + + 0.050000 0.370000 0.300000 + + + + + -0.290000 0.000000 0.851000 0.000000 -0.000000 0.000000 + + + 0.050000 0.370000 0.300000 + + + + + 0.000000 0.000000 0.051000 0.000000 -0.000000 0.000000 + + + model://pr2/meshes/base_v0/base_L.stl + + + + + 0.000000 0.000000 0.051000 0.000000 -0.000000 0.000000 + + + model://pr2/meshes/base_v0/base.dae + + + + + 100.000000 + + base_footprint_geom_base_link + __default_topic__ + + + + + 1 + 1 + 20.000000 + 0.275000 0.000000 0.303000 0.000000 -0.000000 0.000000 + + + + 640 + 1.000000 + -2.268900 + 2.268900 + + + + 0.080000 + 10.000000 + 0.010000 + + + + + + + + 0 + -0.224600 0.224600 0.079200 0.000000 -0.000000 0.000000 + + 3.473080 + 0.000000 0.000000 0.070000 0.000000 -0.000000 0.000000 + + 0.012412 + -0.000712 + 0.000503 + 0.015218 + -0.000004 + 0.011764 + + + + + + model://pr2/meshes/base_v0/caster_L.stl + + + + + + + model://pr2/meshes/base_v0/caster.stl + + + + + + + 0 + -0.224600 0.273600 0.079200 0.000000 -0.000000 0.000000 + + 0.440360 + + 0.012412 + -0.000712 + 0.000503 + 0.015218 + -0.000004 + 0.011764 + + + + 0.000000 0.000000 0.000000 1.570800 -0.000000 0.000000 + + + 0.074792 + 0.034000 + + + + + + + model://pr2/meshes/base_v0/wheel.dae + + + + + + + 0 + -0.224600 0.175600 0.079200 0.000000 -0.000000 0.000000 + + 0.440360 + + 0.012412 + 0.000712 + 0.000503 + 0.015218 + 0.000004 + 0.011764 + + + + 0.000000 0.000000 0.000000 1.570800 -0.000000 0.000000 + + + 0.074792 + 0.034000 + + + + + + + model://pr2/meshes/base_v0/wheel.dae + + + + + + + 0 + -0.224600 -0.224600 0.079200 0.000000 -0.000000 0.000000 + + 3.473080 + 0.000000 0.000000 0.070000 0.000000 -0.000000 0.000000 + + 0.012412 + -0.000712 + 0.000503 + 0.015218 + -0.000004 + 0.011764 + + + + + + model://pr2/meshes/base_v0/caster_L.stl + + + + + + + model://pr2/meshes/base_v0/caster.stl + + + + + + + 0 + -0.224600 -0.175600 0.079200 0.000000 -0.000000 0.000000 + + 0.440360 + + 0.012412 + -0.000712 + 0.000503 + 0.015218 + -0.000004 + 0.011764 + + + + 0.000000 0.000000 0.000000 1.570800 -0.000000 0.000000 + + + 0.074792 + 0.034000 + + + + + + + model://pr2/meshes/base_v0/wheel.dae + + + + + + + 0 + -0.224600 -0.273600 0.079200 0.000000 -0.000000 0.000000 + + 0.440360 + + 0.012412 + -0.000712 + 0.000503 + 0.015218 + -0.000004 + 0.011764 + + + + 0.000000 0.000000 0.000000 1.570800 -0.000000 0.000000 + + + 0.074792 + 0.034000 + + + + + + + model://pr2/meshes/base_v0/wheel.dae + + + + + + + 0 + 0.224600 0.224600 0.079200 0.000000 -0.000000 0.000000 + + 3.473080 + 0.000000 0.000000 0.070000 0.000000 -0.000000 0.000000 + + 0.012412 + -0.000712 + 0.000503 + 0.015218 + -0.000004 + 0.011764 + + + + + + model://pr2/meshes/base_v0/caster_L.stl + + + + + + + model://pr2/meshes/base_v0/caster.stl + + + + + + + 0 + 0.224600 0.273600 0.079200 0.000000 -0.000000 0.000000 + + 0.440360 + + 0.012412 + -0.000712 + 0.000503 + 0.015218 + -0.000004 + 0.011764 + + + + 0.000000 0.000000 0.000000 1.570800 -0.000000 0.000000 + + + 0.074792 + 0.034000 + + + + + + + model://pr2/meshes/base_v0/wheel.dae + + + + + + + 0 + 0.224600 0.175600 0.079200 0.000000 -0.000000 0.000000 + + 0.440360 + + 0.012412 + -0.000712 + 0.000503 + 0.015218 + -0.000004 + 0.011764 + + + + 0.000000 0.000000 0.000000 1.570800 -0.000000 0.000000 + + + 0.074792 + 0.034000 + + + + + + + model://pr2/meshes/base_v0/wheel.dae + + + + + + + 0 + 0.224600 -0.224600 0.079200 0.000000 -0.000000 0.000000 + + 3.473080 + 0.000000 0.000000 0.070000 0.000000 -0.000000 0.000000 + + 0.012412 + -0.000712 + 0.000503 + 0.015218 + -0.000004 + 0.011764 + + + + + + model://pr2/meshes/base_v0/caster_L.stl + + + + + + + model://pr2/meshes/base_v0/caster.stl + + + + + + + 0 + 0.224600 -0.175600 0.079200 0.000000 -0.000000 0.000000 + + 0.440360 + + 0.012412 + -0.000712 + 0.000503 + 0.015218 + -0.000004 + 0.011764 + + + + 0.000000 0.000000 0.000000 1.570800 -0.000000 0.000000 + + + 0.074792 + 0.034000 + + + + + + + model://pr2/meshes/base_v0/wheel.dae + + + + + + + 0 + 0.224600 -0.273600 0.079200 0.000000 -0.000000 0.000000 + + 0.440360 + + 0.012412 + -0.000712 + 0.000503 + 0.015218 + -0.000004 + 0.011764 + + + + 0.000000 0.000000 0.000000 1.570800 -0.000000 0.000000 + + + 0.074792 + 0.034000 + + + + + + + model://pr2/meshes/base_v0/wheel.dae + + + + + + + 0 + -0.050000 0.000000 0.790675 0.000000 -0.000000 0.000000 + + 36.449000 + -0.099499 -0.000004 -0.086764 0.000000 -0.000000 0.000000 + + 2.792330 + 0.004280 + -0.160631 + 2.521060 + 0.029689 + 0.536551 + + + + + + model://pr2/meshes/torso_v0/torso_lift_L.stl + + + + + + + model://pr2/meshes/torso_v0/torso_lift.dae + + + + + 100.000000 + + torso_lift_link_geom + __default_topic__ + + + + + + 0 + -0.067070 0.000000 1.172130 0.000000 -0.000000 0.000000 + + 6.339000 + 0.010907 0.031693 0.090507 0.000000 -0.000000 0.000000 + + 0.032498 + 0.000636 + 0.002585 + 0.046546 + -0.002453 + 0.057653 + + + + + + model://pr2/meshes/head_v0/head_pan_L.stl + + + + + + + model://pr2/meshes/head_v0/head_pan.dae + + + + + + + + stereo_projection_pattern_high_res_red.png + 0.959931 + 0.100000 + 10.000000 + 0.023200 0.110000 0.119100 0 -1.570793 0 + + + 0 + 0.000930 0.000000 1.172130 0.000000 -0.000000 0.000000 + + 5.319000 + -0.005151 -0.014635 0.072819 0.000000 -0.000000 0.000000 + + 0.126134 + 0.000237 + 0.011881 + 0.165102 + 0.001606 + 0.166947 + + + + + + model://pr2/meshes/head_v0/head_tilt_L.stl + + + + + + + model://pr2/meshes/head_v0/head_tilt.dae + + + + + -0.147067 0.012500 0.291953 0.000000 -0.000000 0.000000 + + + 0.000500 + + + + + -0.147067 0.012500 0.291953 0.000000 -0.000000 0.000000 + + + 0.000250 + + + + + + + + -0.147067 0.017500 0.291953 0.000000 -0.000000 0.000000 + + + 0.000500 + + + + + -0.147067 0.017500 0.291953 0.000000 -0.000000 0.000000 + + + 0.000250 + + + + + + + + -0.114800 0.000000 0.155500 0.000000 -0.000000 0.000000 + + + 0.000500 + + + + + -0.114800 0.000000 0.155500 0.000000 -0.000000 0.000000 + + + model://pr2/meshes/sensors/kinect_prosilica_v0/115x100_swept_back--coarse.STL + 0.001000 0.001000 0.001000 + + + + + -0.161257 0.012500 0.244421 0.000000 -0.000000 0.000000 + + + 0.000500 + + + + + -0.161257 0.012500 0.244421 0.000000 -0.000000 0.000000 + + + 0.000250 + + + + + + + + 0.023200 0.000000 0.064500 0.000000 -0.000000 0.000000 + + + 0.010000 0.010000 0.010000 + + + + + 0.023200 0.000000 0.064500 0.000000 -0.000000 0.000000 + + + 0.010000 0.010000 0.010000 + + + + + + + + 0 + 0 + 1.000000 + -0.147067 0.012500 0.291953 0.000000 -0.000000 0.000000 + + 0.994838 + + 640 + 480 + L8 + + + 0.010000 + 5.000000 + + + + + 1.000000 + -0.161257 0.012500 0.244421 0.000000 -0.000000 0.000000 + + 1.120501 + + 320 + 240 + R8G8B8 + + + 0.100000 + 100.000000 + + + + + 1.000000 + -0.161257 0.012500 0.244421 0.000000 -0.000000 0.000000 + + 1.120501 + + 320 + 240 + R8G8B8 + + + 0.100000 + 100.000000 + + + + + 1 + 1 + 25.000000 + 0.068200 0.060000 0.114600 0.000000 -0.000000 0.000000 + + 0.785398 + + 640 + 480 + L8 + + + 0.100000 + 100.000000 + + + + + 1 + 25.000000 + 0.068200 -0.030000 0.114600 0.000000 -0.000000 0.000000 + + 0.785398 + + 640 + 480 + L8 + + + 0.100000 + 100.000000 + + + + + 25.000000 + 0.068200 0.030000 0.114600 0.000000 -0.000000 0.000000 + + 1.570796 + + 640 + 480 + BAYER_BGGR8 + + + 0.100000 + 100.000000 + + + + + 25.000000 + 0.068200 -0.060000 0.114600 0.000000 -0.000000 0.000000 + + 1.570796 + + 640 + 480 + BAYER_BGGR8 + + + 0.100000 + 100.000000 + + + + + 20.000000 + 0.069657 -0.110000 0.119100 0.000000 -0.000000 0.000000 + + 0.785398 + + 2448 + 2050 + R8G8B8 + + + 0.100000 + 100.000000 + + + + + + + 0 + 0 + -0.050000 0.188000 0.790675 0.000000 -0.000000 0.000000 + + 25.799300 + -0.001201 0.024513 -0.098231 0.000000 -0.000000 0.000000 + + 0.866179 + -0.060865 + -0.121181 + 0.874217 + -0.058866 + 0.273538 + + + + + + model://pr2/meshes/shoulder_v0/shoulder_pan.stl + + + + + + + model://pr2/meshes/shoulder_v0/shoulder_pan.dae + + + + + + + 0 + 0 + 0.050000 0.188000 0.790675 0.000000 -0.000000 0.000000 + + 2.749880 + 0.021950 -0.026640 -0.031270 0.000000 -0.000000 0.000000 + + 0.021056 + 0.004967 + -0.001948 + 0.021272 + 0.001104 + 0.019758 + + + + + + model://pr2/meshes/shoulder_v0/shoulder_lift.stl + + + + + + + model://pr2/meshes/shoulder_v0/shoulder_lift.dae + + + + + + + 0 + 0 + 0.050000 0.188000 0.790675 0.000000 -0.000000 0.000000 + + 6.117690 + 0.210551 0.016309 -0.000561 0.000000 -0.000000 0.000000 + + 0.025306 + -0.003393 + 0.000608 + 0.084737 + -0.000200 + 0.086016 + + + + + + model://pr2/meshes/shoulder_v0/upper_arm_roll_L.stl + + + + + + + model://pr2/meshes/shoulder_v0/upper_arm_roll.stl + + + + + + + model://pr2/meshes/upper_arm_v0/upper_arm.stl + + + + + + + model://pr2/meshes/upper_arm_v0/upper_arm.dae + + + + + + + 0 + 0 + 0.450000 0.188000 0.790675 0.000000 -0.000000 0.000000 + + 1.903270 + 0.010140 0.000320 -0.012110 0.000000 -0.000000 0.000000 + + 0.003465 + 0.000041 + 0.000432 + 0.004416 + -0.000040 + 0.003592 + + + + + + model://pr2/meshes/upper_arm_v0/elbow_flex.stl + + + + + + + model://pr2/meshes/upper_arm_v0/elbow_flex.dae + + + + + + + 0 + 0 + 0.450000 0.188000 0.790675 0.000000 -0.000000 0.000000 + + 2.689680 + 0.180727 -0.000163 -0.008583 0.000000 -0.000000 0.000000 + + 0.014668 + 0.000052 + 0.000656 + 0.026279 + -0.000013 + 0.027775 + + + + + + model://pr2/meshes/upper_arm_v0/forearm_roll_L.stl + + + + + + + model://pr2/meshes/upper_arm_v0/forearm_roll.stl + + + + + + + model://pr2/meshes/forearm_v0/forearm.stl + + + + + + + model://pr2/meshes/forearm_v0/forearm.dae + + + + + 25.000000 + 0.135000 0.000000 0.044000 -1.570800 -0.562869 0.000000 + + 1.570796 + + 640 + 480 + R8G8B8 + + + 0.100000 + 100.000000 + + + + + + + 0 + 0 + 0.771000 0.188000 0.790675 0.000000 -0.000000 0.000000 + + 0.614020 + -0.001570 0.000000 -0.000750 0.000000 -0.000000 0.000000 + + 0.000652 + 0.000000 + 0.000003 + 0.000198 + 0.000000 + 0.000645 + + + + + + model://pr2/meshes/forearm_v0/wrist_flex.stl + + + + + + + model://pr2/meshes/forearm_v0/wrist_flex.dae + + + + + + + 0 + 0 + 0.771000 0.188000 0.790675 0.000000 -0.000000 0.000000 + + 0.681070 + 0.056408 0.000451 -0.001014 0.000000 -0.000000 0.000000 + + 0.011352 + -0.000016 + -0.000001 + 0.011677 + -0.000001 + 0.011866 + + + + + + model://pr2/meshes/forearm_v0/wrist_roll_L.stl + + + + + + + model://pr2/meshes/forearm_v0/wrist_roll.stl + + + + + + + 0.001000 0.001000 0.001000 + + + + + + + 0.001000 0.001000 0.001000 + + + + + + + model://pr2/meshes/gripper_v0/gripper_palm.stl + + + + + + + model://pr2/meshes/gripper_v0/gripper_palm.dae + + + + + + + 0 + 0 + 0.847910 0.198000 0.790675 0.000000 -0.000000 0.000000 + + 0.171260 + 0.035980 0.017300 -0.001640 0.000000 -0.000000 0.000000 + + 0.000078 + 0.000001 + -0.000010 + 0.000197 + -0.000003 + 0.000181 + + + + + + model://pr2/meshes/gripper_v0/l_finger.stl + + + + + + 500.000000 + 500.000000 + 0.000000 + 0.000000 + + + + + 1000000.000000 + 1.000000 + 100.000000 + 0.000000 + + + + + + + + model://pr2/meshes/gripper_v0/l_finger.dae + + + + + + + 0 + 0 + 0.939280 0.202950 0.790675 0.000000 -0.000000 0.000000 + + 0.044190 + 0.004230 0.002840 0.000000 0.000000 -0.000000 0.000000 + + 0.000008 + 0.000006 + 0.000000 + 0.000010 + 0.000000 + 0.000015 + + + + + + model://pr2/meshes/gripper_v0/l_finger_tip.stl + + + + + + 500.000000 + 500.000000 + 0.000000 + 0.000000 + + + + + 10000000.000000 + 1.000000 + 100.000000 + 0.000000 + + + + + + + + model://pr2/meshes/gripper_v0/l_finger_tip.dae + + + + + 100.000000 + + l_gripper_l_finger_tip_link_geom + __default_topic__ + + + + + + 0 + 0 + 0.939280 0.188000 0.790675 0.000000 -0.000000 0.000000 + + 0.010000 + + 0.001000 + 0.000000 + 0.000000 + 0.001000 + 0.000000 + 0.001000 + + + + + + 0 + 0 + 0.939280 0.188000 0.790675 0.000000 -0.000000 0.000000 + + 0.010000 + + 0.000100 + 0.000000 + 0.000000 + 0.000100 + 0.000000 + 0.000100 + + + + + + 0 + 0 + 0.847910 0.178000 0.790675 0.000000 -0.000000 0.000000 + + 0.173890 + 0.035760 -0.017360 -0.000950 0.000000 -0.000000 0.000000 + + 0.000077 + -0.000002 + -0.000008 + 0.000198 + 0.000002 + 0.000181 + + + + 0.000000 0.000000 0.000000 -3.141590 0.000000 0.000000 + + + model://pr2/meshes/gripper_v0/l_finger.stl + + + + + + 500.000000 + 500.000000 + 0.000000 + 0.000000 + + + + + 1000000.000000 + 1.000000 + 100.000000 + 0.000000 + + + + + + 0.000000 0.000000 0.000000 -3.141590 0.000000 0.000000 + + + model://pr2/meshes/gripper_v0/l_finger.dae + + + + + + + 0 + 0 + 0.939280 0.173050 0.790675 0.000000 -0.000000 0.000000 + + 0.044190 + 0.004230 -0.002840 0.000000 0.000000 -0.000000 0.000000 + + 0.000008 + -0.000006 + 0.000000 + 0.000010 + 0.000000 + 0.000015 + + + + 0.000000 0.000000 0.000000 -3.141590 0.000000 0.000000 + + + model://pr2/meshes/gripper_v0/l_finger_tip.stl + + + + + + 500.000000 + 500.000000 + 0.000000 + 0.000000 + + + + + 10000000.000000 + 1.000000 + 100.000000 + 0.000000 + + + + + + 0.000000 0.000000 0.000000 -3.141590 0.000000 0.000000 + + + model://pr2/meshes/gripper_v0/l_finger_tip.dae + + + + + 100.000000 + + l_gripper_r_finger_tip_link_geom + __default_topic__ + + + + + + 0 + 0.048930 0.000000 1.017680 0.000000 -0.000000 0.000000 + + 0.592000 + -0.001134 0.001667 -0.007067 0.000000 -0.000000 0.000000 + + 0.001296 + 0.000023 + 0.000037 + 0.001086 + 0.000035 + 0.000895 + + + + + + model://pr2/meshes/tilting_laser_v0/tilting_hokuyo_L.stl + + + + + + 0.000000 + 0.000000 + 0.000000 + 0.000000 + + + + + 1000000000000.000000 + 10000.000000 + 100.000000 + 0.000000 + + + + + + + + model://pr2/meshes/tilting_laser_v0/tilting_hokuyo.dae + + + + + 40.000000 + 0.000000 0.000000 0.030000 0.000000 -0.000000 0.000000 + + + + 640 + 1.000000 + -1.396263 + 1.396263 + + + + 0.080000 + 10.000000 + 0.010000 + + + + + + + 0 + 0 + -0.050000 -0.188000 0.790675 0.000000 -0.000000 0.000000 + + 25.799300 + -0.001201 0.024513 -0.098231 0.000000 -0.000000 0.000000 + + 0.866179 + -0.060865 + -0.121181 + 0.874217 + -0.058866 + 0.273538 + + + + + + model://pr2/meshes/shoulder_v0/shoulder_pan.stl + + + + + + 0.000000 + 0.000000 + 0.000000 + 0.000000 + + + + + 1000000000000.000000 + 10000.000000 + 100.000000 + 0.000000 + + + + + + + + model://pr2/meshes/shoulder_v0/shoulder_pan.dae + + + + + + + 0 + 0 + 0.050000 -0.188000 0.790675 0.000000 -0.000000 0.000000 + + 2.749880 + 0.021950 -0.026640 -0.031270 0.000000 -0.000000 0.000000 + + 0.021056 + 0.004967 + -0.001948 + 0.021272 + 0.001104 + 0.019758 + + + + + + model://pr2/meshes/shoulder_v0/shoulder_lift.stl + + + + + + 0.000000 + 0.000000 + 0.000000 + 0.000000 + + + + + 1000000000000.000000 + 10000.000000 + 100.000000 + 0.000000 + + + + + + + + model://pr2/meshes/shoulder_v0/shoulder_lift.dae + + + + + + + 0 + 0 + 0.050000 -0.188000 0.790675 0.000000 -0.000000 0.000000 + + 6.117690 + 0.210482 -0.015945 -0.000197 0.000000 -0.000000 0.000000 + + 0.025378 + 0.003757 + -0.000709 + 0.084737 + -0.000179 + 0.086088 + + + + + + model://pr2/meshes/shoulder_v0/upper_arm_roll_L.stl + + + + + + + model://pr2/meshes/shoulder_v0/upper_arm_roll.stl + + + + + + + model://pr2/meshes/upper_arm_v0/upper_arm.stl + + + + + + + model://pr2/meshes/upper_arm_v0/upper_arm.dae + + + + + + + 0 + 0 + 0.450000 -0.188000 0.790675 0.000000 -0.000000 0.000000 + + 1.903270 + 0.010140 0.000320 -0.012110 0.000000 -0.000000 0.000000 + + 0.003465 + 0.000041 + 0.000432 + 0.004416 + -0.000040 + 0.003592 + + + + + + model://pr2/meshes/upper_arm_v0/elbow_flex.stl + + + + + + + model://pr2/meshes/upper_arm_v0/elbow_flex.dae + + + + + + + 0 + 0 + 0.450000 -0.188000 0.790675 0.000000 -0.000000 0.000000 + + 2.689680 + 0.180727 -0.000163 -0.008583 0.000000 -0.000000 0.000000 + + 0.014668 + 0.000052 + 0.000656 + 0.026279 + -0.000013 + 0.027775 + + + + + + model://pr2/meshes/upper_arm_v0/forearm_roll_L.stl + + + + + + + model://pr2/meshes/upper_arm_v0/forearm_roll.stl + + + + + + + model://pr2/meshes/forearm_v0/forearm.stl + + + + + + + model://pr2/meshes/forearm_v0/forearm.dae + + + + + 25.000000 + 0.135000 0.000000 0.044000 1.570800 -0.562869 -0.000000 + + 1.570796 + + 640 + 480 + R8G8B8 + + + 0.100000 + 100.000000 + + + + + + + 0 + 0 + 0.771000 -0.188000 0.790675 0.000000 -0.000000 0.000000 + + 0.614020 + -0.001570 0.000000 -0.000750 0.000000 -0.000000 0.000000 + + 0.000652 + 0.000000 + 0.000003 + 0.000198 + 0.000000 + 0.000645 + + + + + + model://pr2/meshes/forearm_v0/wrist_flex.stl + + + + + + + model://pr2/meshes/forearm_v0/wrist_flex.dae + + + + + + + 0 + 0 + 0.771000 -0.188000 0.790675 0.000000 -0.000000 0.000000 + + 0.681070 + 0.056408 0.000451 -0.001014 0.000000 -0.000000 0.000000 + + 0.011352 + -0.000016 + -0.000001 + 0.011677 + -0.000001 + 0.011866 + + + + + + model://pr2/meshes/forearm_v0/wrist_roll_L.stl + + + + + + + model://pr2/meshes/forearm_v0/wrist_roll.stl + + + + + + + 0.001000 0.001000 0.001000 + + + + + + + 0.001000 0.001000 0.001000 + + + + + + + model://pr2/meshes/gripper_v0/gripper_palm.stl + + + + + + + model://pr2/meshes/gripper_v0/gripper_palm.dae + + + + + + + 0 + 0 + 0.847910 -0.178000 0.790675 0.000000 -0.000000 0.000000 + + 0.171260 + 0.035980 0.017300 -0.001640 0.000000 -0.000000 0.000000 + + 0.000078 + 0.000001 + 0.000010 + 0.000197 + -0.000003 + 0.000181 + + + + + + model://pr2/meshes/gripper_v0/l_finger.stl + + + + + + 500.000000 + 500.000000 + 0.000000 + 0.000000 + + + + + 1000000.000000 + 1.000000 + 100.000000 + 0.000000 + + + + + + + + model://pr2/meshes/gripper_v0/l_finger.dae + + + + + + + 0 + 0 + 0.939280 -0.173050 0.790675 0.000000 -0.000000 0.000000 + + 0.044190 + 0.004230 0.002840 0.000000 0.000000 -0.000000 0.000000 + + 0.000008 + 0.000006 + 0.000000 + 0.000010 + 0.000000 + 0.000015 + + + + + + model://pr2/meshes/gripper_v0/l_finger_tip.stl + + + + + + 500.000000 + 500.000000 + 0.000000 + 0.000000 + + + + + 10000000.000000 + 1.000000 + 100.000000 + 0.000000 + + + + + + + + model://pr2/meshes/gripper_v0/l_finger_tip.dae + + + + + 100.000000 + + r_gripper_l_finger_tip_link_geom + __default_topic__ + + + + + + 0 + 0 + 0.939280 -0.188000 0.790675 0.000000 -0.000000 0.000000 + + 0.010000 + + 0.001000 + 0.000000 + 0.000000 + 0.001000 + 0.000000 + 0.001000 + + + + + + 0 + 0 + 0.939280 -0.188000 0.790675 0.000000 -0.000000 0.000000 + + 0.010000 + + 0.000100 + 0.000000 + 0.000000 + 0.000100 + 0.000000 + 0.000100 + + + + + + 0 + 0 + 0.847910 -0.198000 0.790675 0.000000 -0.000000 0.000000 + + 0.173890 + 0.035760 -0.017360 -0.000950 0.000000 -0.000000 0.000000 + + 0.000077 + -0.000002 + -0.000008 + 0.000198 + 0.000002 + 0.000181 + + + + 0.000000 0.000000 0.000000 -3.141590 0.000000 0.000000 + + + model://pr2/meshes/gripper_v0/l_finger.stl + + + + + + 500.000000 + 500.000000 + 0.000000 + 0.000000 + + + + + 1000000.000000 + 1.000000 + 100.000000 + 0.000000 + + + + + + 0.000000 0.000000 0.000000 -3.141590 0.000000 0.000000 + + + model://pr2/meshes/gripper_v0/l_finger.dae + + + + + + + 0 + 0 + 0.939280 -0.202950 0.790675 0.000000 -0.000000 0.000000 + + 0.044190 + 0.004230 -0.002840 0.000000 0.000000 -0.000000 0.000000 + + 0.000008 + -0.000006 + 0.000000 + 0.000010 + 0.000000 + 0.000015 + + + + 0.000000 0.000000 0.000000 -3.141590 0.000000 0.000000 + + + model://pr2/meshes/gripper_v0/l_finger_tip.stl + + + + + + 500.000000 + 500.000000 + 0.000000 + 0.000000 + + + + + 10000000.000000 + 1.000000 + 100.000000 + 0.000000 + + + + + + 0.000000 0.000000 0.000000 -3.141590 0.000000 0.000000 + + + model://pr2/meshes/gripper_v0/l_finger_tip.dae + + + + + 100.000000 + + r_gripper_r_finger_tip_link_geom + __default_topic__ + + + + + + 0 + -0.150000 0.000000 0.751000 0.000000 -0.000000 0.000000 + + 1.000000 + + 0.001000 + 0.000000 + 0.000000 + 0.001000 + 0.000000 + 0.001000 + + + + + + 0 + 0 + 0.829910 -0.157000 0.790675 0.000000 -0.000000 0.000000 + + 0.171260 + 0.035980 0.017300 -0.001640 0.000000 -0.000000 0.000000 + + 0.000078 + 0.000001 + -0.000010 + 0.000197 + -0.000003 + 0.000181 + + + + + + 0 + 0 + 0.829910 -0.219000 0.790675 0.000000 -0.000000 0.000000 + + 0.173890 + 0.035760 -0.017360 -0.000950 0.000000 -0.000000 0.000000 + + 0.000077 + -0.000002 + -0.000008 + 0.000198 + 0.000002 + 0.000181 + + + + + + 0 + 0 + 0.829910 0.219000 0.790675 0.000000 -0.000000 0.000000 + + 0.171260 + 0.035980 0.017300 -0.001640 0.000000 -0.000000 0.000000 + + 0.000078 + 0.000001 + 0.000010 + 0.000197 + -0.000003 + 0.000181 + + + + + + 0 + 0 + 0.829910 0.157000 0.790675 0.000000 -0.000000 0.000000 + + 0.173890 + 0.035760 -0.017360 -0.000950 0.000000 -0.000000 0.000000 + + 0.000077 + -0.000002 + 0.000008 + 0.000198 + 0.000002 + 0.000181 + + + + + + base_footprint + bl_caster_rotation_link + + 0.000000 0.000000 1.000000 + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + bl_caster_rotation_link + bl_caster_l_wheel_link + + 0.000000 1.000000 0.000000 + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + bl_caster_rotation_link + bl_caster_r_wheel_link + + 0.000000 1.000000 0.000000 + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + base_footprint + br_caster_rotation_link + + 0.000000 0.000000 1.000000 + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + br_caster_rotation_link + br_caster_l_wheel_link + + 0.000000 1.000000 0.000000 + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + br_caster_rotation_link + br_caster_r_wheel_link + + 0.000000 1.000000 0.000000 + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + base_footprint + fl_caster_rotation_link + + 0.000000 0.000000 1.000000 + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + fl_caster_rotation_link + fl_caster_l_wheel_link + + 0.000000 1.000000 0.000000 + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + fl_caster_rotation_link + fl_caster_r_wheel_link + + 0.000000 1.000000 0.000000 + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + base_footprint + fr_caster_rotation_link + + 0.000000 0.000000 1.000000 + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + fr_caster_rotation_link + fr_caster_l_wheel_link + + 0.000000 1.000000 0.000000 + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + fr_caster_rotation_link + fr_caster_r_wheel_link + + 0.000000 1.000000 0.000000 + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + base_footprint + torso_lift_link + + 0.000000 0.000000 1.000000 + + 0.000000 + 0.330000 + 0.000000 + 4.000000 + + + + + torso_lift_link + head_pan_link + + 0.000000 0.000000 1.000000 + + 2.000000 + 0.000000 + + + -3.006993 + 3.006993 + 0.000000 + 4.000000 + + + + + head_pan_link + head_tilt_link + + 0.000000 1.000000 0.000000 + + 10.000000 + 0.000000 + + + -0.471237 + 1.396260 + 0.000000 + 4.000000 + + + + + torso_lift_link + l_shoulder_pan_link + + 0.000000 0.000000 1.000000 + + 10.000000 + 0.000000 + + + -0.714602 + 2.285404 + 0.000000 + 4.000000 + + + + + l_shoulder_pan_link + l_shoulder_lift_link + + 0.000000 1.000000 0.000000 + + 10.000000 + 0.000000 + + + -0.523601 + 1.396300 + 0.000000 + 4.000000 + + + + + l_shoulder_lift_link + l_upper_arm_roll_link + + 1.000000 0.000000 0.000000 + + 0.100000 + 0.000000 + + + -0.800000 + 3.900008 + 0.000000 + 4.000000 + + + + + l_upper_arm_roll_link + l_elbow_flex_link + + 0.000000 1.000000 0.000000 + + 1.000000 + 0.000000 + + + -2.321305 + 0.000000 + 0.000000 + 4.000000 + + + + + l_elbow_flex_link + l_forearm_roll_link + + 1.000000 0.000000 0.000000 + + 0.100000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + l_forearm_roll_link + l_wrist_flex_link + + 0.000000 1.000000 0.000000 + + 0.100000 + 0.000000 + + + -2.180004 + 0.000000 + 0.000000 + 4.000000 + + + + + l_wrist_flex_link + l_wrist_roll_link + + 1.000000 0.000000 0.000000 + + 0.100000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + l_wrist_roll_link + l_gripper_l_finger_link + + 0.000000 0.000000 1.000000 + + 0.020000 + 0.000000 + + + 0.000000 + 0.548000 + 0.000000 + 4.000000 + + + + + l_gripper_l_finger_link + l_gripper_l_finger_tip_link + + 0.000000 0.000000 -1.000000 + + 0.001000 + 0.000000 + + + 0.000000 + 0.548000 + 0.000000 + 4.000000 + + + + + l_wrist_roll_link + l_gripper_motor_slider_link + + 1.000000 0.000000 0.000000 + + -0.100000 + 0.100000 + 0.000000 + 4.000000 + + + + + l_gripper_motor_slider_link + l_gripper_motor_screw_link + + 0.000000 1.000000 0.000000 + + 0.000100 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + l_wrist_roll_link + l_gripper_r_finger_link + + 0.000000 0.000000 -1.000000 + + 0.020000 + 0.000000 + + + 0.000000 + 0.548000 + 0.000000 + 4.000000 + + + + + l_gripper_r_finger_link + l_gripper_r_finger_tip_link + + 0.000000 0.000000 1.000000 + + 0.001000 + 0.000000 + + + 0.000000 + 0.548000 + 0.000000 + 4.000000 + + + + + torso_lift_link + laser_tilt_mount_link + + 0.000000 1.000000 0.000000 + + 0.008000 + 0.000000 + + + -0.785400 + 1.483530 + 0.000000 + 4.000000 + + + + + torso_lift_link + r_shoulder_pan_link + + 0.000000 0.000000 1.000000 + + 10.000000 + 0.000000 + + + -2.285404 + 0.714602 + 0.000000 + 4.000000 + + + + + r_shoulder_pan_link + r_shoulder_lift_link + + 0.000000 1.000000 0.000000 + + 10.000000 + 0.000000 + + + -0.523601 + 1.396300 + 0.000000 + 4.000000 + + + + + r_shoulder_lift_link + r_upper_arm_roll_link + + 1.000000 0.000000 0.000000 + + 0.100000 + 0.000000 + + + -3.900008 + 0.800000 + 0.000000 + 4.000000 + + + + + r_upper_arm_roll_link + r_elbow_flex_link + + 0.000000 1.000000 0.000000 + + 1.000000 + 0.000000 + + + -2.321305 + 0.000000 + 0.000000 + 4.000000 + + + + + r_elbow_flex_link + r_forearm_roll_link + + 1.000000 0.000000 0.000000 + + 0.100000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + r_forearm_roll_link + r_wrist_flex_link + + 0.000000 1.000000 0.000000 + + 0.100000 + 0.000000 + + + -2.180004 + 0.000000 + 0.000000 + 4.000000 + + + + + r_wrist_flex_link + r_wrist_roll_link + + 1.000000 0.000000 0.000000 + + 0.100000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + r_wrist_roll_link + r_gripper_l_finger_link + + 0.000000 0.000000 1.000000 + + 0.020000 + 0.000000 + + + 0.000000 + 0.548000 + 0.000000 + 4.000000 + + + + + r_gripper_l_finger_link + r_gripper_l_finger_tip_link + + 0.000000 0.000000 -1.000000 + + 0.001000 + 0.000000 + + + 0.000000 + 0.548000 + 0.000000 + 4.000000 + + + + + r_wrist_roll_link + r_gripper_motor_slider_link + + 1.000000 0.000000 0.000000 + + 0.000000 + 0.000000 + + + -0.100000 + 0.100000 + 0.000000 + 4.000000 + + + + + r_gripper_motor_slider_link + r_gripper_motor_screw_link + + 0.000000 1.000000 0.000000 + + 0.000100 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + r_wrist_roll_link + r_gripper_r_finger_link + + 0.000000 0.000000 -1.000000 + + 0.020000 + 0.000000 + + + 0.000000 + 0.548000 + 0.000000 + 4.000000 + + + + + r_gripper_r_finger_link + r_gripper_r_finger_tip_link + + 0.000000 0.000000 1.000000 + + 0.001000 + 0.000000 + + + 0.000000 + 0.548000 + 0.000000 + 4.000000 + + + + + base_footprint + torso_lift_motor_screw_link + + 0.000000 0.000000 1.000000 + + 0.000100 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + torso_lift_link + torso_lift_motor_screw_link + 3141.600000 + + 0.000000 0.000000 1.000000 + + 0.000000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + r_gripper_r_finger_tip_link + r_gripper_motor_screw_link + -3141.600000 + + 0.000000 1.000000 0.000000 + + 0.000000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + r_gripper_l_finger_tip_link + r_gripper_motor_screw_link + 3141.600000 + + 0.000000 1.000000 0.000000 + + 0.000000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + 0.058910 -0.031000 0.000000 0.000000 -0.000000 0.000000 + r_gripper_r_parallel_link + r_wrist_roll_link + + 0.000000 0.000000 -1.000000 + + 0.200000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + 0.058910 0.031000 0.000000 0.000000 -0.000000 0.000000 + r_gripper_l_parallel_link + r_wrist_roll_link + + 0.000000 0.000000 1.000000 + + 0.200000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + -0.018000 -0.021000 0.000000 0.000000 -0.000000 0.000000 + r_gripper_r_parallel_link + r_gripper_r_finger_tip_link + + 0.000000 0.000000 1.000000 + + 0.000000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + -0.018000 0.021000 0.000000 0.000000 -0.000000 0.000000 + r_gripper_l_parallel_link + r_gripper_l_finger_tip_link + + 0.000000 0.000000 1.000000 + + 0.000000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + r_gripper_r_finger_tip_link + r_gripper_l_finger_tip_link + + 0.000000 1.000000 0.000000 + + 0.000000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + l_gripper_r_finger_tip_link + l_gripper_motor_screw_link + -3141.600000 + + 0.000000 1.000000 0.000000 + + 0.000000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + l_gripper_l_finger_tip_link + l_gripper_motor_screw_link + 3141.600000 + + 0.000000 1.000000 0.000000 + + 0.000000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + 0.058910 -0.031000 0.000000 0.000000 -0.000000 0.000000 + l_gripper_r_parallel_link + l_wrist_roll_link + + 0.000000 0.000000 -1.000000 + + 0.200000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + 0.058910 0.031000 0.000000 0.000000 -0.000000 0.000000 + l_gripper_l_parallel_link + l_wrist_roll_link + + 0.000000 0.000000 1.000000 + + 0.200000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + -0.018000 -0.021000 0.000000 0.000000 -0.000000 0.000000 + l_gripper_r_parallel_link + l_gripper_r_finger_tip_link + + 0.000000 0.000000 1.000000 + + 0.000000 + 0.000000 + + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + -0.018000 0.021000 0.000000 0.000000 -0.000000 0.000000 + l_gripper_l_parallel_link + l_gripper_l_finger_tip_link + + 0.000000 0.000000 1.000000 + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + l_gripper_r_finger_tip_link + l_gripper_l_finger_tip_link + + 0.000000 1.000000 0.000000 + + -10000000000000000.000000 + 10000000000000000.000000 + 0.000000 + 4.000000 + + + + + diff --git a/sdformat/test/integration/model/turtlebot.sdf b/sdformat/test/integration/model/turtlebot.sdf new file mode 100644 index 0000000..cd60592 --- /dev/null +++ b/sdformat/test/integration/model/turtlebot.sdf @@ -0,0 +1,474 @@ + + + + + + 0.001453 -0.000453 0.029787 0 0 0 + + 0.058640 + 0.000124 + 0.000615 + 0.058786 + 0.000014 + 1.532440 + + 2.234000 + + + + + -0.043340 0 0.084757 0 0 0 + + + 0.233502 0.314845 0.006401 + + + + + -0.043340 0 0.084757 0 0 0 + + + model://turtlebot/meshes/plate_0_logo.dae + + + + + + -0.002660 0 0.141907 0 0 0 + + + 0.314856 0.314856 0.006401 + + + + + -0.002660 0 0.141907 0 0 0 + + + model://turtlebot/meshes/plate_1_logo.dae + + + + + + -0.002660 0 0.199108 0 0 0 + + + 0.314856 0.314856 0.006401 + + + + + -0.002660 0 0.199108 0 0 0 + + + model://turtlebot/meshes/plate_1_logo.dae + + + + + + -0.015820 0 0.405457 0 0 0 + + + 0.288000 0.315000 0.006401 + + + + + -0.015820 0 0.405457 0 0 0 + + + model://turtlebot/meshes/plate_2_logo.dae + + + + + + -0.002540 0.111468 0.079992 0 0 0 + + + 0.012700 + 0.003175 + + + + + -0.002540 0.111468 0.079992 0 0 0 + + + model://turtlebot/meshes/68-02403-125_Spacer.dae + + + + + + -0.002540 -0.111468 0.079992 0 0 0 + + + 0.012700 + 0.003175 + + + + + -0.002540 -0.111468 0.079992 0 0 0 + + + model://turtlebot/meshes/68-02403-125_Spacer.dae + + + + + + -0.072390 -0.111468 0.079992 0 0 0 + + + 0.012700 + 0.003175 + + + + + -0.072390 -0.111468 0.079992 0 0 0 + + + model://turtlebot/meshes/68-02403-125_Spacer.dae + + + + + + -0.072390 0.111468 0.079992 0 0 0 + + + 0.012700 + 0.003175 + + + + + -0.072390 0.111468 0.079992 0 0 0 + + + model://turtlebot/meshes/68-02403-125_Spacer.dae + + + + + + 0.067640 0.131420 0.087980 0 0 0 + + + 0.038100 + 0.063500 + + + + + 0.067640 0.131420 0.087980 0 0 0 + + + model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae + + + + + + 0.067640 -0.131420 0.087980 0 0 0 + + + 0.038100 + 0.063500 + + + + + 0.067640 -0.131420 0.087980 0 0 0 + + + model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae + + + + + + -0.052832 -0.131420 0.087980 0 0 0 + + + 0.038100 + 0.063500 + + + + + -0.052832 -0.131420 0.087980 0 0 0 + + + model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae + + + + + + -0.052832 0.131420 0.087980 0 0 0 + + + 0.038100 + 0.063500 + + + + + -0.052832 0.131420 0.087980 0 0 0 + + + model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae + + + + + + 0.067640 0.131420 0.145130 0 0 0 + + + 0.038100 + 0.063500 + + + + + 0.067640 0.131420 0.145130 0 0 0 + + + model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae + + + + + + 0.067640 -0.131420 0.145130 0 0 0 + + + 0.038100 + 0.063500 + + + + + 0.067640 -0.131420 0.145130 0 0 0 + + + model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae + + + + + + -0.052832 -0.131420 0.145130 0 0 0 + + + 0.038100 + 0.063500 + + + + + -0.052832 -0.131420 0.145130 0 0 0 + + + model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae + + + + + + -0.052832 0.131420 0.145130 0 0 0 + + + 0.038100 + 0.063500 + + + + + -0.052832 0.131420 0.145130 0 0 0 + + + model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae + + + + + + 0.067640 0.131420 0.202280 0 0 0 + + + 0.011113 + 0.203200 + + + + + 0.067640 0.131420 0.202280 0 0 0 + + + model://turtlebot/meshes/68-02421-8000-RA_Turtlebot_F-F_Standoff.dae + + + + + + 0.067640 -0.131420 0.202280 0 0 0 + + + 0.011113 + 0.203200 + + + + + 0.067640 -0.131420 0.202280 0 0 0 + + + model://turtlebot/meshes/68-02421-8000-RA_Turtlebot_F-F_Standoff.dae + + + + + + -0.052832 -0.131420 0.202280 0 0 0 + + + 0.011113 + 0.203200 + + + + + -0.052832 -0.131420 0.202280 0 0 0 + + + model://turtlebot/meshes/68-02421-8000-RA_Turtlebot_F-F_Standoff.dae + + + + + + -0.052832 0.131420 0.202280 0 0 0 + + + 0.011113 + 0.203200 + + + + + -0.052832 0.131420 0.202280 0 0 0 + + + model://turtlebot/meshes/68-02421-8000-RA_Turtlebot_F-F_Standoff.dae + + + + + + -0.105098 0.098000 0.202308 0 0 0 + + + 0.001111 + 0.008585 + + + + + -0.105098 0.098000 0.202308 0 0 0 + + + model://turtlebot/meshes/68-04556-RA_Kinect_Standoff_Assy.dae + + + + + + -0.105098 -0.098000 0.202308 0 0 0 + + + 0.001111 + 0.008585 + + + + + -0.105098 -0.098000 0.202308 0 0 0 + + + model://turtlebot/meshes/68-04556-RA_Kinect_Standoff_Assy.dae + + + + + + -0.065000 0 0.092000 0 0 0 + + + + 180 + 1.000000 + -2.268928 + 2.268928 + + + + 0.080000 + 10 + 0.010000 + + + + 20 + + + + + model://create + + + + model://kinect + -0.087098 0 0.303857 0 0 0 + + + + create::base + rack + + 0 0 1 + + 0 + 0 + + + + + + kinect::link + rack + + 0 0 1 + + 0 + 0 + + + + + + diff --git a/sdformat/test/integration/model_versions.cc b/sdformat/test/integration/model_versions.cc new file mode 100644 index 0000000..b95b1f9 --- /dev/null +++ b/sdformat/test/integration/model_versions.cc @@ -0,0 +1,75 @@ +/* + * Copyright 2017 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include "sdf/sdf.hh" + +#include "test_config.h" + +TEST(ModelVersionsTest, Empty_ModelFilePath) +{ + std::string modelPath = sdf::getModelFilePath(""); + + EXPECT_EQ(modelPath, ""); +} + +TEST(ModelVersionsTest, NonExistent_ModelFilePath) +{ + const std::string MODEL_PATH = std::string(PROJECT_SOURCE_PATH) + + "/test/integration/model/non-existent/"; + + std::string modelPath = sdf::getModelFilePath(MODEL_PATH); + + EXPECT_EQ(modelPath, ""); +} + +TEST(ModelVersionsTest, MalFormed_ModelFilePath) +{ + const std::string MODEL_PATH = std::string(PROJECT_SOURCE_PATH) + + "/test/integration/model/cococan_malformed/"; + + std::string modelPath = sdf::getModelFilePath(MODEL_PATH); + + EXPECT_EQ(modelPath, ""); +} + +TEST(ModelVersionsTest, NoVersionTag_ModelFilePath) +{ + const std::string MODEL_PATH = std::string(PROJECT_SOURCE_PATH) + + "/test/integration/model/cococan_noversiontag/"; + + std::string modelPath = sdf::getModelFilePath(MODEL_PATH); + + EXPECT_EQ(modelPath, MODEL_PATH + "/model-1_2.sdf"); +} + +TEST(ModelVersionsTest, Correct_ModelFilePath) +{ + const std::string MODEL_PATH = std::string(PROJECT_SOURCE_PATH) + + "/test/integration/model/cococan/"; + + std::string modelPath = sdf::getModelFilePath(MODEL_PATH); + + EXPECT_EQ(modelPath, MODEL_PATH + "/model-1_4.sdf"); +} + +///////////////////////////////////////////////// +int main(int argc, char **argv) +{ + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/sdformat/test/integration/nested_model.cc b/sdformat/test/integration/nested_model.cc new file mode 100644 index 0000000..c4f05db --- /dev/null +++ b/sdformat/test/integration/nested_model.cc @@ -0,0 +1,238 @@ +/* + * Copyright 2015 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include "sdf/sdf.hh" + +#include "test_config.h" + +//////////////////////////////////////// +// Test parsing nested model with joint +TEST(NestedModel, NestedModel) +{ + std::ostringstream stream; + std::string version = "1.5"; + stream + << "" + << "" + << " " + << " " + << " " + << " " + << " " + << " " + << " parent" + << " child" + << " " + << " 1 0 0" + << " " + << " " + << "" + << ""; + + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readString(stream.str(), sdfParsed)); + + // Verify correct parsing + + // top level model + EXPECT_TRUE(sdfParsed->Root()->HasElement("model")); + sdf::ElementPtr modelElem = sdfParsed->Root()->GetElement("model"); + EXPECT_TRUE(modelElem->HasAttribute("name")); + EXPECT_EQ(modelElem->Get("name"), "top_level_model"); + + // top level links + EXPECT_TRUE(modelElem->HasElement("link")); + sdf::ElementPtr linklElem = modelElem->GetElement("link"); + EXPECT_TRUE(linklElem->HasAttribute("name")); + EXPECT_EQ(linklElem->Get("name"), "parent"); + linklElem = linklElem->GetNextElement("link"); + EXPECT_TRUE(linklElem != NULL); + EXPECT_TRUE(linklElem->HasAttribute("name")); + EXPECT_EQ(linklElem->Get("name"), "child"); + + // nested model + EXPECT_TRUE(modelElem->HasElement("model")); + sdf::ElementPtr nestedModelElem = modelElem->GetElement("model"); + + // nested model link + EXPECT_TRUE(nestedModelElem->HasElement("link")); + sdf::ElementPtr nestedLinkElem = nestedModelElem->GetElement("link"); + EXPECT_TRUE(nestedLinkElem->HasAttribute("name")); + EXPECT_EQ(nestedLinkElem->Get("name"), "nested_link01"); + + // top level model joint + EXPECT_TRUE(modelElem->HasElement("joint")); + sdf::ElementPtr jointElem = modelElem->GetElement("joint"); + EXPECT_TRUE(jointElem->HasAttribute("name")); + EXPECT_EQ(jointElem->Get("name"), "top_level_joint"); + EXPECT_TRUE(jointElem->HasAttribute("type")); + EXPECT_EQ(jointElem->Get("type"), "revolute"); + + // joint links + EXPECT_TRUE(jointElem->HasElement("parent")); + EXPECT_EQ(jointElem->Get("parent"), "parent"); + EXPECT_TRUE(jointElem->HasElement("child")); + EXPECT_EQ(jointElem->Get("child"), "child"); + + // joint axis + EXPECT_TRUE(jointElem->HasElement("axis")); + sdf::ElementPtr axisElem = jointElem->GetElement("axis"); + + EXPECT_TRUE(axisElem->HasElement("xyz")); + EXPECT_EQ(axisElem->Get("xyz"), + ignition::math::Vector3d(1, 0, 0)); +} + +//////////////////////////////////////// +// Test parsing nested model states +TEST(NestedModel, State) +{ + std::ostringstream sdfStr; + sdfStr << "" + << "" + << "" + << "" + << " 0 0 0.5 0 0 0" + << " " + << " 0 0 0.5 0 0 0" + << " 0.001 0 0 0 0 0" + << " 0 0.006121 0 0.012288 0 0.001751" + << " 0 0.006121 0 0 0 0" + << " " + << " " + << " 1 0 0.5 0 0 0" + << " " + << " 1.25 0 0.5 0 0 0" + << " 0 -0.001 0 0 0 0" + << " 0 0.000674 0 -0.001268 0 0" + << " 0 0.000674 0 0 0 0" + << " " + << " " + << " 1 1 0.5 0 0 0" + << " " + << " 1.25 1 0.5 0 0 0" + << " 0 0 0.001 0 0 0" + << " 0 0 0 0 0 0" + << " 0 0 0 0 0 0" + << " " + << " " + << " " + << "" + << "" + << "" + << ""; + + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readString(sdfStr.str(), sdfParsed)); + + // load the state sdf + EXPECT_TRUE(sdfParsed->Root()->HasElement("world")); + sdf::ElementPtr worldElem = sdfParsed->Root()->GetElement("world"); + EXPECT_TRUE(worldElem->HasElement("state")); + sdf::ElementPtr stateElem = worldElem->GetElement("state"); + EXPECT_TRUE(stateElem->HasElement("model")); + + sdf::ElementPtr modelStateElem = stateElem->GetElement("model"); + + // model sdf + EXPECT_TRUE(modelStateElem->HasAttribute("name")); + EXPECT_EQ(modelStateElem->Get("name"), "model_00"); + EXPECT_TRUE(modelStateElem->HasElement("pose")); + EXPECT_EQ(modelStateElem->Get("pose"), + ignition::math::Pose3d(0, 0, 0.5, 0, 0, 0)); + EXPECT_TRUE(!modelStateElem->HasElement("joint")); + + // link sdf + EXPECT_TRUE(modelStateElem->HasElement("link")); + sdf::ElementPtr linkStateElem = modelStateElem->GetElement("link"); + EXPECT_TRUE(linkStateElem->HasAttribute("name")); + EXPECT_EQ(linkStateElem->Get("name"), "link_00"); + EXPECT_TRUE(linkStateElem->HasElement("pose")); + EXPECT_EQ(linkStateElem->Get("pose"), + ignition::math::Pose3d(0, 0, 0.5, 0, 0, 0)); + EXPECT_TRUE(linkStateElem->HasElement("velocity")); + EXPECT_EQ(linkStateElem->Get("velocity"), + ignition::math::Pose3d(0.001, 0, 0, 0, 0, 0)); + EXPECT_TRUE(linkStateElem->HasElement("acceleration")); + EXPECT_EQ(linkStateElem->Get("acceleration"), + ignition::math::Pose3d(0, 0.006121, 0, 0.012288, 0, 0.001751)); + EXPECT_TRUE(linkStateElem->HasElement("wrench")); + EXPECT_EQ(linkStateElem->Get("wrench"), + ignition::math::Pose3d(0, 0.006121, 0, 0, 0, 0)); + + // nested model sdf + EXPECT_TRUE(modelStateElem->HasElement("model")); + sdf::ElementPtr nestedModelStateElem = + modelStateElem->GetElement("model"); + EXPECT_TRUE(nestedModelStateElem->HasAttribute("name")); + EXPECT_EQ(nestedModelStateElem->Get("name"), "model_01"); + EXPECT_TRUE(nestedModelStateElem->HasElement("pose")); + EXPECT_EQ(nestedModelStateElem->Get("pose"), + ignition::math::Pose3d(1, 0, 0.5, 0, 0, 0)); + EXPECT_TRUE(!nestedModelStateElem->HasElement("joint")); + + // nested model's link sdf + EXPECT_TRUE(nestedModelStateElem->HasElement("link")); + sdf::ElementPtr nestedLinkStateElem = + nestedModelStateElem->GetElement("link"); + EXPECT_TRUE(nestedLinkStateElem->HasAttribute("name")); + EXPECT_EQ(nestedLinkStateElem->Get("name"), "link_01"); + EXPECT_TRUE(nestedLinkStateElem->HasElement("pose")); + EXPECT_EQ(nestedLinkStateElem->Get("pose"), + ignition::math::Pose3d(1.25, 0, 0.5, 0, 0, 0)); + EXPECT_TRUE(nestedLinkStateElem->HasElement("velocity")); + EXPECT_EQ(nestedLinkStateElem->Get("velocity"), + ignition::math::Pose3d(0, -0.001, 0, 0, 0, 0)); + EXPECT_TRUE(nestedLinkStateElem->HasElement("acceleration")); + EXPECT_EQ(nestedLinkStateElem->Get("acceleration"), + ignition::math::Pose3d(0, 0.000674, 0, -0.001268, 0, 0)); + EXPECT_TRUE(nestedLinkStateElem->HasElement("wrench")); + EXPECT_EQ(nestedLinkStateElem->Get("wrench"), + ignition::math::Pose3d(0, 0.000674, 0, 0, 0, 0)); + + // double nested model sdf + EXPECT_TRUE(nestedModelStateElem->HasElement("model")); + nestedModelStateElem = nestedModelStateElem->GetElement("model"); + EXPECT_TRUE(nestedModelStateElem->HasAttribute("name")); + EXPECT_EQ(nestedModelStateElem->Get("name"), "model_02"); + EXPECT_TRUE(nestedModelStateElem->HasElement("pose")); + EXPECT_EQ(nestedModelStateElem->Get("pose"), + ignition::math::Pose3d(1, 1, 0.5, 0, 0, 0)); + EXPECT_TRUE(!nestedModelStateElem->HasElement("joint")); + + // double nested model's link sdf + EXPECT_TRUE(nestedModelStateElem->HasElement("link")); + nestedLinkStateElem = nestedModelStateElem->GetElement("link"); + EXPECT_TRUE(nestedLinkStateElem->HasAttribute("name")); + EXPECT_EQ(nestedLinkStateElem->Get("name"), "link_02"); + EXPECT_TRUE(nestedLinkStateElem->HasElement("pose")); + EXPECT_EQ(nestedLinkStateElem->Get("pose"), + ignition::math::Pose3d(1.25, 1, 0.5, 0, 0, 0)); + EXPECT_TRUE(nestedLinkStateElem->HasElement("velocity")); + EXPECT_EQ(nestedLinkStateElem->Get("velocity"), + ignition::math::Pose3d(0, 0, 0.001, 0, 0, 0)); + EXPECT_TRUE(nestedLinkStateElem->HasElement("acceleration")); + EXPECT_EQ(nestedLinkStateElem->Get("acceleration"), + ignition::math::Pose3d(0, 0, 0, 0, 0, 0)); + EXPECT_TRUE(nestedLinkStateElem->HasElement("wrench")); + EXPECT_EQ(nestedLinkStateElem->Get("wrench"), + ignition::math::Pose3d(0, 0, 0, 0, 0, 0)); +} diff --git a/sdformat/test/integration/numeric.sdf b/sdformat/test/integration/numeric.sdf new file mode 100644 index 0000000..a845c1c --- /dev/null +++ b/sdformat/test/integration/numeric.sdf @@ -0,0 +1,28 @@ + + + + + + 10 0 3 0 0 3.141592 + + + + 0.0 0.0 -10.00 + + + quick + 100 + 0.823 + + + 0.0 + 0.2 + 0.1 + 0.0 + + + 0 + 0.001 + + + diff --git a/sdformat/test/integration/parser_error_detection.cc b/sdformat/test/integration/parser_error_detection.cc new file mode 100644 index 0000000..2c78795 --- /dev/null +++ b/sdformat/test/integration/parser_error_detection.cc @@ -0,0 +1,54 @@ +/* + * Copyright 2015 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include "sdf/sdf.hh" + +#include "test_config.h" + +std::string get_sdf_string() +{ + std::ostringstream stream; + stream + << "" + << "" + << " " + << " " + << " " + << " 1 1 1" + << " " + << " " + << " " + << " " + << " 1 1 1" + << " " + << " " + << " " + << "" + << ""; + return stream.str(); +} + +//////////////////////////////////////// +// make sure that XML errors get caught +TEST(ParserErrorDetection, BadXML) +{ + sdf::SDFPtr model(new sdf::SDF()); + sdf::init(model); + ASSERT_FALSE(sdf::readString(get_sdf_string(), model)); +} diff --git a/sdformat/test/integration/plugin_attribute.cc b/sdformat/test/integration/plugin_attribute.cc new file mode 100644 index 0000000..97fd06c --- /dev/null +++ b/sdformat/test/integration/plugin_attribute.cc @@ -0,0 +1,65 @@ +/* + * Copyright 2014 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include "sdf/sdf.hh" + +#include "test_config.h" + +std::string get_sdf_string() +{ + std::ostringstream stream; + stream + << "" + << "" + << " " + << " " + << " " + << " value" + << " " + << "" + << ""; + return stream.str(); +} + +//////////////////////////////////////// +// make sure that plugin attributes get parsed +TEST(PluginAttribute, ParseAttributes) +{ + sdf::SDFPtr model(new sdf::SDF()); + sdf::init(model); + ASSERT_TRUE(sdf::readString(get_sdf_string(), model)); + + sdf::ElementPtr plugin = + model->Root()->GetElement("model")->GetElement("plugin"); + ASSERT_TRUE(plugin->HasElement("user")); + { + sdf::ElementPtr user = plugin->GetElement("user"); + EXPECT_TRUE(user->HasAttribute("attribute")); + EXPECT_EQ(user->GetAttribute("attribute")->GetAsString(), + std::string("attribute")); + } + { + sdf::ElementPtr value = plugin->GetElement("value"); + EXPECT_TRUE(value->HasAttribute("attribute")); + EXPECT_EQ(value->GetAttribute("attribute")->GetAsString(), + std::string("attribute")); + EXPECT_EQ(value->Get(""), + std::string("value")); + } +} diff --git a/sdformat/test/integration/plugin_bool.cc b/sdformat/test/integration/plugin_bool.cc new file mode 100644 index 0000000..b10fd6a --- /dev/null +++ b/sdformat/test/integration/plugin_bool.cc @@ -0,0 +1,71 @@ +/* + * Copyright 2014 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include "sdf/sdf.hh" + +#include "test_config.h" + +std::string get_sdf_string() +{ + std::ostringstream stream; + stream + << "" + << "" + << " " + << " true" + << " 1" + << " false" + << " 0" + << " True" + << " TRUE" + << " " + << "" + << ""; + return stream.str(); +} + +//////////////////////////////////////// +// make sure that we can read boolean values from inside a plugin +TEST(PluginBool, ParseBoolValue) +{ + sdf::SDFPtr model(new sdf::SDF()); + sdf::init(model); + ASSERT_TRUE(sdf::readString(get_sdf_string(), model)); + + sdf::ElementPtr plugin = + model->Root()->GetElement("model")->GetElement("plugin"); + + ASSERT_TRUE(plugin->HasElement("value1")); + EXPECT_TRUE(plugin->Get("value1")); + + ASSERT_TRUE(plugin->HasElement("value2")); + EXPECT_TRUE(plugin->Get("value2")); + + ASSERT_TRUE(plugin->HasElement("value3")); + EXPECT_FALSE(plugin->Get("value3")); + + ASSERT_TRUE(plugin->HasElement("value4")); + EXPECT_FALSE(plugin->Get("value4")); + + ASSERT_TRUE(plugin->HasElement("value5")); + EXPECT_TRUE(plugin->Get("value5")); + + ASSERT_TRUE(plugin->HasElement("value6")); + EXPECT_TRUE(plugin->Get("value6")); +} diff --git a/sdformat/test/integration/plugin_include.cc b/sdformat/test/integration/plugin_include.cc new file mode 100644 index 0000000..d39d64d --- /dev/null +++ b/sdformat/test/integration/plugin_include.cc @@ -0,0 +1,98 @@ +/* + * Copyright 2017 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include "sdf/sdf.hh" + +#include "test_config.h" + +//////////////////////////////////////// +// Test that plugin child elements are available even when nested in an include +TEST(PluginInclude, PluginChildElements) +{ + const std::string MODEL_PATH = std::string(PROJECT_SOURCE_PATH) + + "/test/integration/model/box"; + + std::ostringstream stream; + stream + << "" + << "" + << " " + MODEL_PATH + "" + << " " + << " " + << " true" + << " some_uri" + << " " + << "" + << ""; + + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readString(stream.str(), sdfParsed)); + + // Plugin attributes + sdf::ElementPtr plugin = + sdfParsed->Root()->GetElement("model")->GetElement("plugin"); + EXPECT_TRUE(plugin->HasAttribute("name")); + EXPECT_EQ(plugin->GetAttribute("name")->GetAsString(), "example"); + EXPECT_TRUE(plugin->HasAttribute("filename")); + EXPECT_EQ(plugin->GetAttribute("filename")->GetAsString(), "libexample.so"); + + // 1st child element + ASSERT_TRUE(plugin->HasElement("user")); + { + sdf::ElementPtr user = plugin->GetElement("user"); + EXPECT_TRUE(user->HasAttribute("attribute")); + EXPECT_EQ(user->GetAttribute("attribute")->GetAsString(), "attribute"); + } + + // 2nd child element + ASSERT_TRUE(plugin->HasElement("value")); + { + sdf::ElementPtr value = plugin->GetElement("value"); + EXPECT_TRUE(value->HasAttribute("attribute")); + EXPECT_EQ(value->GetAttribute("attribute")->GetAsString(), "boolean"); + EXPECT_TRUE(value->Get("")); + } + EXPECT_TRUE(plugin->Get("value")); + + // 3rd child element + ASSERT_TRUE(plugin->HasElement("uri")); + EXPECT_EQ(plugin->Get("uri"), "some_uri"); +} + +//////////////////////////////////////// +// Test that missing required plugin attributes are detected +TEST(PluginInclude, PluginMissingFilename) +{ + const std::string MODEL_PATH = std::string(PROJECT_SOURCE_PATH) + + "/test/integration/model/box"; + + std::ostringstream stream; + stream + << "" + << "" + << " " + MODEL_PATH + "" + << " " + << "" + << ""; + + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_FALSE(sdf::readString(stream.str(), sdfParsed)); +} diff --git a/sdformat/test/integration/provide_feedback.cc b/sdformat/test/integration/provide_feedback.cc new file mode 100644 index 0000000..536abb3 --- /dev/null +++ b/sdformat/test/integration/provide_feedback.cc @@ -0,0 +1,61 @@ +/* + * Copyright 2013 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include "sdf/sdf.hh" + +#include "test_config.h" + +const std::string SDF_TEST_FILE = std::string(PROJECT_SOURCE_PATH) + + "/test/integration/provide_feedback.urdf"; + +///////////////////////////////////////////////// +TEST(SDFParser, ProvideFeedbackTest) +{ + sdf::SDFPtr robot(new sdf::SDF()); + sdf::init(robot); + ASSERT_TRUE(sdf::readFile(SDF_TEST_FILE, robot)); + + sdf::ElementPtr model = robot->Root()->GetElement("model"); + for (sdf::ElementPtr joint = model->GetElement("joint"); joint; + joint = joint->GetNextElement("joint")) + { + std::string jointName = joint->Get("name"); + if (jointName == "jointw0") + { + // No provide_feedback tag was specified + EXPECT_FALSE(joint->HasElement("physics")); + } + else if (jointName == "joint01") + { + // provide_feedback = 0 + ASSERT_TRUE(joint->HasElement("physics")); + sdf::ElementPtr physics = joint->GetElement("physics"); + ASSERT_TRUE(physics->HasElement("provide_feedback")); + EXPECT_FALSE(physics->Get("provide_feedback")); + } + else if (jointName == "joint12") + { + // provide_feedback = 1 + ASSERT_TRUE(joint->HasElement("physics")); + sdf::ElementPtr physics = joint->GetElement("physics"); + ASSERT_TRUE(physics->HasElement("provide_feedback")); + EXPECT_TRUE(physics->Get("provide_feedback")); + } + } +} diff --git a/sdformat/test/integration/provide_feedback.urdf b/sdformat/test/integration/provide_feedback.urdf new file mode 100644 index 0000000..6478fd0 --- /dev/null +++ b/sdformat/test/integration/provide_feedback.urdf @@ -0,0 +1,37 @@ + + + + + + + + + + + + + + + + + + + + + + + 0 + + + + + + + + + + + 1 + + + diff --git a/sdformat/test/integration/schema_test.cc b/sdformat/test/integration/schema_test.cc new file mode 100644 index 0000000..299866b --- /dev/null +++ b/sdformat/test/integration/schema_test.cc @@ -0,0 +1,70 @@ +/* + * Copyright 2013 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include +#include "sdf/sdf.hh" + +#include "test_config.h" + +const std::string SDF_ROOT_SCHEMA = std::string(PROJECT_BINARY_DIR) + + "/sdf/" + SDF_PROTOCOL_VERSION + "/root.xsd"; + +const std::string SDF_TEST_PR2 = std::string(PROJECT_SOURCE_PATH) + + "/test/integration/model/pr2.sdf"; + +const std::string SDF_TEST_TURTLEBOT = std::string(PROJECT_SOURCE_PATH) + + "/test/integration/model/turtlebot.sdf"; + +const std::string SDF_TEST_PENDULUM = std::string(PROJECT_SOURCE_PATH) + + "/test/integration/model/double_pendulum.sdf"; + + +class SDFSchemaGenerator : public testing::Test +{ + public: + void runXMLlint(const std::string & model) + { + std::string xmllintCmd = "xmllint --noout --schema " + + SDF_ROOT_SCHEMA + " " + model; + std::cout << "CMD[" << xmllintCmd << "]\n"; + if (system(xmllintCmd.c_str()) != 0) + FAIL() << "Fail in parsing the model"; + else + SUCCEED(); + } +}; + +///////////////////////////////////////////////// +TEST_F(SDFSchemaGenerator, TestDoblePendulum) +{ + runXMLlint(SDF_TEST_PENDULUM); +} + +///////////////////////////////////////////////// +TEST_F(SDFSchemaGenerator, TestPR2Model) +{ + runXMLlint(SDF_TEST_PR2); +} + + +///////////////////////////////////////////////// +TEST_F(SDFSchemaGenerator, TestTurtleBotModel) +{ + runXMLlint(SDF_TEST_TURTLEBOT); +} diff --git a/sdformat/test/integration/urdf_gazebo_extensions.cc b/sdformat/test/integration/urdf_gazebo_extensions.cc new file mode 100644 index 0000000..24671ed --- /dev/null +++ b/sdformat/test/integration/urdf_gazebo_extensions.cc @@ -0,0 +1,100 @@ +/* + * Copyright 2015 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include "sdf/sdf.hh" + +#include "test_config.h" + +const std::string URDF_TEST_FILE = std::string(PROJECT_SOURCE_PATH) + + "/test/integration/urdf_gazebo_extensions.urdf"; + +///////////////////////////////////////////////// +TEST(SDFParser, UrdfGazeboExtensionURDFTest) +{ + sdf::SDFPtr robot(new sdf::SDF()); + sdf::init(robot); + ASSERT_TRUE(sdf::readFile(URDF_TEST_FILE, robot)); + + sdf::ElementPtr model = robot->Root()->GetElement("model"); + for (sdf::ElementPtr joint = model->GetElement("joint"); joint; + joint = joint->GetNextElement("joint")) + { + std::string jointName = joint->Get("name"); + if (jointName == "jointw0") + { + // No cfm_damping tag was specified + EXPECT_FALSE(joint->HasElement("physics")); + } + else if (jointName == "joint01") + { + // cfmDamping = true + ASSERT_TRUE(joint->HasElement("physics")); + sdf::ElementPtr physics = joint->GetElement("physics"); + ASSERT_TRUE(physics->HasElement("ode")); + ASSERT_TRUE(physics->HasElement("provide_feedback")); + EXPECT_TRUE(physics->Get("provide_feedback")); + + ASSERT_TRUE(physics->HasElement("ode")); + sdf::ElementPtr ode = physics->GetElement("ode"); + ASSERT_TRUE(ode->HasElement("provide_feedback")); + EXPECT_TRUE(ode->Get("provide_feedback")); + ASSERT_TRUE(ode->HasElement("implicit_spring_damper")); + EXPECT_TRUE(!ode->Get("implicit_spring_damper")); + ASSERT_TRUE(ode->HasElement("cfm_damping")); + EXPECT_TRUE(!ode->Get("cfm_damping")); + ASSERT_TRUE(ode->HasElement("fudge_factor")); + EXPECT_DOUBLE_EQ(ode->Get("fudge_factor"), 0.56789); + + ASSERT_TRUE(ode->HasElement("limit")); + sdf::ElementPtr limit = ode->GetElement("limit"); + ASSERT_TRUE(limit->HasElement("cfm")); + EXPECT_DOUBLE_EQ(limit->Get("cfm"), 123); + ASSERT_TRUE(limit->HasElement("erp")); + EXPECT_DOUBLE_EQ(limit->Get("erp"), 0.987); + + ASSERT_TRUE(joint->HasElement("axis")); + sdf::ElementPtr axis = joint->GetElement("axis"); + ASSERT_TRUE(axis->HasElement("dynamics")); + sdf::ElementPtr dynamics = axis->GetElement("dynamics"); + ASSERT_TRUE(dynamics->HasElement("damping")); + EXPECT_DOUBLE_EQ(dynamics->Get("damping"), 1.1111); + ASSERT_TRUE(dynamics->HasElement("friction")); + EXPECT_DOUBLE_EQ(dynamics->Get("friction"), 2.2222); + ASSERT_TRUE(dynamics->HasElement("spring_reference")); + EXPECT_DOUBLE_EQ(dynamics->Get("spring_reference"), 0.234); + ASSERT_TRUE(dynamics->HasElement("spring_stiffness")); + EXPECT_DOUBLE_EQ(dynamics->Get("spring_stiffness"), 0.567); + } + else if (jointName == "joint12") + { + // cfmDamping not provided + ASSERT_TRUE(joint->HasElement("physics")); + sdf::ElementPtr physics = joint->GetElement("physics"); + EXPECT_FALSE(physics->HasElement("implicit_spring_damper")); + } + else if (jointName == "joint13") + { + // implicitSpringDamper = 1 + ASSERT_TRUE(joint->HasElement("physics")); + sdf::ElementPtr physics = joint->GetElement("physics"); + ASSERT_TRUE(physics->HasElement("implicit_spring_damper")); + EXPECT_TRUE(physics->Get("implicit_spring_damper")); + } + } +} diff --git a/sdformat/test/integration/urdf_gazebo_extensions.urdf b/sdformat/test/integration/urdf_gazebo_extensions.urdf new file mode 100644 index 0000000..4703907 --- /dev/null +++ b/sdformat/test/integration/urdf_gazebo_extensions.urdf @@ -0,0 +1,140 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + 123 + 0.987 + 0.234 + 0.567 + 1 + false + 0.56789 + + + + + + + + + + + + + + + + + + + + + + + + + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/test/integration/urdf_joint_parameters.cc b/sdformat/test/integration/urdf_joint_parameters.cc new file mode 100644 index 0000000..0e18fee --- /dev/null +++ b/sdformat/test/integration/urdf_joint_parameters.cc @@ -0,0 +1,68 @@ +/* + * Copyright 2014 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include +#include "sdf/sdf.hh" + +#include "test_config.h" + +const std::string SDF_TEST_FILE = std::string(PROJECT_SOURCE_PATH) + + "/test/integration/urdf_joint_parameters.urdf"; + +///////////////////////////////////////////////// +TEST(SDFParser, JointAxisParameters) +{ + sdf::SDFPtr robot(new sdf::SDF()); + sdf::init(robot); + ASSERT_TRUE(sdf::readFile(SDF_TEST_FILE, robot)); + + sdf::ElementPtr model = robot->Root()->GetElement("model"); + + ASSERT_TRUE(model->HasElement("joint")); + unsigned int bitmask = 0; + for (sdf::ElementPtr joint = model->GetElement("joint"); joint; + joint = joint->GetNextElement("joint")) + { + std::string jointName = joint->Get("name"); + + double value = -1.0; + if (jointName == "jointw0") + { + bitmask |= 0x1; + value = 0.0; + } + else if (jointName == "joint01") + { + bitmask |= 0x2; + value = 1.0; + } + else + { + continue; + } + ASSERT_TRUE(joint->HasElement("axis")); + sdf::ElementPtr axis = joint->GetElement("axis"); + ASSERT_TRUE(axis->HasElement("dynamics")); + sdf::ElementPtr dynamics = axis->GetElement("dynamics"); + ASSERT_TRUE(dynamics->HasElement("damping")); + ASSERT_TRUE(dynamics->HasElement("friction")); + EXPECT_DOUBLE_EQ(value, dynamics->Get("damping")); + EXPECT_DOUBLE_EQ(value, dynamics->Get("friction")); + } + EXPECT_EQ(bitmask, 0x3u); +} diff --git a/sdformat/test/integration/urdf_joint_parameters.urdf b/sdformat/test/integration/urdf_joint_parameters.urdf new file mode 100644 index 0000000..e33fb28 --- /dev/null +++ b/sdformat/test/integration/urdf_joint_parameters.urdf @@ -0,0 +1,115 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sdformat/test/performance/CMakeLists.txt b/sdformat/test/performance/CMakeLists.txt new file mode 100644 index 0000000..8df89ac --- /dev/null +++ b/sdformat/test/performance/CMakeLists.txt @@ -0,0 +1,9 @@ +set(TEST_TYPE "PERFORMANCE") + +set(tests + parser_urdf.cc +) + +link_directories(${PROJECT_BINARY_DIR}/test) + +sdf_build_tests(${tests}) diff --git a/sdformat/test/performance/parser_urdf.cc b/sdformat/test/performance/parser_urdf.cc new file mode 100644 index 0000000..cd08f66 --- /dev/null +++ b/sdformat/test/performance/parser_urdf.cc @@ -0,0 +1,33 @@ +/* + * Copyright 2013 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include + +#include "sdf/sdf.hh" +#include "sdf/parser_urdf.hh" + +#include "test_config.h" + + +const std::string URDF_TEST_FILE = std::string(PROJECT_SOURCE_PATH) + "/test/performance/parser_urdf_atlas.urdf"; + +TEST(URDFParser, AtlasURDF_5runs_performance) +{ + sdf::URDF2SDF parser; + for (int i = 0; i < 5; i++) + TiXmlDocument sdf_result = parser.InitModelFile(URDF_TEST_FILE); +} diff --git a/sdformat/test/performance/parser_urdf_atlas.urdf b/sdformat/test/performance/parser_urdf_atlas.urdf new file mode 100644 index 0000000..e9d3787 --- /dev/null +++ b/sdformat/test/performance/parser_urdf_atlas.urdf @@ -0,0 +1,1839 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0 0 0.93 0 0 0 + + + + + joint_trajectory + 1000.0 + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + 1000.0 + + + gaussian + + + 0.0 + 2e-4 + 0.0000075 + 0.0000008 + + + 0.0 + 1.7e-2 + 0.1 + 0.001 + + + + + + + 1 + + + 1 + + + 1 + 1 + + + 1 + 1 + + + + 1000000.0 + 100.0 + 1.5 + 1.5 + 1 0 0 + 1.0 + 0.00 + + + 1000000.0 + 100.0 + 1.5 + 1.5 + 1 0 0 + 1.0 + 0.00 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + 0.9 + 0.9 + + + + pelvis + /ground_truth_odom + true + 100.0 + + + + + + 1000.0 + 1 + + r_foot_collision + /r_foot_contact + + + + + + + 1000.0 + 1 + + l_foot_collision + /l_foot_contact + + + + + + pelvis + /atlas/apply_pelvis_force + + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0 0 0 0 0 0 + false + 40 + + + + 720 + 1 + -1.570796 + 1.570796 + + + + 0.10 + 30.0 + 0.01 + + + gaussian + + 0.0 + 0.01 + + + + /multisense_sl/laser/scan + head_hokuyo_frame + + + + + + + + + + + + + + + + + + + + + + + + + + + 30.0 + + + 1.3962634 + + 800 + 800 + R8G8B8 + + + 0.02 + 300 + + + gaussian + + 0.0 + 0.007 + + + + 0 -0.07 0 0 0 0 + + 1.3962634 + + 800 + 800 + R8G8B8 + + + 0.02 + 300 + + + gaussian + + 0.0 + 0.007 + + + + true + 0.0 + multisense_sl/camera + image_raw + camera_info + left_camera_optical_frame + + 0.07 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + 1000.0 + + + gaussian + + + 0.0 + 2e-4 + 0.0000075 + 0.0000008 + + + 0.0 + 1.7e-2 + 0.1 + 0.001 + + + + + + + diff --git a/sdformat/test/test_config.h.in b/sdformat/test/test_config.h.in new file mode 100644 index 0000000..bb52de9 --- /dev/null +++ b/sdformat/test/test_config.h.in @@ -0,0 +1,26 @@ +#define PROJECT_SOURCE_PATH "${PROJECT_SOURCE_DIR}" +#define PROJECT_BINARY_DIR "${CMAKE_BINARY_DIR}" +#define SDF_PROTOCOL_VERSION "${SDF_PROTOCOL_VERSION}" + +/* + * setenv/unstenv are not present in Windows. Define them to make the code + * portable + */ +#if (_MSC_VER >= 1400) // Visual Studio 2005 +#include + +int setenv(const char * name, const char * value, int /*rewrite*/) +{ + std::stringstream sstr; + sstr << *name << '=' << value; + return _putenv(sstr.str().c_str()); +} + +void unsetenv(const char * name) +{ + std::stringstream sstr; + sstr << *name << '='; + _putenv(sstr.str().c_str()); + return; +} +#endif diff --git a/sdformat/tools/check_test_ran.py b/sdformat/tools/check_test_ran.py new file mode 100755 index 0000000..3b87904 --- /dev/null +++ b/sdformat/tools/check_test_ran.py @@ -0,0 +1,81 @@ +#!/usr/bin/env python +# Software License Agreement (BSD License) +# +# Copyright (c) 2008, Willow Garage, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Revision $Id: check_test_ran.py 16671 2012-04-27 16:15:28Z dthomas $ + +""" +Writes a test failure out to test file if it doesn't exist. +""" + +# Adapted from rosunit/check_test_ran.py + +from __future__ import print_function +NAME="check_test_ran.py" + +import os +import sys + +def usage(): + print("""Usage: +\t%s test-file.xml +"""%(NAME), file=sys.stderr) + print(sys.argv) + sys.exit(getattr(os, 'EX_USAGE', 1)) + +def check_main(): + if len(sys.argv) < 2: + usage() + test_file = sys.argv[1] + + print("Checking for test results in %s"%test_file) + + if not os.path.exists(test_file): + if not os.path.exists(os.path.dirname(test_file)): + os.makedirs(os.path.dirname(test_file)) + + print("Cannot find results, writing failure results to", test_file) + + with open(test_file, 'w') as f: + test_name = os.path.basename(test_file) + d = {'test': test_name, 'test_file': test_file } + f.write(""" + + + + +"""%d) + +if __name__ == '__main__': + check_main() + + diff --git a/sdformat/tools/code_check.sh b/sdformat/tools/code_check.sh new file mode 100755 index 0000000..ee1f7bb --- /dev/null +++ b/sdformat/tools/code_check.sh @@ -0,0 +1,74 @@ +#!/bin/sh + +# Jenkins will pass -xml, in which case we want to generate XML output +xmlout=0 +if test "$1" = "-xmldir" -a -n "$2"; then + xmlout=1 + xmldir=$2 + mkdir -p $xmldir + rm -rf $xmldir/*.xml + # Assuming that Jenkins called, the `build` directory is a sibling to the src dir + builddir=../build +else + # This is a heuristic guess; not every developer puts the `build` dir in the src dir + builddir=./build +fi + +# Use a suppression file for spurious errors +SUPPRESS=/tmp/sdf_cpp_check.suppress +echo "*:test/integration/locale_fix.cc:35" > $SUPPRESS + +# Use another suppression file for unused function checking +SUPPRESS2=/tmp/sdf_cpp_check2.suppress +echo "*:src/SDF.cc" > $SUPPRESS2 +echo "*:src/Assert.cc" >> $SUPPRESS2 +echo "*:src/Console.cc" >> $SUPPRESS2 +echo "*:src/parser.cc" >> $SUPPRESS2 +echo "*:src/parser_urdf.cc" >> $SUPPRESS2 +echo "*:src/Element.cc:464" >> $SUPPRESS2 +echo "*:src/Element.cc:39" >> $SUPPRESS2 +echo "*:src/Element.cc:752" >> $SUPPRESS2 + +CHECK_FILE_DIRS="./src ./include ./test/performance ./test/integration" + +#cppcheck +CPPCHECK_BASE="cppcheck -q --suppressions-list=$SUPPRESS" +CPPCHECK_BASE2="cppcheck -q --suppressions-list=$SUPPRESS2" +CPPCHECK_FILES=`find $CHECK_FILE_DIRS -name "*.cc"` +CPPCHECK_INCLUDES="-I include -I . -I src/urdf -I $builddir -I $builddir/include" +CPPCHECK_COMMAND1="-j 4 --enable=style,performance,portability,information $CPPCHECK_FILES" +# Unused function checking must happen in one job +CPPCHECK_COMMAND2="--enable=unusedFunction $CPPCHECK_FILES" +# -j 4 was used previously in CPPCHECK_COMMAND3 but it will generate a false +# warning as described in bug: +# http://sourceforge.net/apps/trac/cppcheck/ticket/4946 +CPPCHECK_COMMAND3="-j 1 --enable=missingInclude --suppress=missingIncludeSystem $CPPCHECK_FILES $CPPCHECK_INCLUDES --check-config" +if [ $xmlout -eq 1 ]; then + # Performance, style, portability, and information + ($CPPCHECK_BASE --xml --xml-version=2 $CPPCHECK_COMMAND1) 2> $xmldir/cppcheck.xml + + # Unused function checking + ($CPPCHECK_BASE2 --xml --xml-version=2 $CPPCHECK_COMMAND2) 2> $xmldir/cppcheck-unused-functions.xml + + # Check the configuration + ($CPPCHECK_BASE --xml --xml-version=2 $CPPCHECK_COMMAND3) 2> $xmldir/cppcheck-configuration.xml +else + # Performance, style, portability, and information + $CPPCHECK_BASE $CPPCHECK_COMMAND1 2>&1 + + # Unused function checking + $CPPCHECK_BASE2 $CPPCHECK_COMMAND2 2>&1 + + # Check the configuration + $CPPCHECK_BASE $CPPCHECK_COMMAND3 2>&1 +fi + +# cpplint +# exclude urdf files for now, since they generate lots of errors +CPPLINT_FILES=`find $CHECK_FILE_DIRS -name "*.cc" -o -name "*.hh" | grep -iv urdf` +if [ $xmlout -eq 1 ]; then + (echo $CPPLINT_FILES | xargs python tools/cpplint.py 2>&1) \ + | python tools/cpplint_to_cppcheckxml.py 2> $xmldir/cpplint.xml +else + echo $CPPLINT_FILES | xargs python tools/cpplint.py 2>&1 +fi diff --git a/sdformat/tools/cpplint.py b/sdformat/tools/cpplint.py new file mode 100644 index 0000000..d338a78 --- /dev/null +++ b/sdformat/tools/cpplint.py @@ -0,0 +1,3351 @@ +#!/usr/bin/python2.4 +# +# Copyright (c) 2009 Google Inc. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are +# met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following disclaimer +# in the documentation and/or other materials provided with the +# distribution. +# * Neither the name of Google Inc. nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +# A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +# OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +# SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +# LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +# DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +# THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +# Here are some issues that I've had people identify in my code during reviews, +# that I think are possible to flag automatically in a lint tool. If these were +# caught by lint, it would save time both for myself and that of my reviewers. +# Most likely, some of these are beyond the scope of the current lint framework, +# but I think it is valuable to retain these wish-list items even if they cannot +# be immediately implemented. +# +# Suggestions +# ----------- +# - Check for no 'explicit' for multi-arg ctor +# - Check for boolean assign RHS in parens +# - Check for ctor initializer-list colon position and spacing +# - Check that if there's a ctor, there should be a dtor +# - Check accessors that return non-pointer member variables are +# declared const +# - Check accessors that return non-const pointer member vars are +# *not* declared const +# - Check for using public includes for testing +# - Check for spaces between brackets in one-line inline method +# - Check for no assert() +# - Check for spaces surrounding operators +# - Check for 0 in pointer context (should be NULL) +# - Check for 0 in char context (should be '\0') +# - Check for camel-case method name conventions for methods +# that are not simple inline getters and setters +# - Check that base classes have virtual destructors +# put " // namespace" after } that closes a namespace, with +# namespace's name after 'namespace' if it is named. +# - Do not indent namespace contents +# - Avoid inlining non-trivial constructors in header files +# include base/basictypes.h if DISALLOW_EVIL_CONSTRUCTORS is used +# - Check for old-school (void) cast for call-sites of functions +# ignored return value +# - Check gUnit usage of anonymous namespace +# - Check for class declaration order (typedefs, consts, enums, +# ctor(s?), dtor, friend declarations, methods, member vars) +# + +"""Does google-lint on c++ files. + +The goal of this script is to identify places in the code that *may* +be in non-compliance with google style. It does not attempt to fix +up these problems -- the point is to educate. It does also not +attempt to find all problems, or to ensure that everything it does +find is legitimately a problem. + +In particular, we can get very confused by /* and // inside strings! +We do a small hack, which is to ignore //'s with "'s after them on the +same line, but it is far from perfect (in either direction). +""" + +import codecs +import getopt +import math # for log +import os +import re +import sre_compile +import string +import sys +import unicodedata + + +_USAGE = """ +Syntax: cpplint.py [--verbose=#] [--output=vs7] [--filter=-x,+y,...] + [--counting=total|toplevel|detailed] + [file] ... + + The style guidelines this tries to follow are those in + http://google-styleguide.googlecode.com/svn/trunk/cppguide.xml + + Every problem is given a confidence score from 1-5, with 5 meaning we are + certain of the problem, and 1 meaning it could be a legitimate construct. + This will miss some errors, and is not a substitute for a code review. + + To suppress false-positive errors of a certain category, add a + 'NOLINT(category)' comment to the line. NOLINT or NOLINT(*) + suppresses errors of all categories on that line. + + The files passed in will be linted; at least one file must be provided. + Linted extensions are .cc, .cpp, and .h. Other file types will be ignored. + + Flags: + + output=vs7 + By default, the output is formatted to ease emacs parsing. Visual Studio + compatible output (vs7) may also be used. Other formats are unsupported. + + verbose=# + Specify a number 0-5 to restrict errors to certain verbosity levels. + + filter=-x,+y,... + Specify a comma-separated list of category-filters to apply: only + error messages whose category names pass the filters will be printed. + (Category names are printed with the message and look like + "[whitespace/indent]".) Filters are evaluated left to right. + "-FOO" and "FOO" means "do not print categories that start with FOO". + "+FOO" means "do print categories that start with FOO". + + Examples: --filter=-whitespace,+whitespace/braces + --filter=whitespace,runtime/printf,+runtime/printf_format + --filter=-,+build/include_what_you_use + + To see a list of all the categories used in cpplint, pass no arg: + --filter= + + counting=total|toplevel|detailed + The total number of errors found is always printed. If + 'toplevel' is provided, then the count of errors in each of + the top-level categories like 'build' and 'whitespace' will + also be printed. If 'detailed' is provided, then a count + is provided for each category like 'build/class'. +""" + +# We categorize each error message we print. Here are the categories. +# We want an explicit list so we can list them all in cpplint --filter=. +# If you add a new error message with a new category, add it to the list +# here! cpplint_unittest.py should tell you if you forget to do this. +# \ used for clearer layout -- pylint: disable-msg=C6013 +_ERROR_CATEGORIES = [ + 'build/class', + 'build/deprecated', + 'build/endif_comment', + 'build/explicit_make_pair', + 'build/forward_decl', + 'build/header_guard', + 'build/include', + 'build/include_alpha', + 'build/include_order', + 'build/include_what_you_use', + 'build/namespaces', + 'build/printf_format', + 'build/storage_class', + 'legal/copyright', + 'readability/braces', + 'readability/casting', + 'readability/check', + 'readability/constructors', + 'readability/fn_size', + 'readability/function', + 'readability/multiline_comment', + 'readability/multiline_string', + 'readability/nolint', + 'readability/streams', + 'readability/todo', + 'readability/utf8', + 'runtime/arrays', + 'runtime/casting', + 'runtime/explicit', + 'runtime/int', + 'runtime/init', + 'runtime/invalid_increment', + 'runtime/member_string_references', + 'runtime/memset', + 'runtime/operator', + 'runtime/printf', + 'runtime/printf_format', + 'runtime/references', + 'runtime/rtti', + 'runtime/sizeof', + 'runtime/string', + 'runtime/threadsafe_fn', + 'runtime/virtual', + 'whitespace/blank_line', + 'whitespace/braces', + 'whitespace/comma', + 'whitespace/comments', + 'whitespace/end_of_line', + 'whitespace/ending_newline', + 'whitespace/indent', + 'whitespace/labels', + 'whitespace/line_length', + 'whitespace/newline', + 'whitespace/operators', + 'whitespace/parens', + 'whitespace/semicolon', + 'whitespace/tab', + 'whitespace/todo' + ] + +# These constants define types of headers for use with +# _IncludeState.CheckNextIncludeOrder(). +_C_SYS_HEADER = 1 +_CPP_SYS_HEADER = 2 +_OTHER_HEADER = 3 +_LIKELY_MY_HEADER = 4 +_POSSIBLE_MY_HEADER = 5 + +# The default state of the category filter. This is overrided by the --filter= +# flag. By default all errors are on, so only add here categories that should be +# off by default (i.e., categories that must be enabled by the --filter= flags). +# All entries here should start with a '-' or '+', as in the --filter= flag. +_DEFAULT_FILTERS = ['-build/include_alpha'] + +# We used to check for high-bit characters, but after much discussion we +# decided those were OK, as long as they were in UTF-8 and didn't represent +# hard-coded international strings, which belong in a separate i18n file. + +# Headers that we consider STL headers. +_STL_HEADERS = frozenset([ + 'algobase.h', 'algorithm', 'alloc.h', 'bitset', 'deque', 'exception', + 'function.h', 'functional', 'hash_map', 'hash_map.h', 'hash_set', + 'hash_set.h', 'iterator', 'list', 'list.h', 'map', 'memory', 'new', + 'pair.h', 'pthread_alloc', 'queue', 'set', 'set.h', 'sstream', 'stack', + 'stl_alloc.h', 'stl_relops.h', 'type_traits.h', + 'utility', 'vector', 'vector.h', + ]) + + +# Non-STL C++ system headers. +_CPP_HEADERS = frozenset([ + 'algo.h', 'builtinbuf.h', 'bvector.h', 'cassert', 'cctype', + 'cerrno', 'cfloat', 'ciso646', 'climits', 'clocale', 'cmath', + 'complex', 'complex.h', 'csetjmp', 'csignal', 'cstdarg', 'cstddef', + 'cstdio', 'cstdlib', 'cstring', 'ctime', 'cwchar', 'cwctype', + 'defalloc.h', 'deque.h', 'editbuf.h', 'exception', 'fstream', + 'fstream.h', 'hashtable.h', 'heap.h', 'indstream.h', 'iomanip', + 'iomanip.h', 'ios', 'iosfwd', 'iostream', 'iostream.h', 'istream', + 'istream.h', 'iterator.h', 'limits', 'map.h', 'multimap.h', 'multiset.h', + 'numeric', 'ostream', 'ostream.h', 'parsestream.h', 'pfstream.h', + 'PlotFile.h', 'procbuf.h', 'pthread_alloc.h', 'rope', 'rope.h', + 'ropeimpl.h', 'SFile.h', 'slist', 'slist.h', 'stack.h', 'stdexcept', + 'stdiostream.h', 'streambuf.h', 'stream.h', 'strfile.h', 'string', + 'strstream', 'strstream.h', 'tempbuf.h', 'tree.h', 'typeinfo', 'valarray', + ]) + + +# Assertion macros. These are defined in base/logging.h and +# testing/base/gunit.h. Note that the _M versions need to come first +# for substring matching to work. +_CHECK_MACROS = [ + 'DCHECK', 'CHECK', + 'EXPECT_TRUE_M', 'EXPECT_TRUE', + 'ASSERT_TRUE_M', 'ASSERT_TRUE', + 'EXPECT_FALSE_M', 'EXPECT_FALSE', + 'ASSERT_FALSE_M', 'ASSERT_FALSE', + ] + +# Replacement macros for CHECK/DCHECK/EXPECT_TRUE/EXPECT_FALSE +_CHECK_REPLACEMENT = dict([(m, {}) for m in _CHECK_MACROS]) + +for op, replacement in [('==', 'EQ'), ('!=', 'NE'), + ('>=', 'GE'), ('>', 'GT'), + ('<=', 'LE'), ('<', 'LT')]: + _CHECK_REPLACEMENT['DCHECK'][op] = 'DCHECK_%s' % replacement + _CHECK_REPLACEMENT['CHECK'][op] = 'CHECK_%s' % replacement + _CHECK_REPLACEMENT['EXPECT_TRUE'][op] = 'EXPECT_%s' % replacement + _CHECK_REPLACEMENT['ASSERT_TRUE'][op] = 'ASSERT_%s' % replacement + _CHECK_REPLACEMENT['EXPECT_TRUE_M'][op] = 'EXPECT_%s_M' % replacement + _CHECK_REPLACEMENT['ASSERT_TRUE_M'][op] = 'ASSERT_%s_M' % replacement + +for op, inv_replacement in [('==', 'NE'), ('!=', 'EQ'), + ('>=', 'LT'), ('>', 'LE'), + ('<=', 'GT'), ('<', 'GE')]: + _CHECK_REPLACEMENT['EXPECT_FALSE'][op] = 'EXPECT_%s' % inv_replacement + _CHECK_REPLACEMENT['ASSERT_FALSE'][op] = 'ASSERT_%s' % inv_replacement + _CHECK_REPLACEMENT['EXPECT_FALSE_M'][op] = 'EXPECT_%s_M' % inv_replacement + _CHECK_REPLACEMENT['ASSERT_FALSE_M'][op] = 'ASSERT_%s_M' % inv_replacement + + +_regexp_compile_cache = {} + +# Finds occurrences of NOLINT or NOLINT(...). +_RE_SUPPRESSION = re.compile(r'\bNOLINT\b(\([^)]*\))?') + +# {str, set(int)}: a map from error categories to sets of linenumbers +# on which those errors are expected and should be suppressed. +_error_suppressions = {} + +def ParseNolintSuppressions(filename, raw_line, linenum, error): + """Updates the global list of error-suppressions. + + Parses any NOLINT comments on the current line, updating the global + error_suppressions store. Reports an error if the NOLINT comment + was malformed. + + Args: + filename: str, the name of the input file. + raw_line: str, the line of input text, with comments. + linenum: int, the number of the current line. + error: function, an error handler. + """ + # FIXME(adonovan): "NOLINT(" is misparsed as NOLINT(*). + matched = _RE_SUPPRESSION.search(raw_line) + if matched: + category = matched.group(1) + if category in (None, '(*)'): # => "suppress all" + _error_suppressions.setdefault(None, set()).add(linenum) + else: + if category.startswith('(') and category.endswith(')'): + category = category[1:-1] + if category in _ERROR_CATEGORIES: + _error_suppressions.setdefault(category, set()).add(linenum) + else: + error(filename, linenum, 'readability/nolint', 5, + 'Unknown NOLINT error category: %s' % category) + + +def ResetNolintSuppressions(): + "Resets the set of NOLINT suppressions to empty." + _error_suppressions.clear() + + +def IsErrorSuppressedByNolint(category, linenum): + """Returns true if the specified error category is suppressed on this line. + + Consults the global error_suppressions map populated by + ParseNolintSuppressions/ResetNolintSuppressions. + + Args: + category: str, the category of the error. + linenum: int, the current line number. + Returns: + bool, True iff the error should be suppressed due to a NOLINT comment. + """ + return (linenum in _error_suppressions.get(category, set()) or + linenum in _error_suppressions.get(None, set())) + +def Match(pattern, s): + """Matches the string with the pattern, caching the compiled regexp.""" + # The regexp compilation caching is inlined in both Match and Search for + # performance reasons; factoring it out into a separate function turns out + # to be noticeably expensive. + if not pattern in _regexp_compile_cache: + _regexp_compile_cache[pattern] = sre_compile.compile(pattern) + return _regexp_compile_cache[pattern].match(s) + + +def Search(pattern, s): + """Searches the string for the pattern, caching the compiled regexp.""" + if not pattern in _regexp_compile_cache: + _regexp_compile_cache[pattern] = sre_compile.compile(pattern) + return _regexp_compile_cache[pattern].search(s) + + +class _IncludeState(dict): + """Tracks line numbers for includes, and the order in which includes appear. + + As a dict, an _IncludeState object serves as a mapping between include + filename and line number on which that file was included. + + Call CheckNextIncludeOrder() once for each header in the file, passing + in the type constants defined above. Calls in an illegal order will + raise an _IncludeError with an appropriate error message. + + """ + # self._section will move monotonically through this set. If it ever + # needs to move backwards, CheckNextIncludeOrder will raise an error. + _INITIAL_SECTION = 0 + _C_SECTION = 1 + _CPP_SECTION = 2 + _OTHER_H_SECTION = 3 + _MY_H_SECTION = 4 + + _TYPE_NAMES = { + _C_SYS_HEADER: 'C system header', + _CPP_SYS_HEADER: 'C++ system header', + _LIKELY_MY_HEADER: 'header this file implements', + _POSSIBLE_MY_HEADER: 'header this file may implement', + _OTHER_HEADER: 'other header', + } + _SECTION_NAMES = { + _INITIAL_SECTION: "... nothing. (This can't be an error.)", + _C_SECTION: 'C system header', + _CPP_SECTION: 'C++ system header', + _OTHER_H_SECTION: 'other header', + _MY_H_SECTION: 'a header this file implements', + } + + def __init__(self): + dict.__init__(self) + # The name of the current section. + self._section = self._INITIAL_SECTION + # The path of last found header. + self._last_header = '' + + def CanonicalizeAlphabeticalOrder(self, header_path): + """Returns a path canonicalized for alphabetical comparison. + + - replaces "-" with "_" so they both cmp the same. + - removes '-inl' since we don't require them to be after the main header. + - lowercase everything, just in case. + + Args: + header_path: Path to be canonicalized. + + Returns: + Canonicalized path. + """ + return header_path.replace('-inl.h', '.h').replace('-', '_').lower() + + def IsInAlphabeticalOrder(self, header_path): + """Check if a header is in alphabetical order with the previous header. + + Args: + header_path: Header to be checked. + + Returns: + Returns true if the header is in alphabetical order. + """ + canonical_header = self.CanonicalizeAlphabeticalOrder(header_path) + if self._last_header > canonical_header: + return False + self._last_header = canonical_header + return True + + def CheckNextIncludeOrder(self, header_type): + """Returns a non-empty error message if the next header is out of order. + + This function also updates the internal state to be ready to check + the next include. + + Args: + header_type: One of the _XXX_HEADER constants defined above. + + Returns: + The empty string if the header is in the right order, or an + error message describing what's wrong. + + """ + error_message = ('Found %s after %s' % + (self._TYPE_NAMES[header_type], + self._SECTION_NAMES[self._section])) + + last_section = self._section + + if header_type == _C_SYS_HEADER: + if self._section <= self._C_SECTION: + self._section = self._C_SECTION + else: + self._last_header = '' + return error_message + elif header_type == _CPP_SYS_HEADER: + if self._section <= self._CPP_SECTION: + self._section = self._CPP_SECTION + else: + self._last_header = '' + return error_message + elif header_type == _LIKELY_MY_HEADER: + if self._section <= self._MY_H_SECTION: + self._section = self._MY_H_SECTION + else: + self._section = self._OTHER_H_SECTION + elif header_type == _POSSIBLE_MY_HEADER: + if self._section <= self._MY_H_SECTION: + self._section = self._MY_H_SECTION + else: + # This will always be the fallback because we're not sure + # enough that the header is associated with this file. + self._section = self._OTHER_H_SECTION + else: + assert header_type == _OTHER_HEADER + self._section = self._OTHER_H_SECTION + + if last_section != self._section: + self._last_header = '' + + return '' + + +class _CppLintState(object): + """Maintains module-wide state..""" + + def __init__(self): + self.verbose_level = 1 # global setting. + self.error_count = 0 # global count of reported errors + # filters to apply when emitting error messages + self.filters = _DEFAULT_FILTERS[:] + self.counting = 'total' # In what way are we counting errors? + self.errors_by_category = {} # string to int dict storing error counts + + # output format: + # "emacs" - format that emacs can parse (default) + # "vs7" - format that Microsoft Visual Studio 7 can parse + self.output_format = 'emacs' + + def SetOutputFormat(self, output_format): + """Sets the output format for errors.""" + self.output_format = output_format + + def SetVerboseLevel(self, level): + """Sets the module's verbosity, and returns the previous setting.""" + last_verbose_level = self.verbose_level + self.verbose_level = level + return last_verbose_level + + def SetCountingStyle(self, counting_style): + """Sets the module's counting options.""" + self.counting = counting_style + + def SetFilters(self, filters): + """Sets the error-message filters. + + These filters are applied when deciding whether to emit a given + error message. + + Args: + filters: A string of comma-separated filters (eg "+whitespace/indent"). + Each filter should start with + or -; else we die. + + Raises: + ValueError: The comma-separated filters did not all start with '+' or '-'. + E.g. "-,+whitespace,-whitespace/indent,whitespace/badfilter" + """ + # Default filters always have less priority than the flag ones. + self.filters = _DEFAULT_FILTERS[:] + for filt in filters.split(','): + clean_filt = filt.strip() + if clean_filt: + self.filters.append(clean_filt) + for filt in self.filters: + if not (filt.startswith('+') or filt.startswith('-')): + raise ValueError('Every filter in --filters must start with + or -' + ' (%s does not)' % filt) + + def ResetErrorCounts(self): + """Sets the module's error statistic back to zero.""" + self.error_count = 0 + self.errors_by_category = {} + + def IncrementErrorCount(self, category): + """Bumps the module's error statistic.""" + self.error_count += 1 + if self.counting in ('toplevel', 'detailed'): + if self.counting != 'detailed': + category = category.split('/')[0] + if category not in self.errors_by_category: + self.errors_by_category[category] = 0 + self.errors_by_category[category] += 1 + + def PrintErrorCounts(self): + """Print a summary of errors by category, and the total.""" + for category, count in self.errors_by_category.iteritems(): + sys.stderr.write('Category \'%s\' errors found: %d\n' % + (category, count)) + sys.stderr.write('Total errors found: %d\n' % self.error_count) + +_cpplint_state = _CppLintState() + + +def _OutputFormat(): + """Gets the module's output format.""" + return _cpplint_state.output_format + + +def _SetOutputFormat(output_format): + """Sets the module's output format.""" + _cpplint_state.SetOutputFormat(output_format) + + +def _VerboseLevel(): + """Returns the module's verbosity setting.""" + return _cpplint_state.verbose_level + + +def _SetVerboseLevel(level): + """Sets the module's verbosity, and returns the previous setting.""" + return _cpplint_state.SetVerboseLevel(level) + + +def _SetCountingStyle(level): + """Sets the module's counting options.""" + _cpplint_state.SetCountingStyle(level) + + +def _Filters(): + """Returns the module's list of output filters, as a list.""" + return _cpplint_state.filters + + +def _SetFilters(filters): + """Sets the module's error-message filters. + + These filters are applied when deciding whether to emit a given + error message. + + Args: + filters: A string of comma-separated filters (eg "whitespace/indent"). + Each filter should start with + or -; else we die. + """ + _cpplint_state.SetFilters(filters) + + +class _FunctionState(object): + """Tracks current function name and the number of lines in its body.""" + + _NORMAL_TRIGGER = 250 # for --v=0, 500 for --v=1, etc. + _TEST_TRIGGER = 400 # about 50% more than _NORMAL_TRIGGER. + + def __init__(self): + self.in_a_function = False + self.lines_in_function = 0 + self.current_function = '' + + def Begin(self, function_name): + """Start analyzing function body. + + Args: + function_name: The name of the function being tracked. + """ + self.in_a_function = True + self.lines_in_function = 0 + self.current_function = function_name + + def Count(self): + """Count line in current function body.""" + if self.in_a_function: + self.lines_in_function += 1 + + def Check(self, error, filename, linenum): + """Report if too many lines in function body. + + Args: + error: The function to call with any errors found. + filename: The name of the current file. + linenum: The number of the line to check. + """ + if Match(r'T(EST|est)', self.current_function): + base_trigger = self._TEST_TRIGGER + else: + base_trigger = self._NORMAL_TRIGGER + trigger = base_trigger * 2**_VerboseLevel() + + if self.lines_in_function > trigger: + error_level = int(math.log(self.lines_in_function / base_trigger, 2)) + # 50 => 0, 100 => 1, 200 => 2, 400 => 3, 800 => 4, 1600 => 5, ... + if error_level > 5: + error_level = 5 + error(filename, linenum, 'readability/fn_size', error_level, + 'Small and focused functions are preferred:' + ' %s has %d non-comment lines' + ' (error triggered by exceeding %d lines).' % ( + self.current_function, self.lines_in_function, trigger)) + + def End(self): + """Stop analyzing function body.""" + self.in_a_function = False + + +class _IncludeError(Exception): + """Indicates a problem with the include order in a file.""" + pass + + +class FileInfo: + """Provides utility functions for filenames. + + FileInfo provides easy access to the components of a file's path + relative to the project root. + """ + + def __init__(self, filename): + self._filename = filename + + def FullName(self): + """Make Windows paths like Unix.""" + return os.path.abspath(self._filename).replace('\\', '/') + + def RepositoryName(self): + """FullName after removing the local path to the repository. + + If we have a real absolute path name here we can try to do something smart: + detecting the root of the checkout and truncating /path/to/checkout from + the name so that we get header guards that don't include things like + "C:\Documents and Settings\..." or "/home/username/..." in them and thus + people on different computers who have checked the source out to different + locations won't see bogus errors. + """ + fullname = self.FullName() + + if os.path.exists(fullname): + project_dir = os.path.dirname(fullname) + + if os.path.exists(os.path.join(project_dir, ".svn")): + # If there's a .svn file in the current directory, we recursively look + # up the directory tree for the top of the SVN checkout + root_dir = project_dir + one_up_dir = os.path.dirname(root_dir) + while os.path.exists(os.path.join(one_up_dir, ".svn")): + root_dir = os.path.dirname(root_dir) + one_up_dir = os.path.dirname(one_up_dir) + + prefix = os.path.commonprefix([root_dir, project_dir]) + return fullname[len(prefix) + 1:] + + # Not SVN? Try to find a git or hg top level directory by searching up + # from the current path. + root_dir = os.path.dirname(fullname) + while (root_dir != os.path.dirname(root_dir) and + not os.path.exists(os.path.join(root_dir, ".git")) and + not os.path.exists(os.path.join(root_dir, ".hg"))): + root_dir = os.path.dirname(root_dir) + + if (os.path.exists(os.path.join(root_dir, ".git")) or + os.path.exists(os.path.join(root_dir, ".hg"))): + prefix = os.path.commonprefix([root_dir, project_dir]) + return fullname[len(prefix) + 1:] + + # Don't know what to do; header guard warnings may be wrong... + return fullname + + def Split(self): + """Splits the file into the directory, basename, and extension. + + For 'chrome/browser/browser.cc', Split() would + return ('chrome/browser', 'browser', '.cc') + + Returns: + A tuple of (directory, basename, extension). + """ + + googlename = self.RepositoryName() + project, rest = os.path.split(googlename) + return (project,) + os.path.splitext(rest) + + def BaseName(self): + """File base name - text after the final slash, before the final period.""" + return self.Split()[1] + + def Extension(self): + """File extension - text following the final period.""" + return self.Split()[2] + + def NoExtension(self): + """File has no source file extension.""" + return '/'.join(self.Split()[0:2]) + + def IsSource(self): + """File has a source file extension.""" + return self.Extension()[1:] in ('c', 'cc', 'cpp', 'cxx') + + +def _ShouldPrintError(category, confidence, linenum): + """If confidence >= verbose, category passes filter and is not suppressed.""" + + # There are three ways we might decide not to print an error message: + # a "NOLINT(category)" comment appears in the source, + # the verbosity level isn't high enough, or the filters filter it out. + if IsErrorSuppressedByNolint(category, linenum): + return False + if confidence < _cpplint_state.verbose_level: + return False + + is_filtered = False + for one_filter in _Filters(): + if one_filter.startswith('-'): + if category.startswith(one_filter[1:]): + is_filtered = True + elif one_filter.startswith('+'): + if category.startswith(one_filter[1:]): + is_filtered = False + else: + assert False # should have been checked for in SetFilter. + if is_filtered: + return False + + return True + + +def Error(filename, linenum, category, confidence, message): + """Logs the fact we've found a lint error. + + We log where the error was found, and also our confidence in the error, + that is, how certain we are this is a legitimate style regression, and + not a misidentification or a use that's sometimes justified. + + False positives can be suppressed by the use of + "cpplint(category)" comments on the offending line. These are + parsed into _error_suppressions. + + Args: + filename: The name of the file containing the error. + linenum: The number of the line containing the error. + category: A string used to describe the "category" this bug + falls under: "whitespace", say, or "runtime". Categories + may have a hierarchy separated by slashes: "whitespace/indent". + confidence: A number from 1-5 representing a confidence score for + the error, with 5 meaning that we are certain of the problem, + and 1 meaning that it could be a legitimate construct. + message: The error message. + """ + if _ShouldPrintError(category, confidence, linenum): + _cpplint_state.IncrementErrorCount(category) + if _cpplint_state.output_format == 'vs7': + sys.stderr.write('%s(%s): %s [%s] [%d]\n' % ( + filename, linenum, message, category, confidence)) + else: + sys.stderr.write('%s:%s: %s [%s] [%d]\n' % ( + filename, linenum, message, category, confidence)) + + +# Matches standard C++ escape esequences per 2.13.2.3 of the C++ standard. +_RE_PATTERN_CLEANSE_LINE_ESCAPES = re.compile( + r'\\([abfnrtv?"\\\']|\d+|x[0-9a-fA-F]+)') +# Matches strings. Escape codes should already be removed by ESCAPES. +_RE_PATTERN_CLEANSE_LINE_DOUBLE_QUOTES = re.compile(r'"[^"]*"') +# Matches characters. Escape codes should already be removed by ESCAPES. +_RE_PATTERN_CLEANSE_LINE_SINGLE_QUOTES = re.compile(r"'.'") +# Matches multi-line C++ comments. +# This RE is a little bit more complicated than one might expect, because we +# have to take care of space removals tools so we can handle comments inside +# statements better. +# The current rule is: We only clear spaces from both sides when we're at the +# end of the line. Otherwise, we try to remove spaces from the right side, +# if this doesn't work we try on left side but only if there's a non-character +# on the right. +_RE_PATTERN_CLEANSE_LINE_C_COMMENTS = re.compile( + r"""(\s*/\*.*\*/\s*$| + /\*.*\*/\s+| + \s+/\*.*\*/(?=\W)| + /\*.*\*/)""", re.VERBOSE) + + +def IsCppString(line): + """Does line terminate so, that the next symbol is in string constant. + + This function does not consider single-line nor multi-line comments. + + Args: + line: is a partial line of code starting from the 0..n. + + Returns: + True, if next character appended to 'line' is inside a + string constant. + """ + + line = line.replace(r'\\', 'XX') # after this, \\" does not match to \" + return ((line.count('"') - line.count(r'\"') - line.count("'\"'")) & 1) == 1 + + +def FindNextMultiLineCommentStart(lines, lineix): + """Find the beginning marker for a multiline comment.""" + while lineix < len(lines): + if lines[lineix].strip().startswith('/*'): + # Only return this marker if the comment goes beyond this line + if lines[lineix].strip().find('*/', 2) < 0: + return lineix + lineix += 1 + return len(lines) + + +def FindNextMultiLineCommentEnd(lines, lineix): + """We are inside a comment, find the end marker.""" + while lineix < len(lines): + if lines[lineix].strip().endswith('*/'): + return lineix + lineix += 1 + return len(lines) + + +def RemoveMultiLineCommentsFromRange(lines, begin, end): + """Clears a range of lines for multi-line comments.""" + # Having // dummy comments makes the lines non-empty, so we will not get + # unnecessary blank line warnings later in the code. + for i in range(begin, end): + lines[i] = '// dummy' + + +def RemoveMultiLineComments(filename, lines, error): + """Removes multiline (c-style) comments from lines.""" + lineix = 0 + while lineix < len(lines): + lineix_begin = FindNextMultiLineCommentStart(lines, lineix) + if lineix_begin >= len(lines): + return + lineix_end = FindNextMultiLineCommentEnd(lines, lineix_begin) + if lineix_end >= len(lines): + error(filename, lineix_begin + 1, 'readability/multiline_comment', 5, + 'Could not find end of multi-line comment') + return + RemoveMultiLineCommentsFromRange(lines, lineix_begin, lineix_end + 1) + lineix = lineix_end + 1 + + +def CleanseComments(line): + """Removes //-comments and single-line C-style /* */ comments. + + Args: + line: A line of C++ source. + + Returns: + The line with single-line comments removed. + """ + commentpos = line.find('//') + if commentpos != -1 and not IsCppString(line[:commentpos]): + line = line[:commentpos].rstrip() + # get rid of /* ... */ + return _RE_PATTERN_CLEANSE_LINE_C_COMMENTS.sub('', line) + + +class CleansedLines(object): + """Holds 3 copies of all lines with different preprocessing applied to them. + + 1) elided member contains lines without strings and comments, + 2) lines member contains lines without comments, and + 3) raw member contains all the lines without processing. + All these three members are of , and of the same length. + """ + + def __init__(self, lines): + self.elided = [] + self.lines = [] + self.raw_lines = lines + self.num_lines = len(lines) + for linenum in range(len(lines)): + self.lines.append(CleanseComments(lines[linenum])) + elided = self._CollapseStrings(lines[linenum]) + self.elided.append(CleanseComments(elided)) + + def NumLines(self): + """Returns the number of lines represented.""" + return self.num_lines + + @staticmethod + def _CollapseStrings(elided): + """Collapses strings and chars on a line to simple "" or '' blocks. + + We nix strings first so we're not fooled by text like '"http://"' + + Args: + elided: The line being processed. + + Returns: + The line with collapsed strings. + """ + if not _RE_PATTERN_INCLUDE.match(elided): + # Remove escaped characters first to make quote/single quote collapsing + # basic. Things that look like escaped characters shouldn't occur + # outside of strings and chars. + elided = _RE_PATTERN_CLEANSE_LINE_ESCAPES.sub('', elided) + elided = _RE_PATTERN_CLEANSE_LINE_SINGLE_QUOTES.sub("''", elided) + elided = _RE_PATTERN_CLEANSE_LINE_DOUBLE_QUOTES.sub('""', elided) + return elided + + +def CloseExpression(clean_lines, linenum, pos): + """If input points to ( or { or [, finds the position that closes it. + + If lines[linenum][pos] points to a '(' or '{' or '[', finds the + linenum/pos that correspond to the closing of the expression. + + Args: + clean_lines: A CleansedLines instance containing the file. + linenum: The number of the line to check. + pos: A position on the line. + + Returns: + A tuple (line, linenum, pos) pointer *past* the closing brace, or + (line, len(lines), -1) if we never find a close. Note we ignore + strings and comments when matching; and the line we return is the + 'cleansed' line at linenum. + """ + + line = clean_lines.elided[linenum] + startchar = line[pos] + if startchar not in '({[': + return (line, clean_lines.NumLines(), -1) + if startchar == '(': endchar = ')' + if startchar == '[': endchar = ']' + if startchar == '{': endchar = '}' + + num_open = line.count(startchar) - line.count(endchar) + while linenum < clean_lines.NumLines() and num_open > 0: + linenum += 1 + line = clean_lines.elided[linenum] + num_open += line.count(startchar) - line.count(endchar) + # OK, now find the endchar that actually got us back to even + endpos = len(line) + while num_open >= 0: + endpos = line.rfind(')', 0, endpos) + num_open -= 1 # chopped off another ) + return (line, linenum, endpos + 1) + + +def CheckForCopyright(filename, lines, error): + """Logs an error if no Copyright message appears at the top of the file.""" + + # We'll say it should occur by line 10. Don't forget there's a + # dummy line at the front. + for line in xrange(1, min(len(lines), 11)): + if re.search(r'Copyright', lines[line], re.I): break + else: # means no copyright line was found + error(filename, 0, 'legal/copyright', 5, + 'No copyright message found. ' + 'You should have a line: "Copyright [year] "') + + +def GetHeaderGuardCPPVariable(filename): + """Returns the CPP variable that should be used as a header guard. + + Args: + filename: The name of a C++ header file. + + Returns: + The CPP variable that should be used as a header guard in the + named file. + + """ + + # Restores original filename in case that cpplint is invoked from Emacs's + # flymake. + filename = re.sub(r'_flymake\.h$', '.h', filename) + + fileinfo = FileInfo(filename) + return re.sub(r'[-./\s]', '_', fileinfo.RepositoryName()).upper() + '_' + + +def CheckForHeaderGuard(filename, lines, error): + """Checks that the file contains a header guard. + + Logs an error if no #ifndef header guard is present. For other + headers, checks that the full pathname is used. + + Args: + filename: The name of the C++ header file. + lines: An array of strings, each representing a line of the file. + error: The function to call with any errors found. + """ + + cppvar = GetHeaderGuardCPPVariable(filename) + + ifndef = None + ifndef_linenum = 0 + define = None + endif = None + endif_linenum = 0 + for linenum, line in enumerate(lines): + linesplit = line.split() + if len(linesplit) >= 2: + # find the first occurrence of #ifndef and #define, save arg + if not ifndef and linesplit[0] == '#ifndef': + # set ifndef to the header guard presented on the #ifndef line. + ifndef = linesplit[1] + ifndef_linenum = linenum + if not define and linesplit[0] == '#define': + define = linesplit[1] + # find the last occurrence of #endif, save entire line + if line.startswith('#endif'): + endif = line + endif_linenum = linenum + + if not ifndef or not define or ifndef != define: + error(filename, 0, 'build/header_guard', 5, + 'No #ifndef header guard found, suggested CPP variable is: %s' % + cppvar) + return + + # The guard should be PATH_FILE_H_, but we also allow PATH_FILE_H__ + # for backward compatibility. + #if ifndef != cppvar: + # error_level = 0 + # if ifndef != cppvar + '_': + # error_level = 5 + + # ParseNolintSuppressions(filename, lines[ifndef_linenum], ifndef_linenum, + # error) + # error(filename, ifndef_linenum, 'build/header_guard', error_level, + # '#ifndef header guard has wrong style, please use: %s' % cppvar) + + #if endif != ('#endif // %s' % cppvar): + # error_level = 0 + # if endif != ('#endif // %s' % (cppvar + '_')): + # error_level = 5 + + # ParseNolintSuppressions(filename, lines[endif_linenum], endif_linenum, + # error) + # error(filename, endif_linenum, 'build/header_guard', error_level, + # '#endif line should be "#endif // %s"' % cppvar) + + +def CheckForUnicodeReplacementCharacters(filename, lines, error): + """Logs an error for each line containing Unicode replacement characters. + + These indicate that either the file contained invalid UTF-8 (likely) + or Unicode replacement characters (which it shouldn't). Note that + it's possible for this to throw off line numbering if the invalid + UTF-8 occurred adjacent to a newline. + + Args: + filename: The name of the current file. + lines: An array of strings, each representing a line of the file. + error: The function to call with any errors found. + """ + for linenum, line in enumerate(lines): + if u'\ufffd' in line: + error(filename, linenum, 'readability/utf8', 5, + 'Line contains invalid UTF-8 (or Unicode replacement character).') + + +def CheckForNewlineAtEOF(filename, lines, error): + """Logs an error if there is no newline char at the end of the file. + + Args: + filename: The name of the current file. + lines: An array of strings, each representing a line of the file. + error: The function to call with any errors found. + """ + + # The array lines() was created by adding two newlines to the + # original file (go figure), then splitting on \n. + # To verify that the file ends in \n, we just have to make sure the + # last-but-two element of lines() exists and is empty. + if len(lines) < 3 or lines[-2]: + error(filename, len(lines) - 2, 'whitespace/ending_newline', 5, + 'Could not find a newline character at the end of the file.') + + +def CheckForMultilineCommentsAndStrings(filename, clean_lines, linenum, error): + """Logs an error if we see /* ... */ or "..." that extend past one line. + + /* ... */ comments are legit inside macros, for one line. + Otherwise, we prefer // comments, so it's ok to warn about the + other. Likewise, it's ok for strings to extend across multiple + lines, as long as a line continuation character (backslash) + terminates each line. Although not currently prohibited by the C++ + style guide, it's ugly and unnecessary. We don't do well with either + in this lint program, so we warn about both. + + Args: + filename: The name of the current file. + clean_lines: A CleansedLines instance containing the file. + linenum: The number of the line to check. + error: The function to call with any errors found. + """ + line = clean_lines.elided[linenum] + + # Remove all \\ (escaped backslashes) from the line. They are OK, and the + # second (escaped) slash may trigger later \" detection erroneously. + line = line.replace('\\\\', '') + + if line.count('/*') > line.count('*/'): + error(filename, linenum, 'readability/multiline_comment', 5, + 'Complex multi-line /*...*/-style comment found. ' + 'Lint may give bogus warnings. ' + 'Consider replacing these with //-style comments, ' + 'with #if 0...#endif, ' + 'or with more clearly structured multi-line comments.') + + #if (line.count('"') - line.count('\\"')) % 2: + # error(filename, linenum, 'readability/multiline_string', 5, + # 'Multi-line string ("...") found. This lint script doesn\'t ' + # 'do well with such strings, and may give bogus warnings. They\'re ' + # 'ugly and unnecessary, and you should use concatenation instead".') + + +threading_list = ( + ('asctime(', 'asctime_r('), + ('ctime(', 'ctime_r('), + ('getgrgid(', 'getgrgid_r('), + ('getgrnam(', 'getgrnam_r('), + ('getlogin(', 'getlogin_r('), + ('getpwnam(', 'getpwnam_r('), + ('getpwuid(', 'getpwuid_r('), + ('gmtime(', 'gmtime_r('), + ('localtime(', 'localtime_r('), + ('rand(', 'rand_r('), + ('readdir(', 'readdir_r('), + ('strtok(', 'strtok_r('), + ('ttyname(', 'ttyname_r('), + ) + + +def CheckPosixThreading(filename, clean_lines, linenum, error): + """Checks for calls to thread-unsafe functions. + + Much code has been originally written without consideration of + multi-threading. Also, engineers are relying on their old experience; + they have learned posix before threading extensions were added. These + tests guide the engineers to use thread-safe functions (when using + posix directly). + + Args: + filename: The name of the current file. + clean_lines: A CleansedLines instance containing the file. + linenum: The number of the line to check. + error: The function to call with any errors found. + """ + line = clean_lines.elided[linenum] + for single_thread_function, multithread_safe_function in threading_list: + ix = line.find(single_thread_function) + # Comparisons made explicit for clarity -- pylint: disable-msg=C6403 + if ix >= 0 and (ix == 0 or (not line[ix - 1].isalnum() and + line[ix - 1] not in ('_', '.', '>'))): + error(filename, linenum, 'runtime/threadsafe_fn', 2, + 'Consider using ' + multithread_safe_function + + '...) instead of ' + single_thread_function + + '...) for improved thread safety.') + + +# Matches invalid increment: *count++, which moves pointer instead of +# incrementing a value. +_RE_PATTERN_INVALID_INCREMENT = re.compile( + r'^\s*\*\w+(\+\+|--);') + + +def CheckInvalidIncrement(filename, clean_lines, linenum, error): + """Checks for invalid increment *count++. + + For example following function: + void increment_counter(int* count) { + *count++; + } + is invalid, because it effectively does count++, moving pointer, and should + be replaced with ++*count, (*count)++ or *count += 1. + + Args: + filename: The name of the current file. + clean_lines: A CleansedLines instance containing the file. + linenum: The number of the line to check. + error: The function to call with any errors found. + """ + line = clean_lines.elided[linenum] + if _RE_PATTERN_INVALID_INCREMENT.match(line): + error(filename, linenum, 'runtime/invalid_increment', 5, + 'Changing pointer instead of value (or unused value of operator*).') + + +class _ClassInfo(object): + """Stores information about a class.""" + + def __init__(self, name, clean_lines, linenum): + self.name = name + self.linenum = linenum + self.seen_open_brace = False + self.is_derived = False + self.virtual_method_linenumber = None + self.has_virtual_destructor = False + self.brace_depth = 0 + + # Try to find the end of the class. This will be confused by things like: + # class A { + # } *x = { ... + # + # But it's still good enough for CheckSectionSpacing. + self.last_line = 0 + depth = 0 + for i in range(linenum, clean_lines.NumLines()): + line = clean_lines.lines[i] + depth += line.count('{') - line.count('}') + if not depth: + self.last_line = i + break + + +class _ClassState(object): + """Holds the current state of the parse relating to class declarations. + + It maintains a stack of _ClassInfos representing the parser's guess + as to the current nesting of class declarations. The innermost class + is at the top (back) of the stack. Typically, the stack will either + be empty or have exactly one entry. + """ + + def __init__(self): + self.classinfo_stack = [] + + def CheckFinished(self, filename, error): + """Checks that all classes have been completely parsed. + + Call this when all lines in a file have been processed. + Args: + filename: The name of the current file. + error: The function to call with any errors found. + """ + if self.classinfo_stack: + # Note: This test can result in false positives if #ifdef constructs + # get in the way of brace matching. See the testBuildClass test in + # cpplint_unittest.py for an example of this. + error(filename, self.classinfo_stack[0].linenum, 'build/class', 5, + 'Failed to find complete declaration of class %s' % + self.classinfo_stack[0].name) + + +def CheckForNonStandardConstructs(filename, clean_lines, linenum, + class_state, error): + """Logs an error if we see certain non-ANSI constructs ignored by gcc-2. + + Complain about several constructs which gcc-2 accepts, but which are + not standard C++. Warning about these in lint is one way to ease the + transition to new compilers. + - put storage class first (e.g. "static const" instead of "const static"). + - "%lld" instead of %qd" in printf-type functions. + - "%1$d" is non-standard in printf-type functions. + - "\%" is an undefined character escape sequence. + - text after #endif is not allowed. + - invalid inner-style forward declaration. + - >? and ?= and )\?=?\s*(\w+|[+-]?\d+)(\.\d*)?', + line): + error(filename, linenum, 'build/deprecated', 3, + '>? and ))?' + # r'\s*const\s*' + type_name + '\s*&\s*\w+\s*;' + error(filename, linenum, 'runtime/member_string_references', 2, + 'const string& members are dangerous. It is much better to use ' + 'alternatives, such as pointers or simple constants.') + + # Track class entry and exit, and attempt to find cases within the + # class declaration that don't meet the C++ style + # guidelines. Tracking is very dependent on the code matching Google + # style guidelines, but it seems to perform well enough in testing + # to be a worthwhile addition to the checks. + classinfo_stack = class_state.classinfo_stack + # Look for a class declaration. The regexp accounts for decorated classes + # such as in: + # class LOCKABLE API Object { + # }; + class_decl_match = Match( + r'\s*(template\s*<[\w\s<>,:]*>\s*)?' + '(class|struct)\s+([A-Z_]+\s+)*(\w+(::\w+)*)', line) + if class_decl_match: + classinfo_stack.append(_ClassInfo( + class_decl_match.group(4), clean_lines, linenum)) + + # Everything else in this function uses the top of the stack if it's + # not empty. + if not classinfo_stack: + return + + classinfo = classinfo_stack[-1] + + # If the opening brace hasn't been seen look for it and also + # parent class declarations. + if not classinfo.seen_open_brace: + # If the line has a ';' in it, assume it's a forward declaration or + # a single-line class declaration, which we won't process. + if line.find(';') != -1: + classinfo_stack.pop() + return + classinfo.seen_open_brace = (line.find('{') != -1) + # Look for a bare ':' + if Search('(^|[^:]):($|[^:])', line): + classinfo.is_derived = True + if not classinfo.seen_open_brace: + return # Everything else in this function is for after open brace + + # The class may have been declared with namespace or classname qualifiers. + # The constructor and destructor will not have those qualifiers. + base_classname = classinfo.name.split('::')[-1] + + # Look for single-argument constructors that aren't marked explicit. + # Technically a valid construct, but against style. + args = Match(r'\s+(?:inline\s+)?%s\s*\(([^,()]+)\)' + % re.escape(base_classname), + line) + if (args and + args.group(1) != 'void' and + not Match(r'(const\s+)?%s\s*(?:<\w+>\s*)?&' % re.escape(base_classname), + args.group(1).strip())): + error(filename, linenum, 'runtime/explicit', 5, + 'Single-argument constructors should be marked explicit.') + + # Look for methods declared virtual. + if Search(r'\bvirtual\b', line): + classinfo.virtual_method_linenumber = linenum + # Only look for a destructor declaration on the same line. It would + # be extremely unlikely for the destructor declaration to occupy + # more than one line. + if Search(r'~%s\s*\(' % base_classname, line): + classinfo.has_virtual_destructor = True + + # Look for class end. + brace_depth = classinfo.brace_depth + brace_depth = brace_depth + line.count('{') - line.count('}') + if brace_depth <= 0: + classinfo = classinfo_stack.pop() + # Try to detect missing virtual destructor declarations. + # For now, only warn if a non-derived class with virtual methods lacks + # a virtual destructor. This is to make it less likely that people will + # declare derived virtual destructors without declaring the base + # destructor virtual. + if ((classinfo.virtual_method_linenumber is not None) and + (not classinfo.has_virtual_destructor) and + (not classinfo.is_derived)): # Only warn for base classes + error(filename, classinfo.linenum, 'runtime/virtual', 4, + 'The class %s probably needs a virtual destructor due to ' + 'having virtual method(s), one declared at line %d.' + % (classinfo.name, classinfo.virtual_method_linenumber)) + else: + classinfo.brace_depth = brace_depth + + +def CheckSpacingForFunctionCall(filename, line, linenum, error): + """Checks for the correctness of various spacing around function calls. + + Args: + filename: The name of the current file. + line: The text of the line to check. + linenum: The number of the line to check. + error: The function to call with any errors found. + """ + + # Since function calls often occur inside if/for/while/switch + # expressions - which have their own, more liberal conventions - we + # first see if we should be looking inside such an expression for a + # function call, to which we can apply more strict standards. + fncall = line # if there's no control flow construct, look at whole line + for pattern in (r'\bif\s*\((.*)\)\s*{', + r'\bfor\s*\((.*)\)\s*{', + r'\bwhile\s*\((.*)\)\s*[{;]', + r'\bswitch\s*\((.*)\)\s*{'): + match = Search(pattern, line) + if match: + fncall = match.group(1) # look inside the parens for function calls + break + + # Except in if/for/while/switch, there should never be space + # immediately inside parens (eg "f( 3, 4 )"). We make an exception + # for nested parens ( (a+b) + c ). Likewise, there should never be + # a space before a ( when it's a function argument. I assume it's a + # function argument when the char before the whitespace is legal in + # a function name (alnum + _) and we're not starting a macro. Also ignore + # pointers and references to arrays and functions coz they're too tricky: + # we use a very simple way to recognize these: + # " (something)(maybe-something)" or + # " (something)(maybe-something," or + # " (something)[something]" + # Note that we assume the contents of [] to be short enough that + # they'll never need to wrap. + if ( # Ignore control structures. + not Search(r'\b(if|for|while|switch|return|delete)\b', fncall) and + # Ignore pointers/references to functions. + not Search(r' \([^)]+\)\([^)]*(\)|,$)', fncall) and + # Ignore pointers/references to arrays. + not Search(r' \([^)]+\)\[[^\]]+\]', fncall)): + if Search(r'\w\s*\(\s(?!\s*\\$)', fncall): # a ( used for a fn call + error(filename, linenum, 'whitespace/parens', 4, + 'Extra space after ( in function call') + elif Search(r'\(\s+(?!(\s*\\)|\()', fncall): + error(filename, linenum, 'whitespace/parens', 2, + 'Extra space after (') + if (Search(r'\w\s+\(', fncall) and + not Search(r'#\s*define|typedef', fncall) and + not Search(r'<.*',fncall)): + error(filename, linenum, 'whitespace/parens', 4, + 'Extra space before ( in function call') + # If the ) is followed only by a newline or a { + newline, assume it's + # part of a control statement (if/while/etc), and don't complain + if Search(r'[^)]\s+\)\s*[^{\s]', fncall): + # If the closing parenthesis is preceded by only whitespaces, + # try to give a more descriptive error message. + if Search(r'^\s+\)', fncall): + error(filename, linenum, 'whitespace/parens', 2, + 'Closing ) should be moved to the previous line') + else: + error(filename, linenum, 'whitespace/parens', 2, + 'Extra space before )') + + +def IsBlankLine(line): + """Returns true if the given line is blank. + + We consider a line to be blank if the line is empty or consists of + only white spaces. + + Args: + line: A line of a string. + + Returns: + True, if the given line is blank. + """ + return not line or line.isspace() + + +def CheckForFunctionLengths(filename, clean_lines, linenum, + function_state, error): + """Reports for long function bodies. + + For an overview why this is done, see: + http://google-styleguide.googlecode.com/svn/trunk/cppguide.xml#Write_Short_Functions + + Uses a simplistic algorithm assuming other style guidelines + (especially spacing) are followed. + Only checks unindented functions, so class members are unchecked. + Trivial bodies are unchecked, so constructors with huge initializer lists + may be missed. + Blank/comment lines are not counted so as to avoid encouraging the removal + of vertical space and comments just to get through a lint check. + NOLINT *on the last line of a function* disables this check. + + Args: + filename: The name of the current file. + clean_lines: A CleansedLines instance containing the file. + linenum: The number of the line to check. + function_state: Current function name and lines in body so far. + error: The function to call with any errors found. + """ + lines = clean_lines.lines + line = lines[linenum] + raw = clean_lines.raw_lines + raw_line = raw[linenum] + joined_line = '' + + starting_func = False + regexp = r'(\w(\w|::|\*|\&|\s)*)\(' # decls * & space::name( ... + match_result = Match(regexp, line) + if match_result: + # If the name is all caps and underscores, figure it's a macro and + # ignore it, unless it's TEST or TEST_F. + function_name = match_result.group(1).split()[-1] + if function_name == 'TEST' or function_name == 'TEST_F' or ( + not Match(r'[A-Z_]+$', function_name)): + starting_func = True + + if starting_func: + body_found = False + for start_linenum in xrange(linenum, clean_lines.NumLines()): + start_line = lines[start_linenum] + joined_line += ' ' + start_line.lstrip() + if Search(r'(;|})', start_line): # Declarations and trivial functions + body_found = True + break # ... ignore + elif Search(r'{', start_line): + body_found = True + function = Search(r'((\w|:)*)\(', line).group(1) + if Match(r'TEST', function): # Handle TEST... macros + parameter_regexp = Search(r'(\(.*\))', joined_line) + if parameter_regexp: # Ignore bad syntax + function += parameter_regexp.group(1) + else: + function += '()' + function_state.Begin(function) + break + if not body_found: + # No body for the function (or evidence of a non-function) was found. + error(filename, linenum, 'readability/fn_size', 5, + 'Lint failed to find start of function body.') + elif Match(r'^\}\s*$', line): # function end + function_state.Check(error, filename, linenum) + function_state.End() + elif not Match(r'^\s*$', line): + function_state.Count() # Count non-blank/non-comment lines. + + +_RE_PATTERN_TODO = re.compile(r'^//(\s*)TODO(\(.+?\))?:?(\s|$)?') + + +def CheckComment(comment, filename, linenum, error): + """Checks for common mistakes in TODO comments. + + Args: + comment: The text of the comment from the line in question. + filename: The name of the current file. + linenum: The number of the line to check. + error: The function to call with any errors found. + """ + match = _RE_PATTERN_TODO.match(comment) + if match: + # One whitespace is correct; zero whitespace is handled elsewhere. + leading_whitespace = match.group(1) + if len(leading_whitespace) > 1: + error(filename, linenum, 'whitespace/todo', 2, + 'Too many spaces before TODO') + + #username = match.group(2) + #if not username: + # error(filename, linenum, 'readability/todo', 2, + # 'Missing username in TODO; it should look like ' + # '"// TODO(my_username): Stuff."') + + middle_whitespace = match.group(3) + # Comparisons made explicit for correctness -- pylint: disable-msg=C6403 + if middle_whitespace != ' ' and middle_whitespace != '': + error(filename, linenum, 'whitespace/todo', 2, + 'TODO(my_username) should be followed by a space') + + +def CheckSpacing(filename, clean_lines, linenum, error): + """Checks for the correctness of various spacing issues in the code. + + Things we check for: spaces around operators, spaces after + if/for/while/switch, no spaces around parens in function calls, two + spaces between code and comment, don't start a block with a blank + line, don't end a function with a blank line, don't add a blank line + after public/protected/private, don't have too many blank lines in a row. + + Args: + filename: The name of the current file. + clean_lines: A CleansedLines instance containing the file. + linenum: The number of the line to check. + error: The function to call with any errors found. + """ + + raw = clean_lines.raw_lines + line = raw[linenum] + + # Before nixing comments, check if the line is blank for no good + # reason. This includes the first line after a block is opened, and + # blank lines at the end of a function (ie, right before a line like '}' + if IsBlankLine(line): + elided = clean_lines.elided + prev_line = elided[linenum - 1] + prevbrace = prev_line.rfind('{') + # TODO(unknown): Don't complain if line before blank line, and line after, + # both start with alnums and are indented the same amount. + # This ignores whitespace at the start of a namespace block + # because those are not usually indented. + if (prevbrace != -1 and prev_line[prevbrace:].find('}') == -1 + and prev_line[:prevbrace].find('namespace') == -1): + # OK, we have a blank line at the start of a code block. Before we + # complain, we check if it is an exception to the rule: The previous + # non-empty line has the parameters of a function header that are indented + # 4 spaces (because they did not fit in a 80 column line when placed on + # the same line as the function name). We also check for the case where + # the previous line is indented 6 spaces, which may happen when the + # initializers of a constructor do not fit into a 80 column line. + exception = False + if Match(r' {6}\w', prev_line): # Initializer list? + # We are looking for the opening column of initializer list, which + # should be indented 4 spaces to cause 6 space indentation afterwards. + search_position = linenum-2 + while (search_position >= 0 + and Match(r' {6}\w', elided[search_position])): + search_position -= 1 + exception = (search_position >= 0 + and elided[search_position][:5] == ' :') + else: + # Search for the function arguments or an initializer list. We use a + # simple heuristic here: If the line is indented 4 spaces; and we have a + # closing paren, without the opening paren, followed by an opening brace + # or colon (for initializer lists) we assume that it is the last line of + # a function header. If we have a colon indented 4 spaces, it is an + # initializer list. + exception = (Match(r' {4}\w[^\(]*\)\s*(const\s*)?(\{\s*$|:)', + prev_line) + or Match(r' {4}:', prev_line)) + + if not exception: + error(filename, linenum, 'whitespace/blank_line', 2, + 'Blank line at the start of a code block. Is this needed?') + # This doesn't ignore whitespace at the end of a namespace block + # because that is too hard without pairing open/close braces; + # however, a special exception is made for namespace closing + # brackets which have a comment containing "namespace". + # + # Also, ignore blank lines at the end of a block in a long if-else + # chain, like this: + # if (condition1) { + # // Something followed by a blank line + # + # } else if (condition2) { + # // Something else + # } + if linenum + 1 < clean_lines.NumLines(): + next_line = raw[linenum + 1] + if (next_line + and Match(r'\s*}', next_line) + and next_line.find('namespace') == -1 + and next_line.find('} else ') == -1): + error(filename, linenum, 'whitespace/blank_line', 3, + 'Blank line at the end of a code block. Is this needed?') + + #matched = Match(r'\s*(public|protected|private):', prev_line) + #if matched: + # error(filename, linenum, 'whitespace/blank_line', 3, + # 'Do not leave a blank line after "%s:"' % matched.group(1)) + + # Next, we complain if there's a comment too near the text + commentpos = line.find('//') + if commentpos != -1: + # Check if the // may be in quotes. If so, ignore it + # Comparisons made explicit for clarity -- pylint: disable-msg=C6403 + if (line.count('"', 0, commentpos) - + line.count('\\"', 0, commentpos)) % 2 == 0: # not in quotes + # Allow one space for new scopes, two spaces otherwise: + if (not Match(r'^\s*{ //', line) and + ((commentpos >= 1 and + line[commentpos-1] not in string.whitespace) or + (commentpos >= 2 and + line[commentpos-2] not in string.whitespace))): + error(filename, linenum, 'whitespace/comments', 2, + 'At least two spaces is best between code and comments') + # There should always be a space between the // and the comment + commentend = commentpos + 2 + if commentend < len(line) and not line[commentend] == ' ': + # but some lines are exceptions -- e.g. if they're big + # comment delimiters like: + # //---------------------------------------------------------- + # or are an empty C++ style Doxygen comment, like: + # /// + # or they begin with multiple slashes followed by a space: + # //////// Header comment + match = (Search(r'[=/-]{4,}\s*$', line[commentend:]) or + Search(r'^/$', line[commentend:]) or + Search(r'^/+ ', line[commentend:])) + if not match: + error(filename, linenum, 'whitespace/comments', 4, + 'Should have a space between // and comment') + CheckComment(line[commentpos:], filename, linenum, error) + + line = clean_lines.elided[linenum] # get rid of comments and strings + + # Don't try to do spacing checks for operator methods + line = re.sub(r'operator(==|!=|<|<<|<=|>=|>>|>)\(', 'operator\(', line) + + # We allow no-spaces around = within an if: "if ( (a=Foo()) == 0 )". + # Otherwise not. Note we only check for non-spaces on *both* sides; + # sometimes people put non-spaces on one side when aligning ='s among + # many lines (not that this is behavior that I approve of...) + if Search(r'[\w.]=[\w.]', line) and not Search(r'\b(if|while) ', line): + error(filename, linenum, 'whitespace/operators', 4, + 'Missing spaces around =') + + # It's ok not to have spaces around binary operators like + - * /, but if + # there's too little whitespace, we get concerned. It's hard to tell, + # though, so we punt on this one for now. TODO. + + # You should always have whitespace around binary operators. + # Alas, we can't test < or > because they're legitimately used sans spaces + # (a->b, vector a). The only time we can tell is a < with no >, and + # only if it's not template params list spilling into the next line. + match = Search(r'[^<>=!\s](==|!=|<=|>=)[^<>=!\s]', line) + if not match: + # Note that while it seems that the '<[^<]*' term in the following + # regexp could be simplified to '<.*', which would indeed match + # the same class of strings, the [^<] means that searching for the + # regexp takes linear rather than quadratic time. + if not Search(r'<[^<]*,\s*$', line): # template params spill + match = Search(r'[^<>=!\s](<)[^<>=!\s]([^>]|->)*$', line) + if match: + error(filename, linenum, 'whitespace/operators', 3, + 'Missing spaces around %s' % match.group(1)) + # We allow no-spaces around << and >> when used like this: 10<<20, but + # not otherwise (particularly, not when used as streams) + match = Search(r'[^0-9\s](<<|>>)[^0-9\s]', line) + if match: + error(filename, linenum, 'whitespace/operators', 3, + 'Missing spaces around %s' % match.group(1)) + + # There shouldn't be space around unary operators + match = Search(r'(!\s|~\s|[\s]--[\s;]|[\s]\+\+[\s;])', line) + if match: + error(filename, linenum, 'whitespace/operators', 4, + 'Extra space for operator %s' % match.group(1)) + + # A pet peeve of mine: no spaces after an if, while, switch, or for + match = Search(r' (if\(|for\(|while\(|switch\()', line) + if match: + error(filename, linenum, 'whitespace/parens', 5, + 'Missing space before ( in %s' % match.group(1)) + + # For if/for/while/switch, the left and right parens should be + # consistent about how many spaces are inside the parens, and + # there should either be zero or one spaces inside the parens. + # We don't want: "if ( foo)" or "if ( foo )". + # Exception: "for ( ; foo; bar)" and "for (foo; bar; )" are allowed. + match = Search(r'\b(if|for|while|switch)\s*' + r'\(([ ]*)(.).*[^ ]+([ ]*)\)\s*{\s*$', + line) + if match: + if len(match.group(2)) != len(match.group(4)): + if not (match.group(3) == ';' and + len(match.group(2)) == 1 + len(match.group(4)) or + not match.group(2) and Search(r'\bfor\s*\(.*; \)', line)): + error(filename, linenum, 'whitespace/parens', 5, + 'Mismatching spaces inside () in %s' % match.group(1)) + if not len(match.group(2)) in [0, 1]: + error(filename, linenum, 'whitespace/parens', 5, + 'Should have zero or one spaces inside ( and ) in %s' % + match.group(1)) + + # You should always have a space after a comma (either as fn arg or operator) + if Search(r',[^\s]', line): + error(filename, linenum, 'whitespace/comma', 3, + 'Missing space after ,') + + # You should always have a space after a semicolon + # except for few corner cases + # TODO(unknown): clarify if 'if (1) { return 1;}' is requires one more + # space after ; + if Search(r';[^\s};\\)/]', line): + error(filename, linenum, 'whitespace/semicolon', 3, + 'Missing space after ;') + + # Next we will look for issues with function calls. + CheckSpacingForFunctionCall(filename, line, linenum, error) + + # Except after an opening paren, or after another opening brace (in case of + # an initializer list, for instance), you should have spaces before your + # braces. And since you should never have braces at the beginning of a line, + # this is an easy test. + if Search(r'[^ ({]{', line): + error(filename, linenum, 'whitespace/braces', 5, + 'Missing space before {') + + # Make sure '} else {' has spaces. + if Search(r'}else', line): + error(filename, linenum, 'whitespace/braces', 5, + 'Missing space before else') + + # You shouldn't have spaces before your brackets, except maybe after + # 'delete []' or 'new char * []'. + if Search(r'\w\s+\[', line) and not Search(r'delete\s+\[', line): + error(filename, linenum, 'whitespace/braces', 5, + 'Extra space before [') + + # You shouldn't have a space before a semicolon at the end of the line. + # There's a special case for "for" since the style guide allows space before + # the semicolon there. + if Search(r':\s*;\s*$', line): + error(filename, linenum, 'whitespace/semicolon', 5, + 'Semicolon defining empty statement. Use { } instead.') + elif Search(r'^\s*;\s*$', line): + error(filename, linenum, 'whitespace/semicolon', 5, + 'Line contains only semicolon. If this should be an empty statement, ' + 'use { } instead.') + elif (Search(r'\s+;\s*$', line) and + not Search(r'\bfor\b', line)): + error(filename, linenum, 'whitespace/semicolon', 5, + 'Extra space before last semicolon. If this should be an empty ' + 'statement, use { } instead.') + + +def CheckSectionSpacing(filename, clean_lines, class_info, linenum, error): + """Checks for additional blank line issues related to sections. + + Currently the only thing checked here is blank line before protected/private. + + Args: + filename: The name of the current file. + clean_lines: A CleansedLines instance containing the file. + class_info: A _ClassInfo objects. + linenum: The number of the line to check. + error: The function to call with any errors found. + """ + # Skip checks if the class is small, where small means 25 lines or less. + # 25 lines seems like a good cutoff since that's the usual height of + # terminals, and any class that can't fit in one screen can't really + # be considered "small". + # + # Also skip checks if we are on the first line. This accounts for + # classes that look like + # class Foo { public: ... }; + # + # If we didn't find the end of the class, last_line would be zero, + # and the check will be skipped by the first condition. + if (class_info.last_line - class_info.linenum <= 24 or + linenum <= class_info.linenum): + return + + matched = Match(r'\s*(public|protected|private):', clean_lines.lines[linenum]) + if matched: + # Issue warning if the line before public/protected/private was + # not a blank line, but don't do this if the previous line contains + # "class" or "struct". This can happen two ways: + # - We are at the beginning of the class. + # - We are forward-declaring an inner class that is semantically + # private, but needed to be public for implementation reasons. + prev_line = clean_lines.lines[linenum - 1] + if (not IsBlankLine(prev_line) and + not Search(r'\b(class|struct)\b', prev_line)): + # Try a bit harder to find the beginning of the class. This is to + # account for multi-line base-specifier lists, e.g.: + # class Derived + # : public Base { + end_class_head = class_info.linenum + for i in range(class_info.linenum, linenum): + if Search(r'\{\s*$', clean_lines.lines[i]): + end_class_head = i + break + if end_class_head < linenum - 1: + error(filename, linenum, 'whitespace/blank_line', 3, + '"%s:" should be preceded by a blank line' % matched.group(1)) + + +def GetPreviousNonBlankLine(clean_lines, linenum): + """Return the most recent non-blank line and its line number. + + Args: + clean_lines: A CleansedLines instance containing the file contents. + linenum: The number of the line to check. + + Returns: + A tuple with two elements. The first element is the contents of the last + non-blank line before the current line, or the empty string if this is the + first non-blank line. The second is the line number of that line, or -1 + if this is the first non-blank line. + """ + + prevlinenum = linenum - 1 + while prevlinenum >= 0: + prevline = clean_lines.elided[prevlinenum] + if not IsBlankLine(prevline): # if not a blank line... + return (prevline, prevlinenum) + prevlinenum -= 1 + return ('', -1) + + +def CheckBraces(filename, clean_lines, linenum, error): + """Looks for misplaced braces (e.g. at the end of line). + + Args: + filename: The name of the current file. + clean_lines: A CleansedLines instance containing the file. + linenum: The number of the line to check. + error: The function to call with any errors found. + """ + + line = clean_lines.elided[linenum] # get rid of comments and strings + if Search(r'[\);:}]\s*{\s*$', line): + error(filename, linenum, 'whitespace/braces', 4, + '{ should never be at the end of the previous line') + + # An else clause should be on the same line as the preceding closing brace. + if Match(r'\s*}\s*else\s*', line): + error(filename, linenum, 'whitespace/newline', 4, + 'An else should not appear on the same line as the previous }') + + if Match(r'\s*else\s*{', line): + error(filename, linenum, 'whitespace/newline', 4, + 'An else should not appear on the same line as the next {') + + # If braces come on one side of an else, they should be on both. + # However, we have to worry about "else if" that spans multiple lines! + if Search(r'}\s*else[^{]*$', line) or Match(r'[^}]*else\s*{', line): + if Search(r'}\s*else if([^{]*)$', line): # could be multi-line if + # find the ( after the if + pos = line.find('else if') + pos = line.find('(', pos) + if pos > 0: + (endline, _, endpos) = CloseExpression(clean_lines, linenum, pos) + if endline[endpos:].find('{') == -1: # must be brace after if + error(filename, linenum, 'readability/braces', 5, + 'If an else has a brace on one side, it should have it on both') + else: # common case: else not followed by a multi-line if + error(filename, linenum, 'readability/braces', 5, + 'If an else has a brace on one side, it should have it on both') + + # Likewise, an else should never have the else clause on the same line + if Search(r'\belse [^\s{]', line) and not Search(r'\belse if\b', line): + error(filename, linenum, 'whitespace/newline', 4, + 'Else clause should never be on same line as else (use 2 lines)') + + # In the same way, a do/while should never be on one line + if Match(r'\s*do [^\s{]', line): + error(filename, linenum, 'whitespace/newline', 4, + 'do/while clauses should not be on a single line') + + # Braces shouldn't be followed by a ; unless they're defining a struct + # or initializing an array. + # We can't tell in general, but we can for some common cases. + prevlinenum = linenum + while True: + (prevline, prevlinenum) = GetPreviousNonBlankLine(clean_lines, prevlinenum) + if Match(r'\s+{.*}\s*;', line) and not prevline.count(';'): + line = prevline + line + else: + break + if (Search(r'{.*}\s*;', line) and + line.count('{') == line.count('}') and + not Search(r'struct|class|enum|\s*=\s*{', line)): + error(filename, linenum, 'readability/braces', 4, + "You don't need a ; after a }") + + +def ReplaceableCheck(operator, macro, line): + """Determine whether a basic CHECK can be replaced with a more specific one. + + For example suggest using CHECK_EQ instead of CHECK(a == b) and + similarly for CHECK_GE, CHECK_GT, CHECK_LE, CHECK_LT, CHECK_NE. + + Args: + operator: The C++ operator used in the CHECK. + macro: The CHECK or EXPECT macro being called. + line: The current source line. + + Returns: + True if the CHECK can be replaced with a more specific one. + """ + + # This matches decimal and hex integers, strings, and chars (in that order). + match_constant = r'([-+]?(\d+|0[xX][0-9a-fA-F]+)[lLuU]{0,3}|".*"|\'.*\')' + + # Expression to match two sides of the operator with something that + # looks like a literal, since CHECK(x == iterator) won't compile. + # This means we can't catch all the cases where a more specific + # CHECK is possible, but it's less annoying than dealing with + # extraneous warnings. + match_this = (r'\s*' + macro + r'\((\s*' + + match_constant + r'\s*' + operator + r'[^<>].*|' + r'.*[^<>]' + operator + r'\s*' + match_constant + + r'\s*\))') + + # Don't complain about CHECK(x == NULL) or similar because + # CHECK_EQ(x, NULL) won't compile (requires a cast). + # Also, don't complain about more complex boolean expressions + # involving && or || such as CHECK(a == b || c == d). + return Match(match_this, line) and not Search(r'NULL|&&|\|\|', line) + + +def CheckCheck(filename, clean_lines, linenum, error): + """Checks the use of CHECK and EXPECT macros. + + Args: + filename: The name of the current file. + clean_lines: A CleansedLines instance containing the file. + linenum: The number of the line to check. + error: The function to call with any errors found. + """ + + # Decide the set of replacement macros that should be suggested + raw_lines = clean_lines.raw_lines + current_macro = '' + for macro in _CHECK_MACROS: + if raw_lines[linenum].find(macro) >= 0: + current_macro = macro + break + if not current_macro: + # Don't waste time here if line doesn't contain 'CHECK' or 'EXPECT' + return + + line = clean_lines.elided[linenum] # get rid of comments and strings + + # Encourage replacing plain CHECKs with CHECK_EQ/CHECK_NE/etc. + for operator in ['==', '!=', '>=', '>', '<=', '<']: + if ReplaceableCheck(operator, current_macro, line): + error(filename, linenum, 'readability/check', 2, + 'Consider using %s instead of %s(a %s b)' % ( + _CHECK_REPLACEMENT[current_macro][operator], + current_macro, operator)) + break + + +def GetLineWidth(line): + """Determines the width of the line in column positions. + + Args: + line: A string, which may be a Unicode string. + + Returns: + The width of the line in column positions, accounting for Unicode + combining characters and wide characters. + """ + if isinstance(line, unicode): + width = 0 + for uc in unicodedata.normalize('NFC', line): + if unicodedata.east_asian_width(uc) in ('W', 'F'): + width += 2 + elif not unicodedata.combining(uc): + width += 1 + return width + else: + return len(line) + + +def CheckStyle(filename, clean_lines, linenum, file_extension, class_state, + error): + """Checks rules from the 'C++ style rules' section of cppguide.html. + + Most of these rules are hard to test (naming, comment style), but we + do what we can. In particular we check for 2-space indents, line lengths, + tab usage, spaces inside code, etc. + + Args: + filename: The name of the current file. + clean_lines: A CleansedLines instance containing the file. + linenum: The number of the line to check. + file_extension: The extension (without the dot) of the filename. + error: The function to call with any errors found. + """ + + raw_lines = clean_lines.raw_lines + line = raw_lines[linenum] + + if line.find('\t') != -1: + error(filename, linenum, 'whitespace/tab', 1, + 'Tab found; better to use spaces') + + # One or three blank spaces at the beginning of the line is weird; it's + # hard to reconcile that with 2-space indents. + # NOTE: here are the conditions rob pike used for his tests. Mine aren't + # as sophisticated, but it may be worth becoming so: RLENGTH==initial_spaces + # if(RLENGTH > 20) complain = 0; + # if(match($0, " +(error|private|public|protected):")) complain = 0; + # if(match(prev, "&& *$")) complain = 0; + # if(match(prev, "\\|\\| *$")) complain = 0; + # if(match(prev, "[\",=><] *$")) complain = 0; + # if(match($0, " <<")) complain = 0; + # if(match(prev, " +for \\(")) complain = 0; + # if(prevodd && match(prevprev, " +for \\(")) complain = 0; + initial_spaces = 0 + cleansed_line = clean_lines.elided[linenum] + while initial_spaces < len(line) and line[initial_spaces] == ' ': + initial_spaces += 1 + if line and line[-1].isspace(): + error(filename, linenum, 'whitespace/end_of_line', 4, + 'Line ends in whitespace. Consider deleting these extra spaces.') + # There are certain situations we allow one space, notably for labels + elif ((initial_spaces == 1 or initial_spaces == 3) and + not Match(r'\s*\w+\s*:\s*$', cleansed_line)): + error(filename, linenum, 'whitespace/indent', 3, + 'Weird number of spaces at line-start. ' + 'Are you using a 2-space indent?') + # Labels should always be indented at least one space. + elif not initial_spaces and line[:2] != '//' and Search(r'[^:]:\s*$', + line): + error(filename, linenum, 'whitespace/labels', 4, + 'Labels should always be indented at least one space. ' + 'If this is a member-initializer list in a constructor or ' + 'the base class list in a class definition, the colon should ' + 'be on the following line.') + + + # Check if the line is a header guard. + is_header_guard = False + if file_extension == 'h': + cppvar = GetHeaderGuardCPPVariable(filename) + if (line.startswith('#ifndef %s' % cppvar) or + line.startswith('#define %s' % cppvar) or + line.startswith('#endif // %s' % cppvar)): + is_header_guard = True + # #include lines and header guards can be long, since there's no clean way to + # split them. + # + # URLs can be long too. It's possible to split these, but it makes them + # harder to cut&paste. + # + # The "$Id:...$" comment may also get very long without it being the + # developers fault. + if (not line.startswith('#include') and not is_header_guard and + not Match(r'^\s*//.*http(s?)://\S*$', line) and + not Match(r'^// \$Id:.*#[0-9]+ \$$', line)): + line_width = GetLineWidth(line) + if line_width > 100: + error(filename, linenum, 'whitespace/line_length', 4, + 'Lines should very rarely be longer than 100 characters') + elif line_width > 80: + error(filename, linenum, 'whitespace/line_length', 2, + 'Lines should be <= 80 characters long') + + if (cleansed_line.count(';') > 1 and + # for loops are allowed two ;'s (and may run over two lines). + cleansed_line.find('for') == -1 and + (GetPreviousNonBlankLine(clean_lines, linenum)[0].find('for') == -1 or + GetPreviousNonBlankLine(clean_lines, linenum)[0].find(';') != -1) and + # It's ok to have many commands in a switch case that fits in 1 line + not ((cleansed_line.find('case ') != -1 or + cleansed_line.find('default:') != -1) and + cleansed_line.find('break;') != -1)): + error(filename, linenum, 'whitespace/newline', 4, + 'More than one command on the same line') + + # Some more style checks + CheckBraces(filename, clean_lines, linenum, error) + CheckSpacing(filename, clean_lines, linenum, error) + CheckCheck(filename, clean_lines, linenum, error) + if class_state and class_state.classinfo_stack: + CheckSectionSpacing(filename, clean_lines, + class_state.classinfo_stack[-1], linenum, error) + + +_RE_PATTERN_INCLUDE_NEW_STYLE = re.compile(r'#include +"[^/]+\.h"') +_RE_PATTERN_INCLUDE = re.compile(r'^\s*#\s*include\s*([<"])([^>"]*)[>"].*$') +# Matches the first component of a filename delimited by -s and _s. That is: +# _RE_FIRST_COMPONENT.match('foo').group(0) == 'foo' +# _RE_FIRST_COMPONENT.match('foo.cc').group(0) == 'foo' +# _RE_FIRST_COMPONENT.match('foo-bar_baz.cc').group(0) == 'foo' +# _RE_FIRST_COMPONENT.match('foo_bar-baz.cc').group(0) == 'foo' +_RE_FIRST_COMPONENT = re.compile(r'^[^-_.]+') + + +def _DropCommonSuffixes(filename): + """Drops common suffixes like _test.cc or -inl.h from filename. + + For example: + >>> _DropCommonSuffixes('foo/foo-inl.h') + 'foo/foo' + >>> _DropCommonSuffixes('foo/bar/foo.cc') + 'foo/bar/foo' + >>> _DropCommonSuffixes('foo/foo_internal.h') + 'foo/foo' + >>> _DropCommonSuffixes('foo/foo_unusualinternal.h') + 'foo/foo_unusualinternal' + + Args: + filename: The input filename. + + Returns: + The filename with the common suffix removed. + """ + for suffix in ('test.cc', 'regtest.cc', 'unittest.cc', + 'inl.h', 'impl.h', 'internal.h'): + if (filename.endswith(suffix) and len(filename) > len(suffix) and + filename[-len(suffix) - 1] in ('-', '_')): + return filename[:-len(suffix) - 1] + return os.path.splitext(filename)[0] + + +def _IsTestFilename(filename): + """Determines if the given filename has a suffix that identifies it as a test. + + Args: + filename: The input filename. + + Returns: + True if 'filename' looks like a test, False otherwise. + """ + if (filename.endswith('_test.cc') or + filename.endswith('_unittest.cc') or + filename.endswith('_regtest.cc')): + return True + else: + return False + + +def _ClassifyInclude(fileinfo, include, is_system): + """Figures out what kind of header 'include' is. + + Args: + fileinfo: The current file cpplint is running over. A FileInfo instance. + include: The path to a #included file. + is_system: True if the #include used <> rather than "". + + Returns: + One of the _XXX_HEADER constants. + + For example: + >>> _ClassifyInclude(FileInfo('foo/foo.cc'), 'stdio.h', True) + _C_SYS_HEADER + >>> _ClassifyInclude(FileInfo('foo/foo.cc'), 'string', True) + _CPP_SYS_HEADER + >>> _ClassifyInclude(FileInfo('foo/foo.cc'), 'foo/foo.h', False) + _LIKELY_MY_HEADER + >>> _ClassifyInclude(FileInfo('foo/foo_unknown_extension.cc'), + ... 'bar/foo_other_ext.h', False) + _POSSIBLE_MY_HEADER + >>> _ClassifyInclude(FileInfo('foo/foo.cc'), 'foo/bar.h', False) + _OTHER_HEADER + """ + # This is a list of all standard c++ header files, except + # those already checked for above. + is_stl_h = include in _STL_HEADERS + is_cpp_h = is_stl_h or include in _CPP_HEADERS or include.find(".hpp") or include.find(".hh") > 0 + + if is_system: + if is_cpp_h: + return _CPP_SYS_HEADER + else: + return _C_SYS_HEADER + + # If the target file and the include we're checking share a + # basename when we drop common extensions, and the include + # lives in . , then it's likely to be owned by the target file. + target_dir, target_base = ( + os.path.split(_DropCommonSuffixes(fileinfo.RepositoryName()))) + include_dir, include_base = os.path.split(_DropCommonSuffixes(include)) + if target_base == include_base and ( + include_dir == target_dir or + include_dir == os.path.normpath(target_dir + '/../public')): + return _LIKELY_MY_HEADER + + # If the target and include share some initial basename + # component, it's possible the target is implementing the + # include, so it's allowed to be first, but we'll never + # complain if it's not there. + target_first_component = _RE_FIRST_COMPONENT.match(target_base) + include_first_component = _RE_FIRST_COMPONENT.match(include_base) + if (target_first_component and include_first_component and + target_first_component.group(0) == + include_first_component.group(0)): + return _POSSIBLE_MY_HEADER + + return _OTHER_HEADER + + + +def CheckIncludeLine(filename, clean_lines, linenum, include_state, error): + """Check rules that are applicable to #include lines. + + Strings on #include lines are NOT removed from elided line, to make + certain tasks easier. However, to prevent false positives, checks + applicable to #include lines in CheckLanguage must be put here. + + Args: + filename: The name of the current file. + clean_lines: A CleansedLines instance containing the file. + linenum: The number of the line to check. + include_state: An _IncludeState instance in which the headers are inserted. + error: The function to call with any errors found. + """ + fileinfo = FileInfo(filename) + + line = clean_lines.lines[linenum] + + # "include" should use the new style "foo/bar.h" instead of just "bar.h" + #if _RE_PATTERN_INCLUDE_NEW_STYLE.search(line): + # error(filename, linenum, 'build/include', 4, + # 'Include the directory when naming .h files') + + # we shouldn't include a file more than once. actually, there are a + # handful of instances where doing so is okay, but in general it's + # not. + match = _RE_PATTERN_INCLUDE.search(line) + if match: + include = match.group(2) + is_system = (match.group(1) == '<') + if include in include_state: + error(filename, linenum, 'build/include', 4, + '"%s" already included at %s:%s' % + (include, filename, include_state[include])) + else: + include_state[include] = linenum + + # We want to ensure that headers appear in the right order: + # 1) for foo.cc, foo.h (preferred location) + # 2) c system files + # 3) cpp system files + # 4) for foo.cc, foo.h (deprecated location) + # 5) other google headers + # + # We classify each include statement as one of those 5 types + # using a number of techniques. The include_state object keeps + # track of the highest type seen, and complains if we see a + # lower type after that. + error_message = include_state.CheckNextIncludeOrder( + _ClassifyInclude(fileinfo, include, is_system)) + if error_message: + error(filename, linenum, 'build/include_order', 4, + '%s. Should be: c system, c++ system, other, %s.h .' % + (error_message, fileinfo.BaseName())) + if not include_state.IsInAlphabeticalOrder(include): + error(filename, linenum, 'build/include_alpha', 4, + 'Include "%s" not in alphabetical order' % include) + + # Look for any of the stream classes that are part of standard C++. + #match = _RE_PATTERN_INCLUDE.match(line) + #if match: + # include = match.group(2) + # if Match(r'(f|ind|io|i|o|parse|pf|stdio|str|)?stream$', include): + # # Many unit tests use cout, so we exempt them. + # if not _IsTestFilename(filename): + # error(filename, linenum, 'readability/streams', 3, + # 'Streams are highly discouraged.') + + +def _GetTextInside(text, start_pattern): + """Retrieves all the text between matching open and close parentheses. + + Given a string of lines and a regular expression string, retrieve all the text + following the expression and between opening punctuation symbols like + (, [, or {, and the matching close-punctuation symbol. This properly nested + occurrences of the punctuations, so for the text like + printf(a(), b(c())); + a call to _GetTextInside(text, r'printf\(') will return 'a(), b(c())'. + start_pattern must match string having an open punctuation symbol at the end. + + Args: + text: The lines to extract text. Its comments and strings must be elided. + It can be single line and can span multiple lines. + start_pattern: The regexp string indicating where to start extracting + the text. + Returns: + The extracted text. + None if either the opening string or ending punctuation could not be found. + """ + # TODO(sugawarayu): Audit cpplint.py to see what places could be profitably + # rewritten to use _GetTextInside (and use inferior regexp matching today). + + # Give opening punctuations to get the matching close-punctuations. + matching_punctuation = {'(': ')', '{': '}', '[': ']'} + closing_punctuation = set(matching_punctuation.itervalues()) + + # Find the position to start extracting text. + match = re.search(start_pattern, text, re.M) + if not match: # start_pattern not found in text. + return None + start_position = match.end(0) + + assert start_position > 0, ( + 'start_pattern must ends with an opening punctuation.') + assert text[start_position - 1] in matching_punctuation, ( + 'start_pattern must ends with an opening punctuation.') + # Stack of closing punctuations we expect to have in text after position. + punctuation_stack = [matching_punctuation[text[start_position - 1]]] + position = start_position + while punctuation_stack and position < len(text): + if text[position] == punctuation_stack[-1]: + punctuation_stack.pop() + elif text[position] in closing_punctuation: + # A closing punctuation without matching opening punctuations. + return None + elif text[position] in matching_punctuation: + punctuation_stack.append(matching_punctuation[text[position]]) + position += 1 + if punctuation_stack: + # Opening punctuations left without matching close-punctuations. + return None + # punctuations match. + return text[start_position:position - 1] + + +def CheckLanguage(filename, clean_lines, linenum, file_extension, include_state, + error): + """Checks rules from the 'C++ language rules' section of cppguide.html. + + Some of these rules are hard to test (function overloading, using + uint32 inappropriately), but we do the best we can. + + Args: + filename: The name of the current file. + clean_lines: A CleansedLines instance containing the file. + linenum: The number of the line to check. + file_extension: The extension (without the dot) of the filename. + include_state: An _IncludeState instance in which the headers are inserted. + error: The function to call with any errors found. + """ + # If the line is empty or consists of entirely a comment, no need to + # check it. + line = clean_lines.elided[linenum] + if not line: + return + + match = _RE_PATTERN_INCLUDE.search(line) + if match: + CheckIncludeLine(filename, clean_lines, linenum, include_state, error) + return + + # Create an extended_line, which is the concatenation of the current and + # next lines, for more effective checking of code that may span more than one + # line. + if linenum + 1 < clean_lines.NumLines(): + extended_line = line + clean_lines.elided[linenum + 1] + else: + extended_line = line + + # Make Windows paths like Unix. + fullname = os.path.abspath(filename).replace('\\', '/') + + # TODO(unknown): figure out if they're using default arguments in fn proto. + + # Check for non-const references in functions. This is tricky because & + # is also used to take the address of something. We allow <> for templates, + # (ignoring whatever is between the braces) and : for classes. + # These are complicated re's. They try to capture the following: + # paren (for fn-prototype start), typename, &, varname. For the const + # version, we're willing for const to be before typename or after + # Don't check the implementation on same line. + #fnline = line.split('{', 1)[0] + #if (len(re.findall(r'\([^()]*\b(?:[\w:]|<[^()]*>)+(\s?&|&\s?)\w+', fnline)) > + # len(re.findall(r'\([^()]*\bconst\s+(?:typename\s+)?(?:struct\s+)?' + # r'(?:[\w:]|<[^()]*>)+(\s?&|&\s?)\w+', fnline)) + + # len(re.findall(r'\([^()]*\b(?:[\w:]|<[^()]*>)+\s+const(\s?&|&\s?)[\w]+', + # fnline))): + + # # We allow non-const references in a few standard places, like functions + # # called "swap()" or iostream operators like "<<" or ">>". + # if not Search( + # r'(swap|Swap|operator[<>][<>])\s*\(\s*(?:[\w:]|<.*>)+\s*&', + # fnline): + # error(filename, linenum, 'runtime/references', 2, + # 'Is this a non-const reference? ' + # 'If so, make const or use a pointer.') + + # Check to see if they're using an conversion function cast. + # I just try to capture the most common basic types, though there are more. + # Parameterless conversion functions, such as bool(), are allowed as they are + # probably a member operator declaration or default constructor. + match = Search( + r'(\bnew\s+)?\b' # Grab 'new' operator, if it's there + r'(int|float|double|bool|char|int32|uint32|int64|uint64)\([^)]', line) + if match: + # gMock methods are defined using some variant of MOCK_METHODx(name, type) + # where type may be float(), int(string), etc. Without context they are + # virtually indistinguishable from int(x) casts. Likewise, gMock's + # MockCallback takes a template parameter of the form return_type(arg_type), + # which looks much like the cast we're trying to detect. + if (match.group(1) is None and # If new operator, then this isn't a cast + not (Match(r'^\s*MOCK_(CONST_)?METHOD\d+(_T)?\(', line) or + Match(r'^\s*MockCallback<.*>', line))): + error(filename, linenum, 'readability/casting', 4, + 'Using deprecated casting style. ' + 'Use static_cast<%s>(...) instead' % + match.group(2)) + + CheckCStyleCast(filename, linenum, line, clean_lines.raw_lines[linenum], + 'static_cast', + r'\((int|float|double|bool|char|u?int(16|32|64))\)', error) + + # This doesn't catch all cases. Consider (const char * const)"hello". + # + # (char *) "foo" should always be a const_cast (reinterpret_cast won't + # compile). + if CheckCStyleCast(filename, linenum, line, clean_lines.raw_lines[linenum], + 'const_cast', r'\((char\s?\*+\s?)\)\s*"', error): + pass + else: + # Check pointer casts for other than string constants + CheckCStyleCast(filename, linenum, line, clean_lines.raw_lines[linenum], + 'reinterpret_cast', r'\((\w+\s?\*+\s?)\)', error) + + # In addition, we look for people taking the address of a cast. This + # is dangerous -- casts can assign to temporaries, so the pointer doesn't + # point where you think. + if Search( + r'(&\([^)]+\)[\w(])|(&(static|dynamic|reinterpret)_cast\b)', line): + error(filename, linenum, 'runtime/casting', 4, + ('Are you taking an address of a cast? ' + 'This is dangerous: could be a temp var. ' + 'Take the address before doing the cast, rather than after')) + + # Check for people declaring static/global STL strings at the top level. + # This is dangerous because the C++ language does not guarantee that + # globals with constructors are initialized before the first access. + match = Match( + r'((?:|static +)(?:|const +))string +([a-zA-Z0-9_:]+)\b(.*)', + line) + # Make sure it's not a function. + # Function template specialization looks like: "string foo(...". + # Class template definitions look like: "string Foo::Method(...". + if match and not Match(r'\s*(<.*>)?(::[a-zA-Z0-9_]+)?\s*\(([^"]|$)', + match.group(3)): + error(filename, linenum, 'runtime/string', 4, + 'For a static/global string constant, use a C style string instead: ' + '"%schar %s[]".' % + (match.group(1), match.group(2))) + + # Check that we're not using RTTI outside of testing code. + #if Search(r'\bdynamic_cast<', line) and not _IsTestFilename(filename): + # error(filename, linenum, 'runtime/rtti', 5, + # 'Do not use dynamic_cast<>. If you need to cast within a class ' + # "hierarchy, use static_cast<> to upcast. Google doesn't support " + # 'RTTI.') + + if Search(r'\b([A-Za-z0-9_]*_)\(\1\)', line): + error(filename, linenum, 'runtime/init', 4, + 'You seem to be initializing a member variable with itself.') + + if file_extension == 'h': + # TODO(unknown): check that 1-arg constructors are explicit. + # How to tell it's a constructor? + # (handled in CheckForNonStandardConstructs for now) + # TODO(unknown): check that classes have DISALLOW_EVIL_CONSTRUCTORS + # (level 1 error) + pass + + # Check if people are using the verboten C basic types. The only exception + # we regularly allow is "unsigned short port" for port. + if Search(r'\bshort port\b', line): + if not Search(r'\bunsigned short port\b', line): + error(filename, linenum, 'runtime/int', 4, + 'Use "unsigned short" for ports, not "short"') + else: + match = Search(r'\b(short|long(?! +double)|long long)\b', line) + if match: + error(filename, linenum, 'runtime/int', 4, + 'Use int16/int64/etc, rather than the C type %s' % match.group(1)) + + # When snprintf is used, the second argument shouldn't be a literal. + match = Search(r'snprintf\s*\(([^,]*),\s*([0-9]*)\s*,', line) + if match and match.group(2) != '0': + # If 2nd arg is zero, snprintf is used to calculate size. + error(filename, linenum, 'runtime/printf', 3, + 'If you can, use sizeof(%s) instead of %s as the 2nd arg ' + 'to snprintf.' % (match.group(1), match.group(2))) + + # Check if some verboten C functions are being used. + if Search(r'\bsprintf\b', line): + error(filename, linenum, 'runtime/printf', 5, + 'Never use sprintf. Use snprintf instead.') + match = Search(r'\b(strcpy|strcat)\b', line) + if match: + error(filename, linenum, 'runtime/printf', 4, + 'Almost always, snprintf is better than %s' % match.group(1)) + + #if Search(r'\bsscanf\b', line): + # error(filename, linenum, 'runtime/printf', 1, + # 'sscanf can be ok, but is slow and can overflow buffers.') + + # Check if some verboten operator overloading is going on + # TODO(unknown): catch out-of-line unary operator&: + # class X {}; + # int operator&(const X& x) { return 42; } // unary operator& + # The trick is it's hard to tell apart from binary operator&: + # class Y { int operator&(const Y& x) { return 23; } }; // binary operator& + if Search(r'\boperator\s*&\s*\(\s*\)', line): + error(filename, linenum, 'runtime/operator', 4, + 'Unary operator& is dangerous. Do not use it.') + + # Check for suspicious usage of "if" like + # } if (a == b) { + if Search(r'\}\s*if\s*\(', line): + error(filename, linenum, 'readability/braces', 4, + 'Did you mean "else if"? If not, start a new line for "if".') + + # Check for potential format string bugs like printf(foo). + # We constrain the pattern not to pick things like DocidForPrintf(foo). + # Not perfect but it can catch printf(foo.c_str()) and printf(foo->c_str()) + # TODO(sugawarayu): Catch the following case. Need to change the calling + # convention of the whole function to process multiple line to handle it. + # printf( + # boy_this_is_a_really_long_variable_that_cannot_fit_on_the_prev_line); + printf_args = _GetTextInside(line, r'(?i)\b(string)?printf\s*\(') + if printf_args: + match = Match(r'([\w.\->()]+)$', printf_args) + if match: + function_name = re.search(r'\b((?:string)?printf)\s*\(', + line, re.I).group(1) + error(filename, linenum, 'runtime/printf', 4, + 'Potential format string bug. Do %s("%%s", %s) instead.' + % (function_name, match.group(1))) + + # Check for potential memset bugs like memset(buf, sizeof(buf), 0). + match = Search(r'memset\s*\(([^,]*),\s*([^,]*),\s*0\s*\)', line) + if match and not Match(r"^''|-?[0-9]+|0x[0-9A-Fa-f]$", match.group(2)): + error(filename, linenum, 'runtime/memset', 4, + 'Did you mean "memset(%s, 0, %s)"?' + % (match.group(1), match.group(2))) + + #if Search(r'\busing namespace\b', line): + # error(filename, linenum, 'build/namespaces', 5, + # 'Do not use namespace using-directives. ' + # 'Use using-declarations instead.') + + # Detect variable-length arrays. + match = Match(r'\s*(.+::)?(\w+) [a-z]\w*\[(.+)];', line) + if (match and match.group(2) != 'return' and match.group(2) != 'delete' and + match.group(3).find(']') == -1): + # Split the size using space and arithmetic operators as delimiters. + # If any of the resulting tokens are not compile time constants then + # report the error. + tokens = re.split(r'\s|\+|\-|\*|\/|<<|>>]', match.group(3)) + is_const = True + skip_next = False + for tok in tokens: + if skip_next: + skip_next = False + continue + + if Search(r'sizeof\(.+\)', tok): continue + if Search(r'arraysize\(\w+\)', tok): continue + + tok = tok.lstrip('(') + tok = tok.rstrip(')') + if not tok: continue + if Match(r'\d+', tok): continue + if Match(r'0[xX][0-9a-fA-F]+', tok): continue + if Match(r'k[A-Z0-9]\w*', tok): continue + if Match(r'(.+::)?k[A-Z0-9]\w*', tok): continue + if Match(r'(.+::)?[A-Z][A-Z0-9_]*', tok): continue + # A catch all for tricky sizeof cases, including 'sizeof expression', + # 'sizeof(*type)', 'sizeof(const type)', 'sizeof(struct StructName)' + # requires skipping the next token because we split on ' ' and '*'. + if tok.startswith('sizeof'): + skip_next = True + continue + is_const = False + break + if not is_const: + error(filename, linenum, 'runtime/arrays', 1, + 'Do not use variable-length arrays. Use an appropriately named ' + "('k' followed by CamelCase) compile-time constant for the size.") + + # If DISALLOW_EVIL_CONSTRUCTORS, DISALLOW_COPY_AND_ASSIGN, or + # DISALLOW_IMPLICIT_CONSTRUCTORS is present, then it should be the last thing + # in the class declaration. + match = Match( + (r'\s*' + r'(DISALLOW_(EVIL_CONSTRUCTORS|COPY_AND_ASSIGN|IMPLICIT_CONSTRUCTORS))' + r'\(.*\);$'), + line) + if match and linenum + 1 < clean_lines.NumLines(): + next_line = clean_lines.elided[linenum + 1] + # We allow some, but not all, declarations of variables to be present + # in the statement that defines the class. The [\w\*,\s]* fragment of + # the regular expression below allows users to declare instances of + # the class or pointers to instances, but not less common types such + # as function pointers or arrays. It's a tradeoff between allowing + # reasonable code and avoiding trying to parse more C++ using regexps. + if not Search(r'^\s*}[\w\*,\s]*;', next_line): + error(filename, linenum, 'readability/constructors', 3, + match.group(1) + ' should be the last thing in the class') + + # Check for use of unnamed namespaces in header files. Registration + # macros are typically OK, so we allow use of "namespace {" on lines + # that end with backslashes. + if (file_extension == 'h' + and Search(r'\bnamespace\s*{', line) + and line[-1] != '\\'): + error(filename, linenum, 'build/namespaces', 4, + 'Do not use unnamed namespaces in header files. See ' + 'http://google-styleguide.googlecode.com/svn/trunk/cppguide.xml#Namespaces' + ' for more information.') + + +def CheckCStyleCast(filename, linenum, line, raw_line, cast_type, pattern, + error): + """Checks for a C-style cast by looking for the pattern. + + This also handles sizeof(type) warnings, due to similarity of content. + + Args: + filename: The name of the current file. + linenum: The number of the line to check. + line: The line of code to check. + raw_line: The raw line of code to check, with comments. + cast_type: The string for the C++ cast to recommend. This is either + reinterpret_cast, static_cast, or const_cast, depending. + pattern: The regular expression used to find C-style casts. + error: The function to call with any errors found. + + Returns: + True if an error was emitted. + False otherwise. + """ + match = Search(pattern, line) + if not match: + return False + + # e.g., sizeof(int) + sizeof_match = Match(r'.*sizeof\s*$', line[0:match.start(1) - 1]) + if sizeof_match: + error(filename, linenum, 'runtime/sizeof', 1, + 'Using sizeof(type). Use sizeof(varname) instead if possible') + return True + + typeid_match = Match(r'.*typeid\s*$',line[0:match.start(1) - 1]) + if typeid_match: + return True + + remainder = line[match.end(0):] + + # The close paren is for function pointers as arguments to a function. + # eg, void foo(void (*bar)(int)); + # The semicolon check is a more basic function check; also possibly a + # function pointer typedef. + # eg, void foo(int); or void foo(int) const; + # The equals check is for function pointer assignment. + # eg, void *(*foo)(int) = ... + # The > is for MockCallback<...> ... + # + # Right now, this will only catch cases where there's a single argument, and + # it's unnamed. It should probably be expanded to check for multiple + # arguments with some unnamed. + function_match = Match(r'\s*(\)|=|(const)?\s*(;|\{|throw\(\)|>))', remainder) + #print "Remainder[%s]" % remainder + if function_match: + if ('SIGNAL' not in raw_line and 'SLOT' not in raw_line and + (not function_match.group(3) or + function_match.group(3) == ';' or + ('<' not in raw_line and + '/*' not in raw_line))): + error(filename, linenum, 'readability/function', 3, + 'All parameters should be named in a function') + return True + + # At this point, all that should be left is actual casts. + if len(remainder) > 0 and 'public: ' not in raw_line and 'private:' not in raw_line and 'protected: ' not in raw_line and remainder != ' const' and '::' not in raw_line: + error(filename, linenum, 'readability/casting', 4, + 'Using C-style cast. Use %s<%s>(...) instead' % + (cast_type, match.group(1))) + + return True + + +_HEADERS_CONTAINING_TEMPLATES = ( + ('', ('deque',)), + ('', ('unary_function', 'binary_function', + 'plus', 'minus', 'multiplies', 'divides', 'modulus', + 'negate', + 'equal_to', 'not_equal_to', 'greater', 'less', + 'greater_equal', 'less_equal', + 'logical_and', 'logical_or', 'logical_not', + 'unary_negate', 'not1', 'binary_negate', 'not2', + 'bind1st', 'bind2nd', + 'pointer_to_unary_function', + 'pointer_to_binary_function', + 'ptr_fun', + 'mem_fun_t', 'mem_fun', 'mem_fun1_t', 'mem_fun1_ref_t', + 'mem_fun_ref_t', + 'const_mem_fun_t', 'const_mem_fun1_t', + 'const_mem_fun_ref_t', 'const_mem_fun1_ref_t', + 'mem_fun_ref', + )), + ('', ('numeric_limits',)), + ('', ('list',)), + ('', ('map', 'multimap',)), + ('', ('allocator',)), + ('', ('queue', 'priority_queue',)), + ('', ('set', 'multiset',)), + ('', ('stack',)), + ('', ('char_traits', 'basic_string',)), + ('', ('pair',)), + ('', ('vector',)), + + # gcc extensions. + # Note: std::hash is their hash, ::hash is our hash + ('', ('hash_map', 'hash_multimap',)), + ('', ('hash_set', 'hash_multiset',)), + ('', ('slist',)), + ) + +_RE_PATTERN_STRING = re.compile(r'\bstring\b') + +_re_pattern_algorithm_header = [] +for _template in ('copy', 'max', 'min', 'min_element', 'sort', 'swap', + 'transform'): + # Match max(..., ...), max(..., ...), but not foo->max, foo.max or + # type::max(). + _re_pattern_algorithm_header.append( + (re.compile(r'[^>.]\b' + _template + r'(<.*?>)?\([^\)]'), + _template, + '')) + +_re_pattern_templates = [] +for _header, _templates in _HEADERS_CONTAINING_TEMPLATES: + for _template in _templates: + _re_pattern_templates.append( + (re.compile(r'(\<|\b)' + _template + r'\s*\<'), + _template + '<>', + _header)) + + +def FilesBelongToSameModule(filename_cc, filename_h): + """Check if these two filenames belong to the same module. + + The concept of a 'module' here is a as follows: + foo.h, foo-inl.h, foo.cc, foo_test.cc and foo_unittest.cc belong to the + same 'module' if they are in the same directory. + some/path/public/xyzzy and some/path/internal/xyzzy are also considered + to belong to the same module here. + + If the filename_cc contains a longer path than the filename_h, for example, + '/absolute/path/to/base/sysinfo.cc', and this file would include + 'base/sysinfo.h', this function also produces the prefix needed to open the + header. This is used by the caller of this function to more robustly open the + header file. We don't have access to the real include paths in this context, + so we need this guesswork here. + + Known bugs: tools/base/bar.cc and base/bar.h belong to the same module + according to this implementation. Because of this, this function gives + some false positives. This should be sufficiently rare in practice. + + Args: + filename_cc: is the path for the .cc file + filename_h: is the path for the header path + + Returns: + Tuple with a bool and a string: + bool: True if filename_cc and filename_h belong to the same module. + string: the additional prefix needed to open the header file. + """ + + if not filename_cc.endswith('.cc'): + return (False, '') + filename_cc = filename_cc[:-len('.cc')] + if filename_cc.endswith('_unittest'): + filename_cc = filename_cc[:-len('_unittest')] + elif filename_cc.endswith('_test'): + filename_cc = filename_cc[:-len('_test')] + filename_cc = filename_cc.replace('/public/', '/') + filename_cc = filename_cc.replace('/internal/', '/') + + if not filename_h.endswith('.h'): + return (False, '') + filename_h = filename_h[:-len('.h')] + if filename_h.endswith('-inl'): + filename_h = filename_h[:-len('-inl')] + filename_h = filename_h.replace('/public/', '/') + filename_h = filename_h.replace('/internal/', '/') + + files_belong_to_same_module = filename_cc.endswith(filename_h) + common_path = '' + if files_belong_to_same_module: + common_path = filename_cc[:-len(filename_h)] + return files_belong_to_same_module, common_path + + +def UpdateIncludeState(filename, include_state, io=codecs): + """Fill up the include_state with new includes found from the file. + + Args: + filename: the name of the header to read. + include_state: an _IncludeState instance in which the headers are inserted. + io: The io factory to use to read the file. Provided for testability. + + Returns: + True if a header was succesfully added. False otherwise. + """ + headerfile = None + try: + headerfile = io.open(filename, 'r', 'utf8', 'replace') + except IOError: + return False + linenum = 0 + for line in headerfile: + linenum += 1 + clean_line = CleanseComments(line) + match = _RE_PATTERN_INCLUDE.search(clean_line) + if match: + include = match.group(2) + # The value formatting is cute, but not really used right now. + # What matters here is that the key is in include_state. + include_state.setdefault(include, '%s:%d' % (filename, linenum)) + return True + + +def CheckForIncludeWhatYouUse(filename, clean_lines, include_state, error, + io=codecs): + """Reports for missing stl includes. + + This function will output warnings to make sure you are including the headers + necessary for the stl containers and functions that you use. We only give one + reason to include a header. For example, if you use both equal_to<> and + less<> in a .h file, only one (the latter in the file) of these will be + reported as a reason to include the . + + Args: + filename: The name of the current file. + clean_lines: A CleansedLines instance containing the file. + include_state: An _IncludeState instance. + error: The function to call with any errors found. + io: The IO factory to use to read the header file. Provided for unittest + injection. + """ + required = {} # A map of header name to linenumber and the template entity. + # Example of required: { '': (1219, 'less<>') } + + for linenum in xrange(clean_lines.NumLines()): + line = clean_lines.elided[linenum] + if not line or line[0] == '#': + continue + + # String is special -- it is a non-templatized type in STL. + matched = _RE_PATTERN_STRING.search(line) + if matched: + # Don't warn about strings in non-STL namespaces: + # (We check only the first match per line; good enough.) + prefix = line[:matched.start()] + if prefix.endswith('std::') or not prefix.endswith('::'): + required[''] = (linenum, 'string') + + for pattern, template, header in _re_pattern_algorithm_header: + if pattern.search(line): + required[header] = (linenum, template) + + # The following function is just a speed up, no semantics are changed. + if not '<' in line: # Reduces the cpu time usage by skipping lines. + continue + + for pattern, template, header in _re_pattern_templates: + if pattern.search(line): + required[header] = (linenum, template) + + # The policy is that if you #include something in foo.h you don't need to + # include it again in foo.cc. Here, we will look at possible includes. + # Let's copy the include_state so it is only messed up within this function. + include_state = include_state.copy() + + # Did we find the header for this file (if any) and succesfully load it? + header_found = False + + # Use the absolute path so that matching works properly. + abs_filename = os.path.abspath(filename) + + # For Emacs's flymake. + # If cpplint is invoked from Emacs's flymake, a temporary file is generated + # by flymake and that file name might end with '_flymake.cc'. In that case, + # restore original file name here so that the corresponding header file can be + # found. + # e.g. If the file name is 'foo_flymake.cc', we should search for 'foo.h' + # instead of 'foo_flymake.h' + abs_filename = re.sub(r'_flymake\.cc$', '.cc', abs_filename) + + # include_state is modified during iteration, so we iterate over a copy of + # the keys. + header_keys = include_state.keys() + for header in header_keys: + (same_module, common_path) = FilesBelongToSameModule(abs_filename, header) + fullpath = common_path + header + if same_module and UpdateIncludeState(fullpath, include_state, io): + header_found = True + + # If we can't find the header file for a .cc, assume it's because we don't + # know where to look. In that case we'll give up as we're not sure they + # didn't include it in the .h file. + # TODO(unknown): Do a better job of finding .h files so we are confident that + # not having the .h file means there isn't one. + if filename.endswith('.cc') and not header_found: + return + + # All the lines have been processed, report the errors found. + for required_header_unstripped in required: + template = required[required_header_unstripped][1] + if required_header_unstripped.strip('<>"') not in include_state: + error(filename, required[required_header_unstripped][0], + 'build/include_what_you_use', 4, + 'Add #include ' + required_header_unstripped + ' for ' + template) + + +_RE_PATTERN_EXPLICIT_MAKEPAIR = re.compile(r'\bmake_pair\s*<') + + +def CheckMakePairUsesDeduction(filename, clean_lines, linenum, error): + """Check that make_pair's template arguments are deduced. + + G++ 4.6 in C++0x mode fails badly if make_pair's template arguments are + specified explicitly, and such use isn't intended in any case. + + Args: + filename: The name of the current file. + clean_lines: A CleansedLines instance containing the file. + linenum: The number of the line to check. + error: The function to call with any errors found. + """ + raw = clean_lines.raw_lines + line = raw[linenum] + match = _RE_PATTERN_EXPLICIT_MAKEPAIR.search(line) + if match: + error(filename, linenum, 'build/explicit_make_pair', + 4, # 4 = high confidence + 'Omit template arguments from make_pair OR use pair directly OR' + ' if appropriate, construct a pair directly') + + +def ProcessLine(filename, file_extension, + clean_lines, line, include_state, function_state, + class_state, error, extra_check_functions=[]): + """Processes a single line in the file. + + Args: + filename: Filename of the file that is being processed. + file_extension: The extension (dot not included) of the file. + clean_lines: An array of strings, each representing a line of the file, + with comments stripped. + line: Number of line being processed. + include_state: An _IncludeState instance in which the headers are inserted. + function_state: A _FunctionState instance which counts function lines, etc. + class_state: A _ClassState instance which maintains information about + the current stack of nested class declarations being parsed. + error: A callable to which errors are reported, which takes 4 arguments: + filename, line number, error level, and message + extra_check_functions: An array of additional check functions that will be + run on each source line. Each function takes 4 + arguments: filename, clean_lines, line, error + """ + raw_lines = clean_lines.raw_lines + ParseNolintSuppressions(filename, raw_lines[line], line, error) + CheckForFunctionLengths(filename, clean_lines, line, function_state, error) + CheckForMultilineCommentsAndStrings(filename, clean_lines, line, error) + CheckStyle(filename, clean_lines, line, file_extension, class_state, error) + CheckLanguage(filename, clean_lines, line, file_extension, include_state, + error) + CheckForNonStandardConstructs(filename, clean_lines, line, + class_state, error) + CheckPosixThreading(filename, clean_lines, line, error) + CheckInvalidIncrement(filename, clean_lines, line, error) + CheckMakePairUsesDeduction(filename, clean_lines, line, error) + for check_fn in extra_check_functions: + check_fn(filename, clean_lines, line, error) + +def ProcessFileData(filename, file_extension, lines, error, + extra_check_functions=[]): + """Performs lint checks and reports any errors to the given error function. + + Args: + filename: Filename of the file that is being processed. + file_extension: The extension (dot not included) of the file. + lines: An array of strings, each representing a line of the file, with the + last element being empty if the file is terminated with a newline. + error: A callable to which errors are reported, which takes 4 arguments: + filename, line number, error level, and message + extra_check_functions: An array of additional check functions that will be + run on each source line. Each function takes 4 + arguments: filename, clean_lines, line, error + """ + lines = (['// marker so line numbers and indices both start at 1'] + lines + + ['// marker so line numbers end in a known way']) + + include_state = _IncludeState() + function_state = _FunctionState() + class_state = _ClassState() + + ResetNolintSuppressions() + + CheckForCopyright(filename, lines, error) + + if file_extension == 'h': + CheckForHeaderGuard(filename, lines, error) + + RemoveMultiLineComments(filename, lines, error) + clean_lines = CleansedLines(lines) + for line in xrange(clean_lines.NumLines()): + ProcessLine(filename, file_extension, clean_lines, line, + include_state, function_state, class_state, error, + extra_check_functions) + class_state.CheckFinished(filename, error) + + CheckForIncludeWhatYouUse(filename, clean_lines, include_state, error) + + # We check here rather than inside ProcessLine so that we see raw + # lines rather than "cleaned" lines. + CheckForUnicodeReplacementCharacters(filename, lines, error) + + CheckForNewlineAtEOF(filename, lines, error) + +def ProcessFile(filename, vlevel, extra_check_functions=[]): + """Does google-lint on a single file. + + Args: + filename: The name of the file to parse. + + vlevel: The level of errors to report. Every error of confidence + >= verbose_level will be reported. 0 is a good default. + + extra_check_functions: An array of additional check functions that will be + run on each source line. Each function takes 4 + arguments: filename, clean_lines, line, error + """ + + _SetVerboseLevel(vlevel) + + try: + # Support the UNIX convention of using "-" for stdin. Note that + # we are not opening the file with universal newline support + # (which codecs doesn't support anyway), so the resulting lines do + # contain trailing '\r' characters if we are reading a file that + # has CRLF endings. + # If after the split a trailing '\r' is present, it is removed + # below. If it is not expected to be present (i.e. os.linesep != + # '\r\n' as in Windows), a warning is issued below if this file + # is processed. + + if filename == '-': + lines = codecs.StreamReaderWriter(sys.stdin, + codecs.getreader('utf8'), + codecs.getwriter('utf8'), + 'replace').read().split('\n') + else: + lines = codecs.open(filename, 'r', 'utf8', 'replace').read().split('\n') + + carriage_return_found = False + # Remove trailing '\r'. + for linenum in range(len(lines)): + if lines[linenum].endswith('\r'): + lines[linenum] = lines[linenum].rstrip('\r') + carriage_return_found = True + + except IOError: + #sys.stderr.write( + # "Skipping input '%s': Can't open for reading\n" % filename) + return + + # Note, if no dot is found, this will give the entire filename as the ext. + file_extension = filename[filename.rfind('.') + 1:] + + # When reading from stdin, the extension is unknown, so no cpplint tests + # should rely on the extension. + if (filename != '-' and file_extension != 'cc' and file_extension != 'h' + and file_extension != 'cpp' and file_extension != 'hh'): + if (filename != "CMakeLists.txt" and file_extension != "in" + and file_extension != "proto" and file_extension != "sdf"): + pass + #sys.stderr.write('Ignoring %s; not a .cc or .h file\n' % filename) + else: + ProcessFileData(filename, file_extension, lines, Error, + extra_check_functions) + if carriage_return_found and os.linesep != '\r\n': + # Use 0 for linenum since outputting only one error for potentially + # several lines. + Error(filename, 0, 'whitespace/newline', 1, + 'One or more unexpected \\r (^M) found;' + 'better to use only a \\n') + + #sys.stderr.write('Done processing %s\n' % filename) + + +def PrintUsage(message): + """Prints a brief usage string and exits, optionally with an error message. + + Args: + message: The optional error message. + """ + sys.stderr.write(_USAGE) + if message: + sys.exit('\nFATAL ERROR: ' + message) + else: + sys.exit(1) + + +def PrintCategories(): + """Prints a list of all the error-categories used by error messages. + + These are the categories used to filter messages via --filter. + """ + sys.stderr.write(''.join(' %s\n' % cat for cat in _ERROR_CATEGORIES)) + sys.exit(0) + + +def ParseArguments(args): + """Parses the command line arguments. + + This may set the output format and verbosity level as side-effects. + + Args: + args: The command line arguments: + + Returns: + The list of filenames to lint. + """ + try: + (opts, filenames) = getopt.getopt(args, '', ['help', 'output=', 'verbose=', + 'counting=', + 'filter=']) + except getopt.GetoptError: + PrintUsage('Invalid arguments.') + + verbosity = _VerboseLevel() + output_format = _OutputFormat() + filters = '' + counting_style = '' + + for (opt, val) in opts: + if opt == '--help': + PrintUsage(None) + elif opt == '--output': + if not val in ('emacs', 'vs7'): + PrintUsage('The only allowed output formats are emacs and vs7.') + output_format = val + elif opt == '--verbose': + verbosity = int(val) + elif opt == '--filter': + filters = val + if not filters: + PrintCategories() + elif opt == '--counting': + if val not in ('total', 'toplevel', 'detailed'): + PrintUsage('Valid counting options are total, toplevel, and detailed') + counting_style = val + + if not filenames: + PrintUsage('No files were specified.') + + _SetOutputFormat(output_format) + _SetVerboseLevel(verbosity) + _SetFilters(filters) + _SetCountingStyle(counting_style) + + return filenames + + +def main(): + filenames = ParseArguments(sys.argv[1:]) + + # Change stderr to write with replacement characters so we don't die + # if we try to print something containing non-ASCII characters. + sys.stderr = codecs.StreamReaderWriter(sys.stderr, + codecs.getreader('utf8'), + codecs.getwriter('utf8'), + 'replace') + + _cpplint_state.ResetErrorCounts() + for filename in filenames: + if filename != "./gazebo/rendering/cegui.h": + ProcessFile(filename, _cpplint_state.verbose_level) + _cpplint_state.PrintErrorCounts() + + sys.exit(_cpplint_state.error_count > 0) + + +if __name__ == '__main__': + main() diff --git a/sdformat/tools/cpplint_to_cppcheckxml.py b/sdformat/tools/cpplint_to_cppcheckxml.py new file mode 100644 index 0000000..7e9eee1 --- /dev/null +++ b/sdformat/tools/cpplint_to_cppcheckxml.py @@ -0,0 +1,54 @@ +#!/usr/bin/env python + +# Convert output from Google's cpplint.py to the cppcheck XML format for +# consumption by the Jenkins cppcheck plugin. + +# Reads from stdin and writes to stderr (to mimic cppcheck) + + +import sys +import re +import xml.sax.saxutils + +def cpplint_score_to_cppcheck_severity(score): + # I'm making this up + if score == 1: + return 'style' + elif score == 2: + return 'style' + elif score == 3: + return 'warning' + elif score == 4: + return 'warning' + elif score == 5: + return 'error' + + +def parse(): + # TODO: do this properly, using the xml module. + # Write header + sys.stderr.write('''\n''') + sys.stderr.write('''\n''') + + # Do line-by-line conversion + r = re.compile('([^:]*):([0-9]*): ([^\[]*)\[([^\]]*)\] \[([0-9]*)\].*') + + for l in sys.stdin.readlines(): + m = r.match(l.strip()) + if not m: + continue + g = m.groups() + if len(g) != 5: + continue + fname, lineno, rawmsg, label, score = g + # Protect Jenkins from bad XML, which makes it barf + msg = xml.sax.saxutils.escape(rawmsg) + severity = cpplint_score_to_cppcheck_severity(int(score)) + sys.stderr.write('''\n'''%(fname, lineno, label, severity, msg)) + + # Write footer + sys.stderr.write('''\n''') + + +if __name__ == '__main__': + parse() diff --git a/sdformat/tools/get_mem_info.py b/sdformat/tools/get_mem_info.py new file mode 100644 index 0000000..32a1b06 --- /dev/null +++ b/sdformat/tools/get_mem_info.py @@ -0,0 +1,12 @@ +#!/usr/bin/env python + +import os; +import psutil; +# get pid of parent process +pid = os.getppid(); +# get and print memory usage of parent process +p = psutil.Process(pid); +# note that different versions of psutil have different API +# some versions have memory_info(), others have get_memory_info() +memory_info = (p.memory_info() if hasattr(p, 'memory_info') else p.get_memory_info()); +print (memory_info[0]) diff --git a/sdformat/tools/xmlschema.rb b/sdformat/tools/xmlschema.rb new file mode 100755 index 0000000..af07443 --- /dev/null +++ b/sdformat/tools/xmlschema.rb @@ -0,0 +1,302 @@ +#!/usr/bin/env ruby + +require "rexml/document" +require "optparse" + +$path = nil + +################################################# +# \brief A not very elegant way to convert to schema types +def xsdType(_type) + if _type == "unsigned int" + return "unsignedInt" + elsif _type == "unsigned long" + return "unsignedLog" + elsif _type == "bool" + return "boolean" + else + return _type + end +end + +################################################# +def isStdType(_type) + return _type == "string" || _type == "int" || _type == "double" || + _type == "float" || _type == "bool" || _type == "char" || + _type == "unsigned int" +end + +################################################# +def printElem(_file, _spaces, _elem) + + # this currently short-circuits the plugin.sdf copy_data element. + if _elem.attributes["name"].nil? + _file.printf("%*s\n", _spaces-2, "") + _file.printf("%*s\n", _spaces, "") + _file.printf("%*s\n", _spaces-2, "") + return + end + + type = _elem.attributes["type"] + if isStdType(type) + type = "xsd:" + xsdType(type) + end + + minOccurs = '0' + maxOccurs = 'unbounded' + if _elem.attributes["required"] == '0' + minOccurs='0' + maxOccurs='1' + elsif _elem.attributes["required"] == '1' + minOccurs='1' + maxOccurs='1' + elsif _elem.attributes["required"] == '+' + minOccurs='1' + maxOccurs='unbounded' + elsif _elem.attributes["required"] == '*' + minOccurs='0' + maxOccurs='unbounded' + end + + _file.printf("%*s\n", + _spaces, "", minOccurs, maxOccurs) + + # Print the complex type with a name + if type.nil? || type == "" + + _file.printf("%*s\n", + _spaces, "", _elem.attributes["name"]) + + if !_elem.elements["description"].nil? && + !_elem.elements["description"].text.nil? + printDocumentation(_file, _spaces+2, _elem.elements["description"].text) + end + + _file.printf("%*s\n", _spaces+2, "") + + _file.printf("%*s\n", _spaces+4, "") + + _elem.get_elements("element").each do |elem| + printElem(_file, _spaces+6, elem) + end + _file.printf("%*s\n", _spaces+4, "") + + # Print the attributes for the complex type + # Attributes must go at the end of the complex type. + _elem.get_elements("attribute").each do |attr| + printAttribute(_file, _spaces+4, attr); + end + + _file.printf("%*s\n", _spaces+2, "") + else + _file.printf("%*s\n", + _spaces, "", _elem.attributes["name"], type) + + if !_elem.elements["description"].nil? && + !_elem.elements["description"].text.nil? + printDocumentation(_file, _spaces+2, _elem.elements["description"].text) + end + end + + _file.printf("%*s\n", _spaces, "") + _file.printf("%*s\n", _spaces, "") + +end + +################################################# +def printDocumentation(_file, _spaces, _doc) + _file.printf("%*s\n", _spaces, "") + + _spaces += 2 + _file.printf("%*s\n", _spaces, "") + + _spaces += 2 + _file.printf("%*s\n",_spaces, "", _doc); + _spaces -= 2 + + _file.printf("%*s\n", _spaces, "") + _spaces -= 2 + + _file.printf("%*s\n", _spaces, "") +end + +################################################# +def printIncludeRef(_file, _spaces, _inc) + path = File.join($path, _inc.attributes["filename"]) + doc = REXML::Document.new File.new(path) + incElemName = doc.root.attributes['name'] + _file.printf("%*s\n", _spaces, "", incElemName) +end + +################################################# +def printInclude(_file, _spaces, _attr) + loc = "http://sdformat.org/schemas/" + loc += _attr.attributes['filename'].sub("\.sdf","\.xsd") + _file.printf("%*s\n", _spaces, "", loc) +end + +################################################# +def printAttribute(_file, _spaces, _attr) + name = _attr.attributes["name"] + type = _attr.attributes["type"] + use = "" + default = "" + + if !_attr.attributes["required"].nil? + if _attr.attributes["required"] == "1" + use = "use='required'" + elsif _attr.attributes["required"] == "0" + use = "use='optional'" + + # Default is only valid if use is optional + if !_attr.attributes["default"].nil? + default="default='#{_attr.attributes["default"]}'" + end + end + end + + if isStdType(type) + type = "xsd:" + xsdType(type) + end + + _file.printf("%*s\n", _spaces, + "", name, type, use, default) + + if !_attr.elements["description"].nil? && + !_attr.elements["description"].text.nil? + printDocumentation(_file, _spaces+2, _attr.elements["description"].text) + end + _file.printf("%*s\n", _spaces, "") +end + +################################################# +# \brief Print the complete schema for an element into a file. +# \param[in] _file File pointer in which to print the schema. +# \param[in] _spaces Number of spaces to prepend to each line. +# \param[in] _elem The SDF element to convert to an xml schema. +def printXSD(_file, _spaces, _elem) + + if !_elem.elements["description"].nil? && + !_elem.elements["description"].text.nil? + printDocumentation(_file, _spaces, _elem.elements["description"].text) + end + + _file.printf("%*s\n", _spaces, "") + + # Print the inclues for the complex type + # The includes must appear first + _elem.get_elements("include").each do |inc| + printInclude(_file, _spaces, inc); + end + + if _elem.get_elements("element").size > 0 || + _elem.get_elements("attribute").size > 0 || + _elem.get_elements("include").size > 0 + + # Print the complex type with a name + _file.printf("%*s\n", _spaces, "", + _elem.attributes["name"]) + _file.printf("%*s\n", _spaces+2, "") + + if _elem.attributes['name'] != "plugin" && + (_elem.get_elements("element").size > 0 || + _elem.get_elements("include").size > 0) + _file.printf("%*s\n", _spaces+4, "") + end + + # Print all the child elements + _elem.get_elements("element").each do |elem| + printElem(_file, _spaces+6, elem); + end + + # Print all the included sdf's root elements + _elem.get_elements("include").each do |inc| + printIncludeRef(_file, _spaces+6, inc); + end + if _elem.attributes['name'] != "plugin" && + (_elem.get_elements("element").size > 0 || + _elem.get_elements("include").size > 0) + _file.printf("%*s\n", _spaces+4, "") + end + + # Print the attributes for the complex type + # Attributes must go at the end of the complex type. + _elem.get_elements("attribute").each do |attr| + printAttribute(_file, _spaces+4, attr); + end + + # Close the complex type + _file.printf("%*s\n", _spaces+2, "") + _file.printf("%*s\n", _spaces, "") + else + type = _elem.attributes["type"] + + if isStdType(type) + type = "xsd:" + type + end + + if !type.nil? + type = "type='" + type + "'" + end + + _file.printf("%*s\n", _spaces, "", + _elem.attributes["name"], type) + end +end + + +infile = nil +outdir = nil + +opt_parser = OptionParser.new do |o| + o.on("-i", "--in [path]", String, + "SDF file to compile") {|path| infile = path} + o.on("-o", "--out [path]", String, + "Output directory for source and header files") {|path| outdir = path} + o.on("-s", "--sdf [path]", String, + "Directory containing all the SDF files") {|path| $path = path} + o.on("-h", "--help", "Display this help message") do + puts opt_parser + exit + end +end +opt_parser.parse! + +if infile.nil? + puts "Missing option -i." + exit +elsif !File.exists?(infile) + puts "Input file[#{infile}] does not exist\n" + exit +end + +if $path.nil? + puts "Missing option -s." + exit +elsif !Dir.exists?($path) + puts "SDF source dir[#{$path}] does not exist\n" + exit +end + +if outdir.nil? + puts "Missing output directory, option -o." + exit +elsif !Dir.exists?(outdir) + Dir.mkdir(outdir) +end + +doc = REXML::Document.new File.new(infile) + +spaces = 2 +doc.elements.each_with_index("element") do |elem, i| + out_xsd = infile.split("/").last.sub("\.sdf","\.xsd") + file = File.open(File.join(outdir, out_xsd), "w") + + file.print("\n") + file.print("\n") + + printXSD(file, spaces, elem) + + file.print("\n") + file.close() +end